From 558ccb393d571addf62e991cfabbe5c13086c920 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 12 Apr 2021 10:04:15 +0200 Subject: [PATCH 001/102] Update to total length of average and variance windows --- src/main/flight/kalman.c | 2 +- src/main/flight/kalman.h | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/flight/kalman.c b/src/main/flight/kalman.c index 99b0a00b2b..7049f66991 100755 --- a/src/main/flight/kalman.c +++ b/src/main/flight/kalman.c @@ -92,7 +92,7 @@ static void updateAxisVariance(kalman_t *kalmanState, float rate) kalmanState->varianceWindow[kalmanState->windex] = varianceElement; kalmanState->windex++; - if (kalmanState->windex >= kalmanState->w) { + if (kalmanState->windex > kalmanState->w) { kalmanState->windex = 0; } diff --git a/src/main/flight/kalman.h b/src/main/flight/kalman.h index 17b714b8ff..295caef96f 100755 --- a/src/main/flight/kalman.h +++ b/src/main/flight/kalman.h @@ -40,8 +40,8 @@ typedef struct kalman float axisVar; uint16_t windex; - float axisWindow[MAX_KALMAN_WINDOW_SIZE]; - float varianceWindow[MAX_KALMAN_WINDOW_SIZE]; + float axisWindow[MAX_KALMAN_WINDOW_SIZE + 1]; + float varianceWindow[MAX_KALMAN_WINDOW_SIZE + 1]; float axisSumMean; float axisMean; float axisSumVar; From 2800d11392d13a774a1a21822601f7b9031408d0 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sat, 15 May 2021 08:54:01 +0200 Subject: [PATCH 002/102] Version bump to 3.1 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 400e890b7f..9e7de58298 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -37,7 +37,7 @@ else() include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}-checks.cmake") endif() -project(INAV VERSION 3.0.0) +project(INAV VERSION 3.1.0) enable_language(ASM) From c8cc15dfa4b944698c0f6646ce2ed34fe9525391 Mon Sep 17 00:00:00 2001 From: tednv Date: Sat, 15 May 2021 00:18:18 -0700 Subject: [PATCH 003/102] adding documentation for Windows MSYS2 build environment --- .../Building in Windows 10 with MSYS2.md | 66 +++++++++++++++++++ 1 file changed, 66 insertions(+) create mode 100644 docs/development/Building in Windows 10 with MSYS2.md diff --git a/docs/development/Building in Windows 10 with MSYS2.md b/docs/development/Building in Windows 10 with MSYS2.md new file mode 100644 index 0000000000..134e9c1379 --- /dev/null +++ b/docs/development/Building in Windows 10 with MSYS2.md @@ -0,0 +1,66 @@ +# General Info + +This is a guide on how to use Windows MSYS2 distribution and building platform to build iNav firmware. This environment is very simple to manage and does not require installing docker for Windows which may get in the way of VMWare or any other virtualization software you already have running for other reasons. Another benefit of this approach is that the compiler runs natively on Windows, so performance is much better than compiling in a virtual environment or a container. You can also integrate with whatever IDE you are using to make code edits and work with github, which makes the entire development and testing workflow a lot more efficient. In addition to MSYS2, this build environment also uses Arm Embedded GCC tolkit from The xPack Project, which provides many benefits over the toolkits maintained by arm.com + +Some of those benefits are described here: +https://xpack.github.io/arm-none-eabi-gcc/ + +## Setting up build environment + +Download MSYS2 for your architecture (most likely 64-bit) +https://www.msys2.org/wiki/MSYS2-installation/ + +Click on 64-bit, scroll all the way down for the latest release + +pacman is the package manager which makes it a lot easier to install and maintain all the dependencies + +## Installing dependencies + +Once MSYS2 is installed, you can open up a new terminal window by running: + +"C:\msys64\mingw64.exe" + +You can also make a shortcut of this somewhere on your taskbar, desktop, etc, or even setup a shortcut key to open it up every time you need to get a terminal window. If you right click on the window you can customize the font and layout to make it more comfortable to work with. This is very similar to cygwin or any other terminal program you might have used before + +This is the best part: +` +pacman -S git ruby make cmake gcc mingw-w64-x86_64-libwinpthread-git unzip wget +` + +Now, each release needs a different version of arm toolchain. To setup the xPack ARM toolchain, use the following process: + +First, get the release you want to build or master if you want the latest/greatest +` +mkdir /c/Workspace +cd /c/Workspace +# you can also check out your own fork here which makes contributing easier +git clone https://github.com/iNavFlight/inav +cd inav +# switch to release you want or skip next 2 lines if you want latest +git fetch origin +git checkout -b release_2.6.1 origin/release_2.6.1 +mkdir build +cd build +mkdir /c/Workspace/xpack +cd /c/Workspace/xpack +# now find the arm toolchain version you need for this inav release +cat /c/Workspace/inav/cmake/arm-none-eabi-checks.cmake | grep "set(arm_none_eabi_gcc_version" | cut -d\" -f2 +# this will give you the version you need for any given release or master branch +# you can get to all the releases here and find the version you need +# https://github.com/xpack-dev-tools/arm-none-eabi-gcc-xpack/releases/ +# for version 2.6.1, version needed is 9.2.1 +wget https://github.com/xpack-dev-tools/arm-none-eabi-gcc-xpack/releases/download/v9.2.1-1.1/xpack-arm-none-eabi-gcc-9.2.1-1.1-win32-x64.zip +unzip xpack-arm-none-eabi-gcc-9.2.1-1.1-win32-x64.zip +# this is important, put the toolkit first before your path so that it is +# picked up ahead of any other versions that may be present on your system +export PATH=/c/Workspace/xpack/xpack-arm-none-eabi-gcc-9.2.1-1.1/bin:$PATH +cd /c/Workspace/inav/build +# you may need to run rm -rf * in build directory if you had any failed previous runs +# now run cmake .. while inside the build directory +cmake .. +# once that's done you can compile the firmware for your controller +make DALRCF405 +# the generated hex file will be in /c/Workspace/inav/build folder +` + +At the time of writting this document, I believe this is the fastest, easiest, and most efficient Windows build environment that is available. I have used this approach several years ago and was very happy with it building iNav 2.1 and 2.2, and now I'm getting back into it so figured I would share my method \ No newline at end of file From 9010fd14add31aa33f775d9c0a224d19916cf5d9 Mon Sep 17 00:00:00 2001 From: tednv Date: Sat, 15 May 2021 00:26:02 -0700 Subject: [PATCH 004/102] enabling DSHOT for DALRCF405 which pairs perfectly with DALRC engine --- src/main/target/DALRCF405/target.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/main/target/DALRCF405/target.h b/src/main/target/DALRCF405/target.h index 0b37dc2c11..c2787f71ef 100644 --- a/src/main/target/DALRCF405/target.h +++ b/src/main/target/DALRCF405/target.h @@ -151,3 +151,5 @@ //TIMER #define MAX_PWM_OUTPUT_PORTS 10 + +#define USE_DSHOT From 500c6ab92322b6a8c8d64235d61aba1dd35fa304 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 17 May 2021 11:47:37 +0200 Subject: [PATCH 005/102] Minor performance update --- src/main/common/maths.c | 13 ++++++++++--- src/main/common/maths.h | 1 + src/main/common/quaternion.h | 2 +- src/main/common/vector.h | 2 +- src/main/flight/imu.c | 10 +++++----- src/main/flight/mixer.c | 8 ++++---- src/main/flight/pid.c | 2 +- src/main/flight/servos.c | 2 +- src/main/flight/wind_estimator.c | 8 ++++---- src/main/io/gps_msp.c | 2 +- src/main/io/gps_naza.c | 2 +- src/main/io/osd.c | 2 +- src/main/io/osd_common.c | 2 +- src/main/navigation/navigation.c | 6 +++--- src/main/navigation/navigation_fixedwing.c | 4 ++-- src/main/navigation/navigation_multicopter.c | 6 +++--- src/main/navigation/navigation_pos_estimator.c | 4 ++-- src/main/navigation/navigation_pos_estimator_flow.c | 2 +- src/main/programming/logic_condition.c | 2 +- src/main/sensors/acceleration.c | 10 +++++----- src/main/sensors/opflow.c | 4 ++-- src/main/sensors/pitotmeter.c | 2 +- 22 files changed, 52 insertions(+), 44 deletions(-) diff --git a/src/main/common/maths.c b/src/main/common/maths.c index 26b3fe21ba..6c388ba717 100644 --- a/src/main/common/maths.c +++ b/src/main/common/maths.c @@ -19,6 +19,7 @@ #include #include +#include "arm_math.h" #include "axis.h" #include "maths.h" #include "vector.h" @@ -95,7 +96,7 @@ float atan2_approx(float y, float x) float acos_approx(float x) { float xa = fabsf(x); - float result = sqrtf(1.0f - xa) * (1.5707288f + xa * (-0.2121144f + xa * (0.0742610f + (-0.0187293f * xa)))); + float result = fast_fsqrtf(1.0f - xa) * (1.5707288f + xa * (-0.2121144f + xa * (0.0742610f + (-0.0187293f * xa)))); if (x < 0.0f) return M_PIf - result; else @@ -200,7 +201,7 @@ float devVariance(stdev_t *dev) float devStandardDeviation(stdev_t *dev) { - return sqrtf(devVariance(dev)); + return fast_fsqrtf(devVariance(dev)); } float degreesToRadians(int16_t degrees) @@ -508,7 +509,7 @@ bool sensorCalibrationSolveForScale(sensorCalibrationState_t * state, float resu sensorCalibration_SolveLGS(state->XtX, beta, state->XtY); for (int i = 0; i < 3; i++) { - result[i] = sqrtf(beta[i]); + result[i] = fast_fsqrtf(beta[i]); } return sensorCalibrationValidateResult(result); @@ -518,3 +519,9 @@ float bellCurve(const float x, const float curveWidth) { return powf(M_Ef, -sq(x) / (2.0f * sq(curveWidth))); } + +float fast_fsqrtf(const float value) { + float squirt; + arm_sqrt_f32(value, &squirt); + return squirt; +} \ No newline at end of file diff --git a/src/main/common/maths.h b/src/main/common/maths.h index 6f2d9b1245..581513f148 100644 --- a/src/main/common/maths.h +++ b/src/main/common/maths.h @@ -176,3 +176,4 @@ float acos_approx(float x); void arraySubInt32(int32_t *dest, int32_t *array1, int32_t *array2, int count); float bellCurve(const float x, const float curveWidth); +float fast_fsqrtf(const float value); diff --git a/src/main/common/quaternion.h b/src/main/common/quaternion.h index beaf566c55..6fbbfc7527 100644 --- a/src/main/common/quaternion.h +++ b/src/main/common/quaternion.h @@ -142,7 +142,7 @@ static inline fpQuaternion_t * quaternionConjugate(fpQuaternion_t * result, cons static inline fpQuaternion_t * quaternionNormalize(fpQuaternion_t * result, const fpQuaternion_t * q) { - float mod = sqrtf(quaternionNormSqared(q)); + float mod = fast_fsqrtf(quaternionNormSqared(q)); if (mod < 1e-6f) { // Length is too small - re-initialize to zero rotation result->q0 = 1; diff --git a/src/main/common/vector.h b/src/main/common/vector.h index 25d02ea3cb..449a0973b3 100644 --- a/src/main/common/vector.h +++ b/src/main/common/vector.h @@ -67,7 +67,7 @@ static inline float vectorNormSquared(const fpVector3_t * v) static inline fpVector3_t * vectorNormalize(fpVector3_t * result, const fpVector3_t * v) { - float length = sqrtf(vectorNormSquared(v)); + float length = fast_fsqrtf(vectorNormSquared(v)); if (length != 0) { result->x = v->x / length; result->y = v->y / length; diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index 3401e3b00c..dcbacf226b 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -241,7 +241,7 @@ static float imuGetPGainScaleFactor(void) static void imuResetOrientationQuaternion(const fpVector3_t * accBF) { - const float accNorm = sqrtf(vectorNormSquared(accBF)); + const float accNorm = fast_fsqrtf(vectorNormSquared(accBF)); orientation.q0 = accBF->z + accNorm; orientation.q1 = accBF->y; @@ -436,12 +436,12 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe // Proper quaternion from axis/angle involves computing sin/cos, but the formula becomes numerically unstable as Theta approaches zero. // For near-zero cases we use the first 3 terms of the Taylor series expansion for sin/cos. We check if fourth term is less than machine precision - // then we can safely use the "low angle" approximated version without loss of accuracy. - if (thetaMagnitudeSq < sqrtf(24.0f * 1e-6f)) { + if (thetaMagnitudeSq < fast_fsqrtf(24.0f * 1e-6f)) { quaternionScale(&deltaQ, &deltaQ, 1.0f - thetaMagnitudeSq / 6.0f); deltaQ.q0 = 1.0f - thetaMagnitudeSq / 2.0f; } else { - const float thetaMagnitude = sqrtf(thetaMagnitudeSq); + const float thetaMagnitude = fast_fsqrtf(thetaMagnitudeSq); quaternionScale(&deltaQ, &deltaQ, sin_approx(thetaMagnitude) / thetaMagnitude); deltaQ.q0 = cos_approx(thetaMagnitude); } @@ -483,7 +483,7 @@ static float imuCalculateAccelerometerWeight(const float dT) accMagnitudeSq += acc.accADCf[axis] * acc.accADCf[axis]; } - const float accWeight_Nearness = bellCurve(sqrtf(accMagnitudeSq) - 1.0f, MAX_ACC_NEARNESS); + const float accWeight_Nearness = bellCurve(fast_fsqrtf(accMagnitudeSq) - 1.0f, MAX_ACC_NEARNESS); // Experiment: if rotation rate on a FIXED_WING_LEGACY is higher than a threshold - centrifugal force messes up too much and we // should not use measured accel for AHRS comp @@ -504,7 +504,7 @@ static float imuCalculateAccelerometerWeight(const float dT) float accWeight_RateIgnore = 1.0f; if (ARMING_FLAG(ARMED) && STATE(FIXED_WING_LEGACY) && imuConfig()->acc_ignore_rate) { - const float rotRateMagnitude = sqrtf(vectorNormSquared(&imuMeasuredRotationBF)); + const float rotRateMagnitude = fast_fsqrtf(vectorNormSquared(&imuMeasuredRotationBF)); const float rotRateMagnitudeFiltered = pt1FilterApply4(&rotRateFilter, rotRateMagnitude, IMU_CENTRIFUGAL_LPF, dT); if (imuConfig()->acc_ignore_slope) { diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 2ee79621f0..a42625ccb8 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -347,8 +347,8 @@ static void applyTurtleModeToMotors(void) { float signRoll = rcCommand[ROLL] < 0 ? 1 : -1; float signYaw = (float)((rcCommand[YAW] < 0 ? 1 : -1) * (mixerConfig()->motorDirectionInverted ? 1 : -1)); - float stickDeflectionLength = sqrtf(sq(stickDeflectionPitchAbs) + sq(stickDeflectionRollAbs)); - float stickDeflectionExpoLength = sqrtf(sq(stickDeflectionPitchExpo) + sq(stickDeflectionRollExpo)); + float stickDeflectionLength = fast_fsqrtf(sq(stickDeflectionPitchAbs) + sq(stickDeflectionRollAbs)); + float stickDeflectionExpoLength = fast_fsqrtf(sq(stickDeflectionPitchExpo) + sq(stickDeflectionRollExpo)); if (stickDeflectionYawAbs > MAX(stickDeflectionPitchAbs, stickDeflectionRollAbs)) { // If yaw is the dominant, disable pitch and roll @@ -362,8 +362,8 @@ static void applyTurtleModeToMotors(void) { } const float cosPhi = (stickDeflectionLength > 0) ? (stickDeflectionPitchAbs + stickDeflectionRollAbs) / - (sqrtf(2.0f) * stickDeflectionLength) : 0; - const float cosThreshold = sqrtf(3.0f) / 2.0f; // cos(PI/6.0f) + (fast_fsqrtf(2.0f) * stickDeflectionLength) : 0; + const float cosThreshold = fast_fsqrtf(3.0f) / 2.0f; // cos(PI/6.0f) if (cosPhi < cosThreshold) { // Enforce either roll or pitch exclusively, if not on diagonal diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 6f6222d901..f773e275d8 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -421,7 +421,7 @@ void pidReduceErrorAccumulators(int8_t delta, uint8_t axis) float getTotalRateTarget(void) { - return sqrtf(sq(pidState[FD_ROLL].rateTarget) + sq(pidState[FD_PITCH].rateTarget) + sq(pidState[FD_YAW].rateTarget)); + return fast_fsqrtf(sq(pidState[FD_ROLL].rateTarget) + sq(pidState[FD_PITCH].rateTarget) + sq(pidState[FD_YAW].rateTarget)); } float getAxisIterm(uint8_t axis) diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index c3a242497c..b4bfb7948f 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -497,7 +497,7 @@ void processContinuousServoAutotrim(const float dT) static servoAutotrimState_e trimState = AUTOTRIM_IDLE; static uint32_t servoMiddleUpdateCount; - const float rotRateMagnitude = sqrtf(vectorNormSquared(&imuMeasuredRotationBF)); + const float rotRateMagnitude = fast_fsqrtf(vectorNormSquared(&imuMeasuredRotationBF)); const float rotRateMagnitudeFiltered = pt1FilterApply4(&rotRateFilter, rotRateMagnitude, SERVO_AUTOTRIM_FILTER_CUTOFF, dT); const float targetRateMagnitude = getTotalRateTarget(); const float targetRateMagnitudeFiltered = pt1FilterApply4(&targetRateFilter, targetRateMagnitude, SERVO_AUTOTRIM_FILTER_CUTOFF, dT); diff --git a/src/main/flight/wind_estimator.c b/src/main/flight/wind_estimator.c index 0de1f18ad4..2561ff6b21 100644 --- a/src/main/flight/wind_estimator.c +++ b/src/main/flight/wind_estimator.c @@ -72,7 +72,7 @@ float getEstimatedHorizontalWindSpeed(uint16_t *angle) } *angle = RADIANS_TO_CENTIDEGREES(horizontalWindAngle); } - return sqrtf(sq(xWindSpeed) + sq(yWindSpeed)); + return fast_fsqrtf(sq(xWindSpeed) + sq(yWindSpeed)); } void updateWindEstimator(timeUs_t currentTimeUs) @@ -133,7 +133,7 @@ void updateWindEstimator(timeUs_t currentTimeUs) groundVelocityDiff[Z] = groundVelocity[X] - lastGroundVelocity[Z]; // estimate airspeed it using equation 6 - float V = (sqrtf(sq(groundVelocityDiff[0]) + sq(groundVelocityDiff[1]) + sq(groundVelocityDiff[2]))) / sqrtf(diffLengthSq); + float V = (fast_fsqrtf(sq(groundVelocityDiff[0]) + sq(groundVelocityDiff[1]) + sq(groundVelocityDiff[2]))) / fast_fsqrtf(diffLengthSq); fuselageDirectionSum[X] = fuselageDirection[X] + lastFuselageDirection[X]; fuselageDirectionSum[Y] = fuselageDirection[Y] + lastFuselageDirection[Y]; @@ -155,8 +155,8 @@ void updateWindEstimator(timeUs_t currentTimeUs) wind[Y] = (groundVelocitySum[Y] - V * (sintheta * fuselageDirectionSum[X] + costheta * fuselageDirectionSum[Y])) * 0.5f;// equation 11 wind[Z] = (groundVelocitySum[Z] - V * fuselageDirectionSum[Z]) * 0.5f;// equation 12 - float prevWindLength = sqrtf(sq(estimatedWind[X]) + sq(estimatedWind[Y]) + sq(estimatedWind[Z])); - float windLength = sqrtf(sq(wind[X]) + sq(wind[Y]) + sq(wind[Z])); + float prevWindLength = fast_fsqrtf(sq(estimatedWind[X]) + sq(estimatedWind[Y]) + sq(estimatedWind[Z])); + float windLength = fast_fsqrtf(sq(wind[X]) + sq(wind[Y]) + sq(wind[Z])); if (windLength < prevWindLength + 2000) { // TODO: Better filtering diff --git a/src/main/io/gps_msp.c b/src/main/io/gps_msp.c index 35e7d12a1f..af90f711ad 100644 --- a/src/main/io/gps_msp.c +++ b/src/main/io/gps_msp.c @@ -89,7 +89,7 @@ void mspGPSReceiveNewData(const uint8_t * bufferPtr) gpsSol.velNED[X] = pkt->nedVelNorth; gpsSol.velNED[Y] = pkt->nedVelEast; gpsSol.velNED[Z] = pkt->nedVelDown; - gpsSol.groundSpeed = sqrtf(sq((float)pkt->nedVelNorth) + sq((float)pkt->nedVelEast)); + gpsSol.groundSpeed = fast_fsqrtf(sq((float)pkt->nedVelNorth) + sq((float)pkt->nedVelEast)); gpsSol.groundCourse = pkt->groundCourse / 10; // in deg * 10 gpsSol.eph = gpsConstrainEPE(pkt->horizontalPosAccuracy / 10); gpsSol.epv = gpsConstrainEPE(pkt->verticalPosAccuracy / 10); diff --git a/src/main/io/gps_naza.c b/src/main/io/gps_naza.c index 9413ed2588..91e3d09fcd 100644 --- a/src/main/io/gps_naza.c +++ b/src/main/io/gps_naza.c @@ -199,7 +199,7 @@ static bool NAZA_parse_gps(void) gpsSol.eph = gpsConstrainEPE(h_acc / 10); // hAcc in cm gpsSol.epv = gpsConstrainEPE(v_acc / 10); // vAcc in cm gpsSol.numSat = _buffernaza.nav.satellites; - gpsSol.groundSpeed = sqrtf(powf(gpsSol.velNED[0], 2)+powf(gpsSol.velNED[1], 2)); //cm/s + gpsSol.groundSpeed = fast_fsqrtf(powf(gpsSol.velNED[0], 2)+powf(gpsSol.velNED[1], 2)); //cm/s // calculate gps heading from VELNE gpsSol.groundCourse = (uint16_t) (fmodf(RADIANS_TO_DECIDEGREES(atan2_approx(gpsSol.velNED[1], gpsSol.velNED[0]))+3600.0f,3600.0f)); diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 8da246f8c1..6af5ec867c 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -3544,7 +3544,7 @@ static void osdFilterData(timeUs_t currentTimeUs) { static timeUs_t lastRefresh = 0; float refresh_dT = US2S(cmpTimeUs(currentTimeUs, lastRefresh)); - GForce = sqrtf(vectorNormSquared(&imuMeasuredAccelBF)) / GRAVITY_MSS; + GForce = fast_fsqrtf(vectorNormSquared(&imuMeasuredAccelBF)) / GRAVITY_MSS; for (uint8_t axis = 0; axis < XYZ_AXIS_COUNT; ++axis) GForceAxis[axis] = imuMeasuredAccelBF.v[axis] / GRAVITY_MSS; if (lastRefresh) { diff --git a/src/main/io/osd_common.c b/src/main/io/osd_common.c index adad66c6e2..3fa1d19d51 100644 --- a/src/main/io/osd_common.c +++ b/src/main/io/osd_common.c @@ -195,6 +195,6 @@ int16_t osdGet3DSpeed(void) { int16_t vert_speed = getEstimatedActualVelocity(Z); int16_t hor_speed = gpsSol.groundSpeed; - return (int16_t)sqrtf(sq(hor_speed) + sq(vert_speed)); + return (int16_t)fast_fsqrtf(sq(hor_speed) + sq(vert_speed)); } #endif diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 37a6c3c000..1edc58d00a 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -1933,7 +1933,7 @@ void updateActualHorizontalPositionAndVelocity(bool estPosValid, bool estVelVali posControl.actualState.agl.vel.x = newVelX; posControl.actualState.agl.vel.y = newVelY; - posControl.actualState.velXY = sqrtf(sq(newVelX) + sq(newVelY)); + posControl.actualState.velXY = fast_fsqrtf(sq(newVelX) + sq(newVelY)); // CASE 1: POS & VEL valid if (estPosValid && estVelValid) { @@ -2067,7 +2067,7 @@ const navEstimatedPosVel_t * navGetCurrentActualPositionAndVelocity(void) *-----------------------------------------------------------*/ static uint32_t calculateDistanceFromDelta(float deltaX, float deltaY) { - return sqrtf(sq(deltaX) + sq(deltaY)); + return fast_fsqrtf(sq(deltaX) + sq(deltaY)); } static int32_t calculateBearingFromDelta(float deltaX, float deltaY) @@ -3730,7 +3730,7 @@ static void GPS_distance_cm_bearing(int32_t currentLat1, int32_t currentLon1, in const float dLat = destinationLat2 - currentLat1; // difference of latitude in 1/10 000 000 degrees const float dLon = (float)(destinationLon2 - currentLon1) * GPS_scaleLonDown; - *dist = sqrtf(sq(dLat) + sq(dLon)) * DISTANCE_BETWEEN_TWO_LONGITUDE_POINTS_AT_EQUATOR; + *dist = fast_fsqrtf(sq(dLat) + sq(dLon)) * DISTANCE_BETWEEN_TWO_LONGITUDE_POINTS_AT_EQUATOR; *bearing = 9000.0f + RADIANS_TO_CENTIDEGREES(atan2_approx(-dLat, dLon)); // Convert the output radians to 100xdeg diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 6501cc7ea2..a20689fd91 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -249,7 +249,7 @@ static void calculateVirtualPositionTarget_FW(float trackingPeriod) float posErrorX = posControl.desiredState.pos.x - navGetCurrentActualPositionAndVelocity()->pos.x; float posErrorY = posControl.desiredState.pos.y - navGetCurrentActualPositionAndVelocity()->pos.y; - float distanceToActualTarget = sqrtf(sq(posErrorX) + sq(posErrorY)); + float distanceToActualTarget = fast_fsqrtf(sq(posErrorX) + sq(posErrorY)); // Limit minimum forward velocity to 1 m/s float trackingDistance = trackingPeriod * MAX(posControl.actualState.velXY, 100.0f); @@ -272,7 +272,7 @@ static void calculateVirtualPositionTarget_FW(float trackingPeriod) // We have temporary loiter target. Recalculate distance and position error posErrorX = loiterTargetX - navGetCurrentActualPositionAndVelocity()->pos.x; posErrorY = loiterTargetY - navGetCurrentActualPositionAndVelocity()->pos.y; - distanceToActualTarget = sqrtf(sq(posErrorX) + sq(posErrorY)); + distanceToActualTarget = fast_fsqrtf(sq(posErrorX) + sq(posErrorY)); } // Calculate virtual waypoint diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c index 8af05db4da..a141af251f 100755 --- a/src/main/navigation/navigation_multicopter.c +++ b/src/main/navigation/navigation_multicopter.c @@ -437,7 +437,7 @@ static void updatePositionVelocityController_MC(const float maxSpeed) float newVelY = posErrorY * posControl.pids.pos[Y].param.kP; // Scale velocity to respect max_speed - float newVelTotal = sqrtf(sq(newVelX) + sq(newVelY)); + float newVelTotal = fast_fsqrtf(sq(newVelX) + sq(newVelY)); /* * We override computed speed with max speed in following cases: @@ -497,7 +497,7 @@ static void updatePositionAccelController_MC(timeDelta_t deltaMicros, float maxA const float setpointX = posControl.desiredState.vel.x; const float setpointY = posControl.desiredState.vel.y; - const float setpointXY = sqrtf(powf(setpointX, 2)+powf(setpointY, 2)); + const float setpointXY = fast_fsqrtf(powf(setpointX, 2)+powf(setpointY, 2)); // Calculate velocity error const float velErrorX = setpointX - measurementX; @@ -505,7 +505,7 @@ static void updatePositionAccelController_MC(timeDelta_t deltaMicros, float maxA // Calculate XY-acceleration limit according to velocity error limit float accelLimitX, accelLimitY; - const float velErrorMagnitude = sqrtf(sq(velErrorX) + sq(velErrorY)); + const float velErrorMagnitude = fast_fsqrtf(sq(velErrorX) + sq(velErrorY)); if (velErrorMagnitude > 0.1f) { accelLimitX = maxAccelLimit / velErrorMagnitude * fabsf(velErrorX); accelLimitY = maxAccelLimit / velErrorMagnitude * fabsf(velErrorY); diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c index 700909aaa4..236420c89b 100755 --- a/src/main/navigation/navigation_pos_estimator.c +++ b/src/main/navigation/navigation_pos_estimator.c @@ -164,7 +164,7 @@ static bool detectGPSGlitch(timeUs_t currentTimeUs) predictedGpsPosition.y = lastKnownGoodPosition.y + lastKnownGoodVelocity.y * dT; /* New pos is within predefined radius of predicted pos, radius is expanded exponentially */ - gpsDistance = sqrtf(sq(predictedGpsPosition.x - lastKnownGoodPosition.x) + sq(predictedGpsPosition.y - lastKnownGoodPosition.y)); + gpsDistance = fast_fsqrtf(sq(predictedGpsPosition.x - lastKnownGoodPosition.x) + sq(predictedGpsPosition.y - lastKnownGoodPosition.y)); if (gpsDistance <= (INAV_GPS_GLITCH_RADIUS + 0.5f * INAV_GPS_GLITCH_ACCEL * dT * dT)) { isGlitching = false; } @@ -640,7 +640,7 @@ static bool estimationCalculateCorrection_XY_GPS(estimationContext_t * ctx) const float gpsPosYResidual = posEstimator.gps.pos.y - posEstimator.est.pos.y; const float gpsVelXResidual = posEstimator.gps.vel.x - posEstimator.est.vel.x; const float gpsVelYResidual = posEstimator.gps.vel.y - posEstimator.est.vel.y; - const float gpsPosResidualMag = sqrtf(sq(gpsPosXResidual) + sq(gpsPosYResidual)); + const float gpsPosResidualMag = fast_fsqrtf(sq(gpsPosXResidual) + sq(gpsPosYResidual)); //const float gpsWeightScaler = scaleRangef(bellCurve(gpsPosResidualMag, INAV_GPS_ACCEPTANCE_EPE), 0.0f, 1.0f, 0.1f, 1.0f); const float gpsWeightScaler = 1.0f; diff --git a/src/main/navigation/navigation_pos_estimator_flow.c b/src/main/navigation/navigation_pos_estimator_flow.c index 60ecaad865..d3fac7c5de 100644 --- a/src/main/navigation/navigation_pos_estimator_flow.c +++ b/src/main/navigation/navigation_pos_estimator_flow.c @@ -109,7 +109,7 @@ bool estimationCalculateCorrection_XY_FLOW(estimationContext_t * ctx) ctx->estPosCorr.x = flowResidualX * positionEstimationConfig()->w_xy_flow_p * ctx->dt; ctx->estPosCorr.y = flowResidualY * positionEstimationConfig()->w_xy_flow_p * ctx->dt; - ctx->newEPH = updateEPE(posEstimator.est.eph, ctx->dt, sqrtf(sq(flowResidualX) + sq(flowResidualY)), positionEstimationConfig()->w_xy_flow_p); + ctx->newEPH = updateEPE(posEstimator.est.eph, ctx->dt, fast_fsqrtf(sq(flowResidualX) + sq(flowResidualY)), positionEstimationConfig()->w_xy_flow_p); } DEBUG_SET(DEBUG_FLOW, 0, RADIANS_TO_DEGREES(posEstimator.flow.flowRate[X])); diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index 01e2dada95..5fa6f92733 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -514,7 +514,7 @@ static int logicConditionGetFlightOperandValue(int operand) { break; case LOGIC_CONDITION_OPERAND_FLIGHT_3D_HOME_DISTANCE: //in m - return constrain(sqrtf(sq(GPS_distanceToHome) + sq(getEstimatedActualPosition(Z)/100)), 0, INT16_MAX); + return constrain(fast_fsqrtf(sq(GPS_distanceToHome) + sq(getEstimatedActualPosition(Z)/100)), 0, INT16_MAX); break; case LOGIC_CONDITION_OPERAND_FLIGHT_CRSF_LQ: diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index aeb6af2965..1f5d1de04d 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -616,20 +616,20 @@ void updateAccExtremes(void) if (acc.accADCf[axis] > acc.extremes[axis].max) acc.extremes[axis].max = acc.accADCf[axis]; } - float gforce = sqrtf(sq(acc.accADCf[0]) + sq(acc.accADCf[1]) + sq(acc.accADCf[2])); + float gforce = fast_fsqrtf(sq(acc.accADCf[0]) + sq(acc.accADCf[1]) + sq(acc.accADCf[2])); if (gforce > acc.maxG) acc.maxG = gforce; } void accGetVibrationLevels(fpVector3_t *accVibeLevels) { - accVibeLevels->x = sqrtf(acc.accVibeSq[X]); - accVibeLevels->y = sqrtf(acc.accVibeSq[Y]); - accVibeLevels->z = sqrtf(acc.accVibeSq[Z]); + accVibeLevels->x = fast_fsqrtf(acc.accVibeSq[X]); + accVibeLevels->y = fast_fsqrtf(acc.accVibeSq[Y]); + accVibeLevels->z = fast_fsqrtf(acc.accVibeSq[Z]); } float accGetVibrationLevel(void) { - return sqrtf(acc.accVibeSq[X] + acc.accVibeSq[Y] + acc.accVibeSq[Z]); + return fast_fsqrtf(acc.accVibeSq[X] + acc.accVibeSq[Y] + acc.accVibeSq[Z]); } uint32_t accGetClipCount(void) diff --git a/src/main/sensors/opflow.c b/src/main/sensors/opflow.c index 9c1b6f265e..aaecd8bc53 100755 --- a/src/main/sensors/opflow.c +++ b/src/main/sensors/opflow.c @@ -237,8 +237,8 @@ void opflowUpdate(timeUs_t currentTimeUs) else if (opflow.flowQuality == OPFLOW_QUALITY_VALID) { // Ongoing calibration - accumulate body and flow rotation magniture if opflow quality is good enough const float invDt = 1.0e6 / opflow.dev.rawData.deltaTime; - opflowCalibrationBodyAcc += sqrtf(sq(opflow.bodyRate[X]) + sq(opflow.bodyRate[Y])); - opflowCalibrationFlowAcc += sqrtf(sq(opflow.dev.rawData.flowRateRaw[X]) + sq(opflow.dev.rawData.flowRateRaw[Y])) * invDt; + opflowCalibrationBodyAcc += fast_fsqrtf(sq(opflow.bodyRate[X]) + sq(opflow.bodyRate[Y])); + opflowCalibrationFlowAcc += fast_fsqrtf(sq(opflow.dev.rawData.flowRateRaw[X]) + sq(opflow.dev.rawData.flowRateRaw[Y])) * invDt; } } diff --git a/src/main/sensors/pitotmeter.c b/src/main/sensors/pitotmeter.c index a330be79bb..332f98e02e 100644 --- a/src/main/sensors/pitotmeter.c +++ b/src/main/sensors/pitotmeter.c @@ -223,7 +223,7 @@ STATIC_PROTOTHREAD(pitotThread) // // Therefore we shouldn't care about CAS/TAS and only calculate IAS since it's more indicative to the pilot and more useful in calculations // It also allows us to use pitot_scale to calibrate the dynamic pressure sensor scale - pitot.airSpeed = pitotmeterConfig()->pitot_scale * sqrtf(2.0f * fabsf(pitot.pressure - pitot.pressureZero) / AIR_DENSITY_SEA_LEVEL_15C) * 100; + pitot.airSpeed = pitotmeterConfig()->pitot_scale * fast_fsqrtf(2.0f * fabsf(pitot.pressure - pitot.pressureZero) / AIR_DENSITY_SEA_LEVEL_15C) * 100; } else { performPitotCalibrationCycle(); pitot.airSpeed = 0; From 02d4f17f78fc71aa2ed3126a493ca18e0454de37 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 17 May 2021 12:23:40 +0200 Subject: [PATCH 006/102] Fix unit tests --- src/main/common/maths.c | 13 ++++++++++--- src/main/common/maths.h | 2 +- src/main/target/common_post.h | 3 +++ 3 files changed, 14 insertions(+), 4 deletions(-) diff --git a/src/main/common/maths.c b/src/main/common/maths.c index 6c388ba717..a99c3f346b 100644 --- a/src/main/common/maths.c +++ b/src/main/common/maths.c @@ -19,13 +19,16 @@ #include #include -#include "arm_math.h" #include "axis.h" #include "maths.h" #include "vector.h" #include "quaternion.h" #include "platform.h" +#ifdef USE_ARM_MATH +#include "arm_math.h" +#endif + FILE_COMPILE_FOR_SPEED // http://lolengine.net/blog/2011/12/21/better-function-approximations @@ -520,8 +523,12 @@ float bellCurve(const float x, const float curveWidth) return powf(M_Ef, -sq(x) / (2.0f * sq(curveWidth))); } -float fast_fsqrtf(const float value) { +float fast_fsqrtf(const double value) { +#ifdef USE_ARM_MATH float squirt; arm_sqrt_f32(value, &squirt); - return squirt; + return squirt; +#else + return sqrtf(value); +#endif } \ No newline at end of file diff --git a/src/main/common/maths.h b/src/main/common/maths.h index 581513f148..d84fc25751 100644 --- a/src/main/common/maths.h +++ b/src/main/common/maths.h @@ -176,4 +176,4 @@ float acos_approx(float x); void arraySubInt32(int32_t *dest, int32_t *array1, int32_t *array2, int count); float bellCurve(const float x, const float curveWidth); -float fast_fsqrtf(const float value); +float fast_fsqrtf(const double value); diff --git a/src/main/target/common_post.h b/src/main/target/common_post.h index 1091319057..1c7767dcf8 100644 --- a/src/main/target/common_post.h +++ b/src/main/target/common_post.h @@ -61,9 +61,12 @@ extern uint8_t __config_end; #undef USE_PWM_SERVO_DRIVER #endif +#define USE_ARM_MATH // try to use FPU functions + #if defined(SIMULATOR_BUILD) || defined(UNIT_TEST) // This feature uses 'arm_math.h', which does not exist for x86. #undef USE_DYNAMIC_FILTERS +#undef USE_ARM_MATH #endif //Defines for compiler optimizations From 9448d08baa3a8ef46dac70280ea0626e2201d993 Mon Sep 17 00:00:00 2001 From: tednv <24532778+tednv@users.noreply.github.com> Date: Mon, 17 May 2021 07:37:59 -0700 Subject: [PATCH 007/102] fixing formatting --- .../Building in Windows 10 with MSYS2.md | 43 ++++++++++++------- 1 file changed, 27 insertions(+), 16 deletions(-) diff --git a/docs/development/Building in Windows 10 with MSYS2.md b/docs/development/Building in Windows 10 with MSYS2.md index 134e9c1379..59bd2c3537 100644 --- a/docs/development/Building in Windows 10 with MSYS2.md +++ b/docs/development/Building in Windows 10 with MSYS2.md @@ -23,14 +23,14 @@ Once MSYS2 is installed, you can open up a new terminal window by running: You can also make a shortcut of this somewhere on your taskbar, desktop, etc, or even setup a shortcut key to open it up every time you need to get a terminal window. If you right click on the window you can customize the font and layout to make it more comfortable to work with. This is very similar to cygwin or any other terminal program you might have used before This is the best part: -` +``` pacman -S git ruby make cmake gcc mingw-w64-x86_64-libwinpthread-git unzip wget -` +``` Now, each release needs a different version of arm toolchain. To setup the xPack ARM toolchain, use the following process: -First, get the release you want to build or master if you want the latest/greatest -` +First, setup your work path, get the release you want to build or master if you want the latest/greatest +``` mkdir /c/Workspace cd /c/Workspace # you can also check out your own fork here which makes contributing easier @@ -39,28 +39,39 @@ cd inav # switch to release you want or skip next 2 lines if you want latest git fetch origin git checkout -b release_2.6.1 origin/release_2.6.1 +``` +Now create the build and xpack directories and get the toolkit version you need for your inav version +``` mkdir build cd build mkdir /c/Workspace/xpack cd /c/Workspace/xpack -# now find the arm toolchain version you need for this inav release cat /c/Workspace/inav/cmake/arm-none-eabi-checks.cmake | grep "set(arm_none_eabi_gcc_version" | cut -d\" -f2 -# this will give you the version you need for any given release or master branch -# you can get to all the releases here and find the version you need -# https://github.com/xpack-dev-tools/arm-none-eabi-gcc-xpack/releases/ +``` +This will give you the version you need for any given release or master branch. You can get to all the releases here and find the version you need +https://github.com/xpack-dev-tools/arm-none-eabi-gcc-xpack/releases/ +``` # for version 2.6.1, version needed is 9.2.1 wget https://github.com/xpack-dev-tools/arm-none-eabi-gcc-xpack/releases/download/v9.2.1-1.1/xpack-arm-none-eabi-gcc-9.2.1-1.1-win32-x64.zip unzip xpack-arm-none-eabi-gcc-9.2.1-1.1-win32-x64.zip -# this is important, put the toolkit first before your path so that it is -# picked up ahead of any other versions that may be present on your system +``` +This is important, put the toolkit first before your path so that it is picked up ahead of any other versions that may be present on your system +``` export PATH=/c/Workspace/xpack/xpack-arm-none-eabi-gcc-9.2.1-1.1/bin:$PATH cd /c/Workspace/inav/build -# you may need to run rm -rf * in build directory if you had any failed previous runs -# now run cmake .. while inside the build directory +``` +You may need to run rm -rf * in build directory if you had any failed previous runs now run cmake +``` +# while inside the build directory cmake .. -# once that's done you can compile the firmware for your controller +``` +Once that's done you can compile the firmware for your controller +``` make DALRCF405 -# the generated hex file will be in /c/Workspace/inav/build folder -` +``` +To get a list of available targets in iNav, see the target src folder +https://github.com/tednv/inav/tree/master/src/main/target -At the time of writting this document, I believe this is the fastest, easiest, and most efficient Windows build environment that is available. I have used this approach several years ago and was very happy with it building iNav 2.1 and 2.2, and now I'm getting back into it so figured I would share my method \ No newline at end of file +The generated hex file will be in /c/Workspace/inav/build folder + +At the time of writting this document, I believe this is the fastest, easiest, and most efficient Windows build environment that is available. I have used this approach several years ago and was very happy with it building iNav 2.1 and 2.2, and now I'm getting back into it so figured I would share my method From 2aaa22e63261114bebae1bc2c35549d4d9257f96 Mon Sep 17 00:00:00 2001 From: tednv <24532778+tednv@users.noreply.github.com> Date: Mon, 17 May 2021 07:38:41 -0700 Subject: [PATCH 008/102] Update Building in Windows 10 with MSYS2.md --- docs/development/Building in Windows 10 with MSYS2.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/docs/development/Building in Windows 10 with MSYS2.md b/docs/development/Building in Windows 10 with MSYS2.md index 59bd2c3537..2593e25c61 100644 --- a/docs/development/Building in Windows 10 with MSYS2.md +++ b/docs/development/Building in Windows 10 with MSYS2.md @@ -3,11 +3,13 @@ This is a guide on how to use Windows MSYS2 distribution and building platform to build iNav firmware. This environment is very simple to manage and does not require installing docker for Windows which may get in the way of VMWare or any other virtualization software you already have running for other reasons. Another benefit of this approach is that the compiler runs natively on Windows, so performance is much better than compiling in a virtual environment or a container. You can also integrate with whatever IDE you are using to make code edits and work with github, which makes the entire development and testing workflow a lot more efficient. In addition to MSYS2, this build environment also uses Arm Embedded GCC tolkit from The xPack Project, which provides many benefits over the toolkits maintained by arm.com Some of those benefits are described here: + https://xpack.github.io/arm-none-eabi-gcc/ ## Setting up build environment Download MSYS2 for your architecture (most likely 64-bit) + https://www.msys2.org/wiki/MSYS2-installation/ Click on 64-bit, scroll all the way down for the latest release @@ -49,6 +51,7 @@ cd /c/Workspace/xpack cat /c/Workspace/inav/cmake/arm-none-eabi-checks.cmake | grep "set(arm_none_eabi_gcc_version" | cut -d\" -f2 ``` This will give you the version you need for any given release or master branch. You can get to all the releases here and find the version you need + https://github.com/xpack-dev-tools/arm-none-eabi-gcc-xpack/releases/ ``` # for version 2.6.1, version needed is 9.2.1 From 96f54a75c4e3103885f1b65882c7f1826c9fb688 Mon Sep 17 00:00:00 2001 From: flywoo Date: Tue, 18 May 2021 17:11:59 +0800 Subject: [PATCH 009/102] Add new target FLYWOOF745 --- src/main/target/FLYWOOF745/CMakeLists.txt | 2 + src/main/target/FLYWOOF745/target.c | 45 ++++++ src/main/target/FLYWOOF745/target.h | 176 ++++++++++++++++++++++ 3 files changed, 223 insertions(+) create mode 100644 src/main/target/FLYWOOF745/CMakeLists.txt create mode 100644 src/main/target/FLYWOOF745/target.c create mode 100644 src/main/target/FLYWOOF745/target.h diff --git a/src/main/target/FLYWOOF745/CMakeLists.txt b/src/main/target/FLYWOOF745/CMakeLists.txt new file mode 100644 index 0000000000..7839c348b3 --- /dev/null +++ b/src/main/target/FLYWOOF745/CMakeLists.txt @@ -0,0 +1,2 @@ +target_stm32f745xg(FLYWOOF745) +target_stm32f745xg(FLYWOOF745NANO) diff --git a/src/main/target/FLYWOOF745/target.c b/src/main/target/FLYWOOF745/target.c new file mode 100644 index 0000000000..7512bff47b --- /dev/null +++ b/src/main/target/FLYWOOF745/target.c @@ -0,0 +1,45 @@ +/* + * This file is part of INAV. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/bus.h" + +const timerHardware_t timerHardware[] = { + DEF_TIM(TIM1, CH3, PE13, TIM_USE_PPM, 0, 1), // PPM, DMA2_ST6 + + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M1 , DMA1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M2 , DMA1_ST2 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // M3 , DMA2_ST2 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // M4 , DMA2_ST4 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M5 , DMA2_ST7 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M6 , DMA1_ST1 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M7 , DMA1_ST4 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M8 , DMA1_ST5 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0), // LED_STRIP, DMA1_ST0 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/FLYWOOF745/target.h b/src/main/target/FLYWOOF745/target.h new file mode 100644 index 0000000000..ddf5690b2d --- /dev/null +++ b/src/main/target/FLYWOOF745/target.h @@ -0,0 +1,176 @@ +/* + * This file is part of INAV. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +#ifdef FLYWOOF745 +#define TARGET_BOARD_IDENTIFIER "FWF7" +#define USBD_PRODUCT_STRING "FLYWOOF745" +#else +#define TARGET_BOARD_IDENTIFIER "FW7N" +#define USBD_PRODUCT_STRING "FLYWOOF745NANO" +#endif + +#define LED0 PA2// + +#define BEEPER PD15// +#define BEEPER_INVERTED + +#define USE_DSHOT +#define USE_ESC_SENSOR + +#define USE_MPU_DATA_READY_SIGNAL +#define USE_EXTI + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW270_DEG// +#define GYRO_INT_EXTI PE1// +#define MPU6000_CS_PIN SPI4_NSS_PIN// +#define MPU6000_SPI_BUS BUS_SPI4// + + +#define USB_IO +#define USE_VCP +#define VBUS_SENSING_ENABLED +#define VBUS_SENSING_PIN PA8// + +#define USE_UART1 +#define UART1_TX_PIN PA9// +#define UART1_RX_PIN PA10// + +#define USE_UART2 +#define UART2_TX_PIN PD5// +#define UART2_RX_PIN PD6// + +#define USE_UART3 + +#ifdef FLYWOOF745 +#define UART3_TX_PIN PB10// +#define UART3_RX_PIN PB11// +#else +#define UART3_TX_PIN PD8// +#define UART3_RX_PIN PD9// +#endif + +#define USE_UART4 +#define UART4_TX_PIN PA0// +#define UART4_RX_PIN PA1// + +#define USE_UART5 +#define UART5_TX_PIN PC12// +#define UART5_RX_PIN PD2// + +#define USE_UART6 +#define UART6_TX_PIN PC6// +#define UART6_RX_PIN PC7// + +#define USE_UART7 +#define UART7_TX_PIN PE8// +#define UART7_RX_PIN PE7// + +#define SERIAL_PORT_COUNT 8 //VCP,UART1,UART2,UART3,UART4,UART5,UART6,UART7 + +#define USE_SPI +#define USE_SPI_DEVICE_1 //FLASH +#define USE_SPI_DEVICE_2 //OSD +#define USE_SPI_DEVICE_4 //ICM20689 + +#define SPI1_NSS_PIN PA4// +#define SPI1_SCK_PIN PA5// +#define SPI1_MISO_PIN PA6// +#define SPI1_MOSI_PIN PA7// + +#define SPI2_NSS_PIN PB12// +#define SPI2_SCK_PIN PB13/// +#define SPI2_MISO_PIN PB14// +#define SPI2_MOSI_PIN PB15// + +#define SPI4_NSS_PIN PE4// +#define SPI4_SCK_PIN PE2// +#define SPI4_MISO_PIN PE5// +#define SPI4_MOSI_PIN PE6// + +#define USE_OSD + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN SPI2_NSS_PIN + +#define M25P16_CS_PIN SPI1_NSS_PIN +#define M25P16_SPI_BUS BUS_SPI1 +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 + +#ifdef FLYWOOF745NANO +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 +#endif +#define USE_BARO +#define USE_BARO_BMP280 +#define BARO_I2C_BUS BUS_I2C1 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_MAG3110 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_LIS3MDL + +#define TEMPERATURE_I2C_BUS BUS_I2C1 + +#define RANGEFINDER_I2C_BUS BUS_I2C1 + +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC2// +#define ADC_CHANNEL_2_PIN PC3// +#define ADC_CHANNEL_3_PIN PC5// + +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 +#define VBAT_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_VBAT | FEATURE_BLACKBOX) +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_UART SERIAL_PORT_USART1 +#define SERIALRX_PROVIDER SERIALRX_SBUS + +#define USE_LED_STRIP +#define WS2811_PIN PD12 // //TIM4_CH1 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff + +#define MAX_PWM_OUTPUT_PORTS 8 From 9f98cbc91e95fbb752dec0bd6df5ec65f44bedef Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Tue, 18 May 2021 18:24:21 +0200 Subject: [PATCH 010/102] Add .cache/ to .gitignore (#6983) --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index cc71acb9c4..a27fcbeb0a 100644 --- a/.gitignore +++ b/.gitignore @@ -8,6 +8,7 @@ .project .settings .cproject +.cache/ __pycache__ startup_stm32f10x_md_gcc.s .vagrant/ From 2e9eeb838c62ced6a88427a80a5622928378613c Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Wed, 19 May 2021 11:57:09 +0100 Subject: [PATCH 011/102] OSD RTC time seconds display option --- src/main/fc/settings.yaml | 7 ++++++- src/main/io/osd.c | 7 ++++++- src/main/io/osd.h | 1 + 3 files changed, 13 insertions(+), 2 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 26cc4d446f..e93820d2d0 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -77,7 +77,7 @@ tables: enum: videoSystem_e - name: osd_telemetry values: ["OFF", "ON","TEST"] - enum: osd_telemetry_e + enum: osd_telemetry_e - name: osd_alignment values: ["LEFT", "RIGHT"] enum: osd_alignment_e @@ -3254,6 +3254,11 @@ groups: field: main_voltage_decimals min: 1 max: 2 + - name: osd_rtc_time_show_seconds + description: "Enable to show seconds in current time display." + field: rtc_time_show_seconds + type: bool + default_value: OFF - name: osd_coordinate_digits field: coordinate_digits min: 8 diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 8da246f8c1..8f1fb05f5e 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2283,7 +2283,11 @@ static bool osdDrawSingleElement(uint8_t item) dateTime_t dateTime; rtcGetDateTimeLocal(&dateTime); buff[0] = SYM_CLOCK; - tfp_sprintf(buff + 1, "%02u:%02u", dateTime.hours, dateTime.minutes); + if (osdConfig()->rtc_time_show_seconds) { + tfp_sprintf(buff + 1, "%02u:%02u:%02u", dateTime.hours, dateTime.minutes, dateTime.seconds); + } else { + tfp_sprintf(buff + 1, "%02u:%02u", dateTime.hours, dateTime.minutes); + } break; } @@ -2918,6 +2922,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .units = SETTING_OSD_UNITS_DEFAULT, .main_voltage_decimals = SETTING_OSD_MAIN_VOLTAGE_DECIMALS_DEFAULT, + .rtc_time_show_seconds = SETTING_OSD_RTC_TIME_SHOW_SECONDS_DEFAULT, #ifdef USE_WIND_ESTIMATOR .estimations_wind_compensation = SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_DEFAULT, diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 8f4e4d4bf9..d08ee95956 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -375,6 +375,7 @@ typedef struct osdConfig_s { uint8_t crsf_lq_format; uint8_t sidebar_height; // sidebar height in rows, 0 turns off sidebars leaving only level indicator arrows uint8_t telemetry; // use telemetry on displayed pixel line 0 + bool rtc_time_show_seconds; // show seconds in current time display when enabled } osdConfig_t; From cea6a580d854348cce15460059e662a1ceb7444d Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Wed, 19 May 2021 12:02:14 +0100 Subject: [PATCH 012/102] Update Settings.md --- docs/Settings.md | 1 + 1 file changed, 1 insertion(+) diff --git a/docs/Settings.md b/docs/Settings.md index 1fe695deca..343ddebe30 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -441,6 +441,7 @@ | osd_right_sidebar_scroll_step | 0 | | 255 | Same as left_sidebar_scroll_step, but for the right sidebar | | osd_row_shiftdown | 0 | 0 | 1 | Number of rows to shift the OSD display (increase if top rows are cut off) | | osd_rssi_alarm | 20 | 0 | 100 | Value below which to make the OSD RSSI indicator blink | +| osd_rtc_time_show_seconds | OFF | | | Enable to show seconds in current time display. | | osd_sidebar_height | 3 | 0 | 5 | Height of sidebars in rows. 0 leaves only the level indicator arrows (Not for pixel OSD) | | osd_sidebar_horizontal_offset | 0 | -128 | 127 | Sidebar horizontal offset from default position. Positive values move the sidebars closer to the edges. | | osd_sidebar_scroll_arrows | OFF | | | | From 60494f44accb630547503aefee5063e8b87150a0 Mon Sep 17 00:00:00 2001 From: Hubert Jozwiak Date: Wed, 19 May 2021 15:55:58 +0200 Subject: [PATCH 013/102] Include compass in OSD sensors calibration message --- AUTHORS | 1 + src/main/fc/fc_core.c | 13 ++++++++++--- src/main/fc/fc_core.h | 2 +- src/main/sensors/compass.c | 10 ++++++++++ src/main/sensors/compass.h | 1 + src/main/telemetry/mavlink.c | 2 +- 6 files changed, 24 insertions(+), 5 deletions(-) diff --git a/AUTHORS b/AUTHORS index 839a8a5d8e..a254cd3364 100644 --- a/AUTHORS +++ b/AUTHORS @@ -35,6 +35,7 @@ GaĆ«l James Gregor Ottmann Google LLC Hyon Lim +Hubert Jozwiak James Harrison Jan Staal Jeremy Waters diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 57825a01cc..34dc4e6706 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -45,6 +45,7 @@ FILE_COMPILE_FOR_SPEED #include "sensors/boardalignment.h" #include "sensors/acceleration.h" #include "sensors/barometer.h" +#include "sensors/compass.h" #include "sensors/pitotmeter.h" #include "sensors/gyro.h" #include "sensors/battery.h" @@ -135,7 +136,7 @@ static emergencyArmingState_t emergencyArming; static bool prearmWasReset = false; // Prearm must be reset (RC Mode not active) before arming is possible static timeMs_t prearmActivationTime = 0; -bool isCalibrating(void) +bool areSensorsCalibrating(void) { #ifdef USE_BARO if (sensors(SENSOR_BARO) && !baroIsCalibrationComplete()) { @@ -143,6 +144,12 @@ bool isCalibrating(void) } #endif +#ifdef USE_MAG + if (sensors(SENSOR_MAG) && !compassIsCalibrationComplete()) { + return true; + } +#endif + #ifdef USE_PITOT if (sensors(SENSOR_PITOT) && !pitotIsCalibrationComplete()) { return true; @@ -183,7 +190,7 @@ static void updateArmingStatus(void) } else { /* CHECK: Run-time calibration */ static bool calibratingFinishedBeep = false; - if (isCalibrating()) { + if (areSensorsCalibrating()) { ENABLE_ARMING_FLAG(ARMING_DISABLED_SENSORS_CALIBRATING); calibratingFinishedBeep = false; } @@ -711,7 +718,7 @@ void processRx(timeUs_t currentTimeUs) // Handle passthrough mode if (STATE(FIXED_WING_LEGACY)) { if ((IS_RC_MODE_ACTIVE(BOXMANUAL) && !navigationRequiresAngleMode() && !failsafeRequiresAngleMode()) || // Normal activation of passthrough - (!ARMING_FLAG(ARMED) && isCalibrating())){ // Backup - if we are not armed - enforce passthrough while calibrating + (!ARMING_FLAG(ARMED) && areSensorsCalibrating())){ // Backup - if we are not armed - enforce passthrough while calibrating ENABLE_FLIGHT_MODE(MANUAL_MODE); } else { DISABLE_FLIGHT_MODE(MANUAL_MODE); diff --git a/src/main/fc/fc_core.h b/src/main/fc/fc_core.h index f41322fa02..e948dec836 100644 --- a/src/main/fc/fc_core.h +++ b/src/main/fc/fc_core.h @@ -43,7 +43,7 @@ disarmReason_t getDisarmReason(void); void emergencyArmingUpdate(bool armingSwitchIsOn); -bool isCalibrating(void); +bool areSensorsCalibrating(void); float getFlightTime(void); float getArmTime(void); diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index 1089f6fbb6..92ea43ee6b 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -329,6 +329,16 @@ bool compassIsReady(void) return magUpdatedAtLeastOnce; } +bool compassIsCalibrationComplete(void) +{ + if (STATE(COMPASS_CALIBRATED)) { + return true; + } + else { + return false; + } +} + void compassUpdate(timeUs_t currentTimeUs) { static sensorCalibrationState_t calState; diff --git a/src/main/sensors/compass.h b/src/main/sensors/compass.h index baba7bf6a1..fb0e75367f 100644 --- a/src/main/sensors/compass.h +++ b/src/main/sensors/compass.h @@ -78,5 +78,6 @@ bool compassInit(void); void compassUpdate(timeUs_t currentTimeUs); bool compassIsReady(void); bool compassIsHealthy(void); +bool compassIsCalibrationComplete(void); #endif diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index 6c9ded6869..06332a166c 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -733,7 +733,7 @@ void mavlinkSendHUDAndHeartbeat(void) mavSystemState = MAV_STATE_ACTIVE; } } - else if (isCalibrating()) { + else if (areSensorsCalibrating()) { mavSystemState = MAV_STATE_CALIBRATING; } else { From 96b934a00e46c5c33c44e62421930003571c5d8c Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Wed, 19 May 2021 16:11:39 +0100 Subject: [PATCH 014/102] Remove option --- docs/Settings.md | 1 - src/main/fc/settings.yaml | 5 ----- src/main/io/osd.c | 7 +------ src/main/io/osd.h | 1 - 4 files changed, 1 insertion(+), 13 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 343ddebe30..1fe695deca 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -441,7 +441,6 @@ | osd_right_sidebar_scroll_step | 0 | | 255 | Same as left_sidebar_scroll_step, but for the right sidebar | | osd_row_shiftdown | 0 | 0 | 1 | Number of rows to shift the OSD display (increase if top rows are cut off) | | osd_rssi_alarm | 20 | 0 | 100 | Value below which to make the OSD RSSI indicator blink | -| osd_rtc_time_show_seconds | OFF | | | Enable to show seconds in current time display. | | osd_sidebar_height | 3 | 0 | 5 | Height of sidebars in rows. 0 leaves only the level indicator arrows (Not for pixel OSD) | | osd_sidebar_horizontal_offset | 0 | -128 | 127 | Sidebar horizontal offset from default position. Positive values move the sidebars closer to the edges. | | osd_sidebar_scroll_arrows | OFF | | | | diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index e93820d2d0..6864eadfcf 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3254,11 +3254,6 @@ groups: field: main_voltage_decimals min: 1 max: 2 - - name: osd_rtc_time_show_seconds - description: "Enable to show seconds in current time display." - field: rtc_time_show_seconds - type: bool - default_value: OFF - name: osd_coordinate_digits field: coordinate_digits min: 8 diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 8f1fb05f5e..f0c4af8c24 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2283,11 +2283,7 @@ static bool osdDrawSingleElement(uint8_t item) dateTime_t dateTime; rtcGetDateTimeLocal(&dateTime); buff[0] = SYM_CLOCK; - if (osdConfig()->rtc_time_show_seconds) { - tfp_sprintf(buff + 1, "%02u:%02u:%02u", dateTime.hours, dateTime.minutes, dateTime.seconds); - } else { - tfp_sprintf(buff + 1, "%02u:%02u", dateTime.hours, dateTime.minutes); - } + tfp_sprintf(buff + 1, "%02u:%02u:%02u", dateTime.hours, dateTime.minutes, dateTime.seconds); break; } @@ -2922,7 +2918,6 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .units = SETTING_OSD_UNITS_DEFAULT, .main_voltage_decimals = SETTING_OSD_MAIN_VOLTAGE_DECIMALS_DEFAULT, - .rtc_time_show_seconds = SETTING_OSD_RTC_TIME_SHOW_SECONDS_DEFAULT, #ifdef USE_WIND_ESTIMATOR .estimations_wind_compensation = SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_DEFAULT, diff --git a/src/main/io/osd.h b/src/main/io/osd.h index d08ee95956..8f4e4d4bf9 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -375,7 +375,6 @@ typedef struct osdConfig_s { uint8_t crsf_lq_format; uint8_t sidebar_height; // sidebar height in rows, 0 turns off sidebars leaving only level indicator arrows uint8_t telemetry; // use telemetry on displayed pixel line 0 - bool rtc_time_show_seconds; // show seconds in current time display when enabled } osdConfig_t; From 6f7358b941bca9875f15647c306c7459a40b4043 Mon Sep 17 00:00:00 2001 From: David Brooks Date: Thu, 27 May 2021 16:33:57 +0100 Subject: [PATCH 015/102] Added MATEKF722SE_8MOTOR --- .../target/MATEKF722SE_8MOTOR/CMakeLists.txt | 1 + src/main/target/MATEKF722SE_8MOTOR/config.c | 30 +++ src/main/target/MATEKF722SE_8MOTOR/target.c | 47 +++++ src/main/target/MATEKF722SE_8MOTOR/target.h | 193 ++++++++++++++++++ 4 files changed, 271 insertions(+) create mode 100644 src/main/target/MATEKF722SE_8MOTOR/CMakeLists.txt create mode 100644 src/main/target/MATEKF722SE_8MOTOR/config.c create mode 100644 src/main/target/MATEKF722SE_8MOTOR/target.c create mode 100644 src/main/target/MATEKF722SE_8MOTOR/target.h diff --git a/src/main/target/MATEKF722SE_8MOTOR/CMakeLists.txt b/src/main/target/MATEKF722SE_8MOTOR/CMakeLists.txt new file mode 100644 index 0000000000..32634b4a8b --- /dev/null +++ b/src/main/target/MATEKF722SE_8MOTOR/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(MATEKF722SE_8MOTOR) diff --git a/src/main/target/MATEKF722SE_8MOTOR/config.c b/src/main/target/MATEKF722SE_8MOTOR/config.c new file mode 100644 index 0000000000..7e47e5bf6b --- /dev/null +++ b/src/main/target/MATEKF722SE_8MOTOR/config.c @@ -0,0 +1,30 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" + +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; +} diff --git a/src/main/target/MATEKF722SE_8MOTOR/target.c b/src/main/target/MATEKF722SE_8MOTOR/target.c new file mode 100644 index 0000000000..9f028655b5 --- /dev/null +++ b/src/main/target/MATEKF722SE_8MOTOR/target.c @@ -0,0 +1,47 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/pinio.h" +#include "drivers/sensor.h" + +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); + +const timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 UP1-2 D(1, 4, 5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 UP1-2 D(1, 5, 5) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 UP1-2 D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 UP1-2 D(1, 2, 5) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 UP1-7 D(1, 5, 3) - clash with S2 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 UP1-7 D(1, 6, 3) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 UP1-6 D(1, 0, 2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 UP1-6 D(1, 3, 2) + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // LED D(2, 6, 0) + DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM, RX2 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_PWM, 0, 0), // TX2 & softserial1 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/MATEKF722SE_8MOTOR/target.h b/src/main/target/MATEKF722SE_8MOTOR/target.h new file mode 100644 index 0000000000..f615018dce --- /dev/null +++ b/src/main/target/MATEKF722SE_8MOTOR/target.h @@ -0,0 +1,193 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "MF7S" +#define USBD_PRODUCT_STRING "MatekF722SE" + +#define LED0 PA14 //Blue SWCLK +#define LED1 PA13 //Green SWDIO + +#define BEEPER PC13 +#define BEEPER_INVERTED + +// *************** SPI1 Gyro & ACC ******************* +#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_DUAL_GYRO + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW180_DEG_FLIP +#define MPU6000_CS_PIN PB2 +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_EXTI_PIN PC4 + +#define USE_IMU_MPU6500 +#define IMU_MPU6500_ALIGN CW90_DEG +#define MPU6500_CS_PIN PC15 +#define MPU6500_SPI_BUS BUS_SPI1 +#define MPU6500_EXTI_PIN PC3 + + + +#define USE_EXTI +#define USE_MPU_DATA_READY_SIGNAL + +// *************** I2C /Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_DPS310 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_AK8975 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +#define TEMPERATURE_I2C_BUS BUS_I2C1 + +#define PITOT_I2C_BUS BUS_I2C1 + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS BUS_I2C1 + +// *************** SPI2 OSD *********************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +// *************** SPI3 SD BLACKBOX******************* +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 + +#if defined(MATEKF722MINI) +# define USE_FLASHFS +# define USE_FLASH_M25P16 +# define M25P16_SPI_BUS BUS_SPI3 +# define M25P16_CS_PIN PD2 +# define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#else +# define USE_SDCARD +# define USE_SDCARD_SPI +# define SDCARD_SPI_BUS BUS_SPI3 +# define SDCARD_CS_PIN PD2 +# define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT +#endif + +// *************** UART ***************************** +#define USE_VCP +#define USB_DETECT_PIN PC14 +#define USE_USB_DETECT + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define USE_UART3 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define USE_SOFTSERIAL1 +#define SOFTSERIAL_1_TX_PIN PA2 +#define SOFTSERIAL_1_RX_PIN PA2 + +#define SERIAL_PORT_COUNT 7 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART2 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 + +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC0 +#define ADC_CHANNEL_4_PIN PA4 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 +#define AIRSPEED_ADC_CHANNEL ADC_CHN_4 + +// *************** PINIO *************************** +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC8 // VTX power switcher +#define PINIO2_PIN PC9 // 2xCamera switcher + +// *************** LEDSTRIP ************************ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) +#define CURRENT_METER_SCALE 179 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff + +#define MAX_PWM_OUTPUT_PORTS 8 +#define USE_DSHOT +#define USE_SERIALSHOT +#define USE_ESC_SENSOR + +#define BNO055_I2C_BUS BUS_I2C1 \ No newline at end of file From d3adfd0b281309c43feb08fe49d464c632d923be Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Fri, 28 May 2021 11:35:25 +0200 Subject: [PATCH 016/102] Show message to switch to acro when autotune is enabled in manual mode --- src/main/io/osd.c | 3 +++ src/main/io/osd.h | 1 + 2 files changed, 4 insertions(+) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 0e6f9738b3..33a121e55e 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -3874,6 +3874,9 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter } if (IS_RC_MODE_ACTIVE(BOXAUTOTUNE)) { messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTUNE); + if (FLIGHT_MODE(MANUAL_MODE)) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTUNE_ACRO); + } } if (FLIGHT_MODE(HEADFREE_MODE)) { messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_HEADFREE); diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 38557f0cb5..b977c0cc1e 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -98,6 +98,7 @@ #define OSD_MSG_ALTITUDE_HOLD "(ALTITUDE HOLD)" #define OSD_MSG_AUTOTRIM "(AUTOTRIM)" #define OSD_MSG_AUTOTUNE "(AUTOTUNE)" +#define OSD_MSG_AUTOTUNE_ACRO "SWITCH TO ACRO" #define OSD_MSG_HEADFREE "(HEADFREE)" #define OSD_MSG_UNABLE_ARM "UNABLE TO ARM" From c6ebdd963e66916f72a1e9b0fb1ee0033c8d3807 Mon Sep 17 00:00:00 2001 From: bkleiner Date: Sat, 29 May 2021 15:33:53 +0200 Subject: [PATCH 017/102] h7: enable uart RCC --- src/main/drivers/serial_uart_stm32h7xx.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/drivers/serial_uart_stm32h7xx.c b/src/main/drivers/serial_uart_stm32h7xx.c index 2ad67b583a..0e22206bed 100644 --- a/src/main/drivers/serial_uart_stm32h7xx.c +++ b/src/main/drivers/serial_uart_stm32h7xx.c @@ -331,6 +331,10 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_t mode, s->Handle.Instance = uart->dev; + if (uart->rcc) { + RCC_ClockCmd(uart->rcc, ENABLE); + } + IO_t tx = IOGetByTag(uart->tx); IO_t rx = IOGetByTag(uart->rx); From 94a53dc498b086a43ecd2dd449ad80240825a755 Mon Sep 17 00:00:00 2001 From: bkleiner Date: Mon, 3 May 2021 20:27:46 +0200 Subject: [PATCH 018/102] h7: enable DPS310 --- src/main/target/MATEKH743/target.h | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/target/MATEKH743/target.h b/src/main/target/MATEKH743/target.h index cc3409c8f5..7390760331 100644 --- a/src/main/target/MATEKH743/target.h +++ b/src/main/target/MATEKH743/target.h @@ -146,6 +146,7 @@ #define BARO_I2C_BUS BUS_I2C2 #define USE_BARO_BMP280 #define USE_BARO_MS5611 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 From 576845abf9bc3d222206b8cb5f6f138b6c382a5e Mon Sep 17 00:00:00 2001 From: David Brooks Date: Sat, 29 May 2021 19:45:41 +0100 Subject: [PATCH 019/102] Removed MATEKF722SE_8MOTOR target and replaced with MATEKF722SE sub target --- src/main/target/MATEKF722SE/CMakeLists.txt | 1 + src/main/target/MATEKF722SE/target.c | 5 + .../target/MATEKF722SE_8MOTOR/CMakeLists.txt | 1 - src/main/target/MATEKF722SE_8MOTOR/config.c | 30 --- src/main/target/MATEKF722SE_8MOTOR/target.c | 47 ----- src/main/target/MATEKF722SE_8MOTOR/target.h | 193 ------------------ 6 files changed, 6 insertions(+), 271 deletions(-) delete mode 100644 src/main/target/MATEKF722SE_8MOTOR/CMakeLists.txt delete mode 100644 src/main/target/MATEKF722SE_8MOTOR/config.c delete mode 100644 src/main/target/MATEKF722SE_8MOTOR/target.c delete mode 100644 src/main/target/MATEKF722SE_8MOTOR/target.h diff --git a/src/main/target/MATEKF722SE/CMakeLists.txt b/src/main/target/MATEKF722SE/CMakeLists.txt index a541da229f..75aa91ec0a 100644 --- a/src/main/target/MATEKF722SE/CMakeLists.txt +++ b/src/main/target/MATEKF722SE/CMakeLists.txt @@ -1,2 +1,3 @@ target_stm32f722xe(MATEKF722SE) target_stm32f722xe(MATEKF722MINI) +target_stm32f722xe(MATEKF722SE_8MOTOR) diff --git a/src/main/target/MATEKF722SE/target.c b/src/main/target/MATEKF722SE/target.c index 2c4170a1ce..36d49b8cfd 100644 --- a/src/main/target/MATEKF722SE/target.c +++ b/src/main/target/MATEKF722SE/target.c @@ -38,8 +38,13 @@ const timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 UP1-7 D(1, 5, 3) - clash with S2 DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 UP1-7 D(1, 6, 3) +#if (defined(MATEKF722SE_8MOTOR)) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 UP1-6 D(1, 0, 2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 UP1-6 D(1, 3, 2) +#else DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S7 UP1-6 D(1, 0, 2) DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S8 UP1-6 D(1, 3, 2) +#endif DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // LED D(2, 6, 0) diff --git a/src/main/target/MATEKF722SE_8MOTOR/CMakeLists.txt b/src/main/target/MATEKF722SE_8MOTOR/CMakeLists.txt deleted file mode 100644 index 32634b4a8b..0000000000 --- a/src/main/target/MATEKF722SE_8MOTOR/CMakeLists.txt +++ /dev/null @@ -1 +0,0 @@ -target_stm32f722xe(MATEKF722SE_8MOTOR) diff --git a/src/main/target/MATEKF722SE_8MOTOR/config.c b/src/main/target/MATEKF722SE_8MOTOR/config.c deleted file mode 100644 index 7e47e5bf6b..0000000000 --- a/src/main/target/MATEKF722SE_8MOTOR/config.c +++ /dev/null @@ -1,30 +0,0 @@ -/* - * This file is part of Cleanflight. - * - * Cleanflight is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * Cleanflight is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with Cleanflight. If not, see . - */ - -#include - -#include "platform.h" - -#include "fc/fc_msp_box.h" - -#include "io/piniobox.h" - -void targetConfiguration(void) -{ - pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; - pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; -} diff --git a/src/main/target/MATEKF722SE_8MOTOR/target.c b/src/main/target/MATEKF722SE_8MOTOR/target.c deleted file mode 100644 index 9f028655b5..0000000000 --- a/src/main/target/MATEKF722SE_8MOTOR/target.c +++ /dev/null @@ -1,47 +0,0 @@ -/* - * This file is part of INAV. - * - * INAV is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * INAV is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with INAV. If not, see . - */ - -#include - -#include "platform.h" - -#include "drivers/bus.h" -#include "drivers/io.h" -#include "drivers/pwm_mapping.h" -#include "drivers/timer.h" -#include "drivers/pinio.h" -#include "drivers/sensor.h" - -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); - -const timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 UP1-2 D(1, 4, 5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 UP1-2 D(1, 5, 5) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 UP1-2 D(1, 7, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 UP1-2 D(1, 2, 5) - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 UP1-7 D(1, 5, 3) - clash with S2 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 UP1-7 D(1, 6, 3) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 UP1-6 D(1, 0, 2) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 UP1-6 D(1, 3, 2) - - DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // LED D(2, 6, 0) - DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM, RX2 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_PWM, 0, 0), // TX2 & softserial1 -}; - -const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/MATEKF722SE_8MOTOR/target.h b/src/main/target/MATEKF722SE_8MOTOR/target.h deleted file mode 100644 index f615018dce..0000000000 --- a/src/main/target/MATEKF722SE_8MOTOR/target.h +++ /dev/null @@ -1,193 +0,0 @@ -/* - * This file is part of INAV. - * - * INAV is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * INAV is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with INAV. If not, see . - */ - - -#pragma once - -#define TARGET_BOARD_IDENTIFIER "MF7S" -#define USBD_PRODUCT_STRING "MatekF722SE" - -#define LED0 PA14 //Blue SWCLK -#define LED1 PA13 //Green SWDIO - -#define BEEPER PC13 -#define BEEPER_INVERTED - -// *************** SPI1 Gyro & ACC ******************* -#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS - -#define USE_SPI -#define USE_SPI_DEVICE_1 -#define SPI1_SCK_PIN PA5 -#define SPI1_MISO_PIN PA6 -#define SPI1_MOSI_PIN PA7 - -#define USE_DUAL_GYRO - -#define USE_IMU_MPU6000 -#define IMU_MPU6000_ALIGN CW180_DEG_FLIP -#define MPU6000_CS_PIN PB2 -#define MPU6000_SPI_BUS BUS_SPI1 -#define MPU6000_EXTI_PIN PC4 - -#define USE_IMU_MPU6500 -#define IMU_MPU6500_ALIGN CW90_DEG -#define MPU6500_CS_PIN PC15 -#define MPU6500_SPI_BUS BUS_SPI1 -#define MPU6500_EXTI_PIN PC3 - - - -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL - -// *************** I2C /Baro/Mag ********************* -#define USE_I2C -#define USE_I2C_DEVICE_1 -#define I2C1_SCL PB8 -#define I2C1_SDA PB9 - -#define USE_BARO -#define BARO_I2C_BUS BUS_I2C1 -#define USE_BARO_BMP280 -#define USE_BARO_MS5611 -#define USE_BARO_DPS310 - -#define USE_MAG -#define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL - -#define TEMPERATURE_I2C_BUS BUS_I2C1 - -#define PITOT_I2C_BUS BUS_I2C1 - -#define USE_RANGEFINDER -#define RANGEFINDER_I2C_BUS BUS_I2C1 - -// *************** SPI2 OSD *********************** -#define USE_SPI_DEVICE_2 -#define SPI2_SCK_PIN PB13 -#define SPI2_MISO_PIN PB14 -#define SPI2_MOSI_PIN PB15 - -#define USE_OSD -#define USE_MAX7456 -#define MAX7456_SPI_BUS BUS_SPI2 -#define MAX7456_CS_PIN PB12 - -// *************** SPI3 SD BLACKBOX******************* -#define USE_SPI_DEVICE_3 -#define SPI3_SCK_PIN PC10 -#define SPI3_MISO_PIN PC11 -#define SPI3_MOSI_PIN PC12 - -#if defined(MATEKF722MINI) -# define USE_FLASHFS -# define USE_FLASH_M25P16 -# define M25P16_SPI_BUS BUS_SPI3 -# define M25P16_CS_PIN PD2 -# define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT -#else -# define USE_SDCARD -# define USE_SDCARD_SPI -# define SDCARD_SPI_BUS BUS_SPI3 -# define SDCARD_CS_PIN PD2 -# define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#endif - -// *************** UART ***************************** -#define USE_VCP -#define USB_DETECT_PIN PC14 -#define USE_USB_DETECT - -#define USE_UART1 -#define UART1_TX_PIN PA9 -#define UART1_RX_PIN PA10 - -#define USE_UART2 -#define UART2_TX_PIN PA2 -#define UART2_RX_PIN PA3 - -#define USE_UART3 -#define UART3_TX_PIN PB10 -#define UART3_RX_PIN PB11 - -#define USE_UART4 -#define UART4_TX_PIN PA0 -#define UART4_RX_PIN PA1 - -#define USE_UART6 -#define UART6_TX_PIN PC6 -#define UART6_RX_PIN PC7 - -#define USE_SOFTSERIAL1 -#define SOFTSERIAL_1_TX_PIN PA2 -#define SOFTSERIAL_1_RX_PIN PA2 - -#define SERIAL_PORT_COUNT 7 - -#define DEFAULT_RX_TYPE RX_TYPE_SERIAL -#define SERIALRX_PROVIDER SERIALRX_SBUS -#define SERIALRX_UART SERIAL_PORT_USART2 - -// *************** ADC ***************************** -#define USE_ADC -#define ADC_INSTANCE ADC1 -#define ADC1_DMA_STREAM DMA2_Stream0 - -#define ADC_CHANNEL_1_PIN PC2 -#define ADC_CHANNEL_2_PIN PC1 -#define ADC_CHANNEL_3_PIN PC0 -#define ADC_CHANNEL_4_PIN PA4 - -#define VBAT_ADC_CHANNEL ADC_CHN_1 -#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 -#define RSSI_ADC_CHANNEL ADC_CHN_3 -#define AIRSPEED_ADC_CHANNEL ADC_CHN_4 - -// *************** PINIO *************************** -#define USE_PINIO -#define USE_PINIOBOX -#define PINIO1_PIN PC8 // VTX power switcher -#define PINIO2_PIN PC9 // 2xCamera switcher - -// *************** LEDSTRIP ************************ -#define USE_LED_STRIP -#define WS2811_PIN PA8 - -#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) -#define CURRENT_METER_SCALE 179 - -#define USE_SERIAL_4WAY_BLHELI_INTERFACE - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff - -#define MAX_PWM_OUTPUT_PORTS 8 -#define USE_DSHOT -#define USE_SERIALSHOT -#define USE_ESC_SENSOR - -#define BNO055_I2C_BUS BUS_I2C1 \ No newline at end of file From 87c8205f69a799ebbf072e66a601800a4f7a4c1a Mon Sep 17 00:00:00 2001 From: bkleiner Date: Sat, 29 May 2021 20:54:42 +0200 Subject: [PATCH 020/102] import dma impl for h7 --- cmake/stm32h7.cmake | 2 +- src/main/drivers/dma_stm32h7xx.c | 128 +++++++++++++++++++++++++++++++ 2 files changed, 129 insertions(+), 1 deletion(-) create mode 100644 src/main/drivers/dma_stm32h7xx.c diff --git a/cmake/stm32h7.cmake b/cmake/stm32h7.cmake index 3642b23d0d..2cddbbfb4d 100644 --- a/cmake/stm32h7.cmake +++ b/cmake/stm32h7.cmake @@ -145,7 +145,7 @@ main_sources(STM32H7_SRC # drivers/adc_stm32h7xx.c drivers/bus_i2c_hal.c -# drivers/dma_stm32h7xx.c + drivers/dma_stm32h7xx.c drivers/bus_spi_hal.c drivers/memprot.h drivers/memprot_hal.c diff --git a/src/main/drivers/dma_stm32h7xx.c b/src/main/drivers/dma_stm32h7xx.c new file mode 100644 index 0000000000..eef3d0c28b --- /dev/null +++ b/src/main/drivers/dma_stm32h7xx.c @@ -0,0 +1,128 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include +#include +#include + +#include + +#include "common/utils.h" +#include "drivers/nvic.h" +#include "drivers/dma.h" +#include "drivers/rcc.h" + +/* + * DMA descriptors. + */ +static dmaChannelDescriptor_t dmaDescriptors[] = { + [0] = DEFINE_DMA_CHANNEL(1, 0, 0), // DMA1_ST0 + [1] = DEFINE_DMA_CHANNEL(1, 1, 6), // DMA1_ST1 + [2] = DEFINE_DMA_CHANNEL(1, 2, 16), // DMA1_ST2 + [3] = DEFINE_DMA_CHANNEL(1, 3, 22), // DMA1_ST3 + [4] = DEFINE_DMA_CHANNEL(1, 4, 32), // DMA1_ST4 + [5] = DEFINE_DMA_CHANNEL(1, 5, 38), // DMA1_ST5 + [6] = DEFINE_DMA_CHANNEL(1, 6, 48), // DMA1_ST6 + [7] = DEFINE_DMA_CHANNEL(1, 7, 54), // DMA1_ST7 + + [8] = DEFINE_DMA_CHANNEL(2, 0, 0), // DMA2_ST0 + [9] = DEFINE_DMA_CHANNEL(2, 1, 6), // DMA2_ST1 + [10] = DEFINE_DMA_CHANNEL(2, 2, 16), // DMA2_ST2 + [11] = DEFINE_DMA_CHANNEL(2, 3, 22), // DMA2_ST3 + [12] = DEFINE_DMA_CHANNEL(2, 4, 32), // DMA2_ST4 + [13] = DEFINE_DMA_CHANNEL(2, 5, 38), // DMA2_ST5 + [14] = DEFINE_DMA_CHANNEL(2, 6, 48), // DMA2_ST6 + [15] = DEFINE_DMA_CHANNEL(2, 7, 54), // DMA2_ST7 +}; + +/* + * DMA IRQ Handlers + */ +DEFINE_DMA_IRQ_HANDLER(1, 0, 0) // DMA1_ST0 +DEFINE_DMA_IRQ_HANDLER(1, 1, 1) // DMA1_ST1 +DEFINE_DMA_IRQ_HANDLER(1, 2, 2) // DMA1_ST2 +DEFINE_DMA_IRQ_HANDLER(1, 3, 3) // DMA1_ST3 +DEFINE_DMA_IRQ_HANDLER(1, 4, 4) // DMA1_ST4 +DEFINE_DMA_IRQ_HANDLER(1, 5, 5) // DMA1_ST5 +DEFINE_DMA_IRQ_HANDLER(1, 6, 6) // DMA1_ST6 +DEFINE_DMA_IRQ_HANDLER(1, 7, 7) // DMA1_ST7 +DEFINE_DMA_IRQ_HANDLER(2, 0, 8) // DMA2_ST0 +DEFINE_DMA_IRQ_HANDLER(2, 1, 9) // DMA2_ST1 +DEFINE_DMA_IRQ_HANDLER(2, 2, 10) // DMA2_ST2 +DEFINE_DMA_IRQ_HANDLER(2, 3, 11) // DMA2_ST3 +DEFINE_DMA_IRQ_HANDLER(2, 4, 12) // DMA2_ST4 +DEFINE_DMA_IRQ_HANDLER(2, 5, 13) // DMA2_ST5 +DEFINE_DMA_IRQ_HANDLER(2, 6, 14) // DMA2_ST6 +DEFINE_DMA_IRQ_HANDLER(2, 7, 15) // DMA2_ST7 + +DMA_t dmaGetByTag(dmaTag_t tag) +{ + for (unsigned i = 0; i < ARRAYLEN(dmaDescriptors); i++) { + if (DMATAG_GET_DMA(dmaDescriptors[i].tag) == DMATAG_GET_DMA(tag) && DMATAG_GET_STREAM(dmaDescriptors[i].tag) == DMATAG_GET_STREAM(tag)) { + return (DMA_t)&dmaDescriptors[i]; + } + } + + return (DMA_t) NULL; +} + +void dmaEnableClock(DMA_t dma) +{ + if (dma->dma == DMA1) { + RCC_ClockCmd(RCC_AHB1(DMA1), ENABLE); + } + else { + RCC_ClockCmd(RCC_AHB1(DMA2), ENABLE); + } +} + +resourceOwner_e dmaGetOwner(DMA_t dma) +{ + return dma->owner; +} + +void dmaInit(DMA_t dma, resourceOwner_e owner, uint8_t resourceIndex) +{ + dmaEnableClock(dma); + dma->owner = owner; + dma->resourceIndex = resourceIndex; +} + +void dmaSetHandler(DMA_t dma, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam) +{ + dmaEnableClock(dma); + + dma->irqHandlerCallback = callback; + dma->userParam = userParam; + + HAL_NVIC_SetPriority(dma->irqNumber, priority, 0); + HAL_NVIC_EnableIRQ(dma->irqNumber); +} + +DMA_t dmaGetByRef(const DMA_Stream_TypeDef* ref) +{ + for (unsigned i = 0; i < (sizeof(dmaDescriptors) / sizeof(dmaDescriptors[0])); i++) { + if (ref == dmaDescriptors[i].ref) { + return &dmaDescriptors[i]; + } + } + + return NULL; +} From 40a9dd55cb82f611e4b9a069f63b3906f7f9ee03 Mon Sep 17 00:00:00 2001 From: bkleiner Date: Sat, 29 May 2021 21:06:47 +0200 Subject: [PATCH 021/102] MATEKH743: tidy target, enable dshot related options --- src/main/target/MATEKH743/target.h | 32 ++++++++++-------------------- 1 file changed, 11 insertions(+), 21 deletions(-) diff --git a/src/main/target/MATEKH743/target.h b/src/main/target/MATEKH743/target.h index cc3409c8f5..ab2e5fc633 100644 --- a/src/main/target/MATEKH743/target.h +++ b/src/main/target/MATEKH743/target.h @@ -27,9 +27,6 @@ #define BEEPER PA15 #define BEEPER_INVERTED - - - // *************** UART ***************************** #define USE_VCP @@ -67,19 +64,6 @@ #define SERIALRX_PROVIDER SERIALRX_SBUS #define SERIALRX_UART SERIAL_PORT_USART6 - - -#define MAX_PWM_OUTPUT_PORTS 15 - - - - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff - // *************** IMU generic *********************** #define USE_DUAL_GYRO #define USE_TARGET_IMU_HARDWARE_DESCRIPTORS @@ -163,7 +147,18 @@ #define USE_RANGEFINDER #define RANGEFINDER_I2C_BUS BUS_I2C2 +#define USE_SERIAL_4WAY_BLHELI_INTERFACE +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff + +#define MAX_PWM_OUTPUT_PORTS 15 +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIALSHOT #if 0 #define USE_EXTI @@ -196,9 +191,4 @@ #define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) #define CURRENT_METER_SCALE 250 -#define USE_SERIAL_4WAY_BLHELI_INTERFACE - -#define USE_DSHOT -#define USE_ESC_SENSOR -#define USE_SERIALSHOT #endif \ No newline at end of file From 471235288930a8bc3bb204f578f3d605d242a526 Mon Sep 17 00:00:00 2001 From: bkleiner Date: Sun, 30 May 2021 01:18:27 +0200 Subject: [PATCH 022/102] move adcChannel to 32bit h7 indexes them differently. --- src/main/drivers/adc.c | 2 +- src/main/drivers/adc_impl.h | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/drivers/adc.c b/src/main/drivers/adc.c index e45ffce32f..21b0975937 100644 --- a/src/main/drivers/adc.c +++ b/src/main/drivers/adc.c @@ -57,7 +57,7 @@ static int adcFunctionMap[ADC_FUNCTION_COUNT]; adc_config_t adcConfig[ADC_CHN_COUNT]; // index 0 is dummy for ADC_CHN_NONE volatile uint16_t adcValues[ADCDEV_COUNT][ADC_CHN_COUNT * ADC_AVERAGE_N_SAMPLES]; -uint8_t adcChannelByTag(ioTag_t ioTag) +uint32_t adcChannelByTag(ioTag_t ioTag) { for (uint8_t i = 0; i < ARRAYLEN(adcTagMap); i++) { if (ioTag == adcTagMap[i].tag) diff --git a/src/main/drivers/adc_impl.h b/src/main/drivers/adc_impl.h index 901122daa9..2546cfeac4 100644 --- a/src/main/drivers/adc_impl.h +++ b/src/main/drivers/adc_impl.h @@ -46,7 +46,7 @@ typedef enum ADCDevice { typedef struct adcTagMap_s { ioTag_t tag; - uint8_t channel; + uint32_t channel; } adcTagMap_t; typedef struct adcDevice_s { @@ -70,7 +70,7 @@ typedef struct adcDevice_s { typedef struct adc_config_s { ioTag_t tag; ADCDevice adcDevice; - uint8_t adcChannel; // ADC1_INxx channel number + uint32_t adcChannel; // ADC1_INxx channel number uint8_t dmaIndex; // index into DMA buffer in case of sparse channels bool enabled; uint8_t sampleTime; @@ -82,4 +82,4 @@ extern volatile uint16_t adcValues[ADCDEV_COUNT][ADC_CHN_COUNT * ADC_AVERAGE_N_S void adcHardwareInit(drv_adc_config_t *init); ADCDevice adcDeviceByInstance(ADC_TypeDef *instance); -uint8_t adcChannelByTag(ioTag_t ioTag); +uint32_t adcChannelByTag(ioTag_t ioTag); From d42fb4314e437795aa649fffc9b14803eb372fec Mon Sep 17 00:00:00 2001 From: bkleiner Date: Sun, 30 May 2021 01:23:03 +0200 Subject: [PATCH 023/102] h7: add adc implementation --- cmake/stm32h7.cmake | 2 +- src/main/drivers/adc.c | 2 +- src/main/drivers/adc_impl.h | 16 +- src/main/drivers/adc_stm32h7xx.c | 230 +++++++++++++++++++++++++++++ src/main/target/MATEKH743/target.h | 33 +++-- 5 files changed, 262 insertions(+), 21 deletions(-) create mode 100644 src/main/drivers/adc_stm32h7xx.c diff --git a/cmake/stm32h7.cmake b/cmake/stm32h7.cmake index 2cddbbfb4d..758f9dca25 100644 --- a/cmake/stm32h7.cmake +++ b/cmake/stm32h7.cmake @@ -143,7 +143,7 @@ main_sources(STM32H7_SRC config/config_streamer_stm32h7.c -# drivers/adc_stm32h7xx.c + drivers/adc_stm32h7xx.c drivers/bus_i2c_hal.c drivers/dma_stm32h7xx.c drivers/bus_spi_hal.c diff --git a/src/main/drivers/adc.c b/src/main/drivers/adc.c index 21b0975937..573c1e69b7 100644 --- a/src/main/drivers/adc.c +++ b/src/main/drivers/adc.c @@ -55,7 +55,7 @@ static uint8_t activeChannelCount[ADCDEV_COUNT] = {0}; static int adcFunctionMap[ADC_FUNCTION_COUNT]; adc_config_t adcConfig[ADC_CHN_COUNT]; // index 0 is dummy for ADC_CHN_NONE -volatile uint16_t adcValues[ADCDEV_COUNT][ADC_CHN_COUNT * ADC_AVERAGE_N_SAMPLES]; +volatile ADC_VALUES_ALIGNMENT(uint16_t adcValues[ADCDEV_COUNT][ADC_CHN_COUNT * ADC_AVERAGE_N_SAMPLES]); uint32_t adcChannelByTag(ioTag_t ioTag) { diff --git a/src/main/drivers/adc_impl.h b/src/main/drivers/adc_impl.h index 2546cfeac4..41f2635ce9 100644 --- a/src/main/drivers/adc_impl.h +++ b/src/main/drivers/adc_impl.h @@ -22,19 +22,27 @@ #if defined(STM32F4) || defined(STM32F7) #define ADC_TAG_MAP_COUNT 16 +#elif defined(STM32H7) +#define ADC_TAG_MAP_COUNT 28 #elif defined(STM32F3) #define ADC_TAG_MAP_COUNT 39 #else #define ADC_TAG_MAP_COUNT 10 #endif +#if defined(STM32H7) +#define ADC_VALUES_ALIGNMENT(def) def __attribute__ ((aligned (32))) +#else +#define ADC_VALUES_ALIGNMENT(def) def +#endif + typedef enum ADCDevice { ADCINVALID = -1, ADCDEV_1 = 0, #if defined(STM32F3) ADCDEV_2, ADCDEV_MAX = ADCDEV_2, -#elif defined(STM32F4) || defined(STM32F7) +#elif defined(STM32F4) || defined(STM32F7) || defined(STM32H7) ADCDEV_2, ADCDEV_3, ADCDEV_MAX = ADCDEV_3, @@ -53,13 +61,13 @@ typedef struct adcDevice_s { ADC_TypeDef* ADCx; rccPeriphTag_t rccADC; rccPeriphTag_t rccDMA; -#if defined(STM32F4) || defined(STM32F7) +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) DMA_Stream_TypeDef* DMAy_Streamx; uint32_t channel; #else DMA_Channel_TypeDef* DMAy_Channelx; #endif -#if defined(STM32F7) +#if defined(STM32F7) || defined(STM32H7) ADC_HandleTypeDef ADCHandle; DMA_HandleTypeDef DmaHandle; #endif @@ -78,7 +86,7 @@ typedef struct adc_config_s { extern const adcTagMap_t adcTagMap[ADC_TAG_MAP_COUNT]; extern adc_config_t adcConfig[ADC_CHN_COUNT]; -extern volatile uint16_t adcValues[ADCDEV_COUNT][ADC_CHN_COUNT * ADC_AVERAGE_N_SAMPLES]; +extern volatile ADC_VALUES_ALIGNMENT(uint16_t adcValues[ADCDEV_COUNT][ADC_CHN_COUNT * ADC_AVERAGE_N_SAMPLES]); void adcHardwareInit(drv_adc_config_t *init); ADCDevice adcDeviceByInstance(ADC_TypeDef *instance); diff --git a/src/main/drivers/adc_stm32h7xx.c b/src/main/drivers/adc_stm32h7xx.c new file mode 100644 index 0000000000..be9f302ff1 --- /dev/null +++ b/src/main/drivers/adc_stm32h7xx.c @@ -0,0 +1,230 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include +#include +#include + +#include "platform.h" + +#include "build/debug.h" + +#include "platform.h" +#include "drivers/time.h" + +#include "drivers/io.h" +#include "io_impl.h" +#include "rcc.h" +#include "dma.h" + +#include "drivers/sensor.h" +#include "drivers/accgyro/accgyro.h" + +#include "adc.h" +#include "adc_impl.h" + + +static adcDevice_t adcHardware[ADCDEV_COUNT] = { + { + .ADCx = ADC1, + .rccADC = RCC_AHB1(ADC12), + .rccDMA = RCC_AHB1(DMA2), + .DMAy_Streamx = DMA2_Stream0, + .channel = DMA_REQUEST_ADC1, + .enabled = false, + .usedChannelCount = 0 + }, + /* currently not used + { + .ADCx = ADC2, + .rccADC = RCC_AHB1(ADC12), + .rccDMA = RCC_AHB1(DMA2), + .DMAy_Streamx = DMA2_Stream1, + .channel = DMA_REQUEST_ADC2, + .enabled = false, + .usedChannelCount = 0 + } + */ +}; + +adcDevice_t adcDevice[ADCDEV_COUNT]; + +/* note these could be packed up for saving space */ +const adcTagMap_t adcTagMap[] = { + { DEFIO_TAG_E__PC0, ADC_CHANNEL_10 }, + { DEFIO_TAG_E__PC1, ADC_CHANNEL_11 }, + { DEFIO_TAG_E__PC2, ADC_CHANNEL_0 }, + { DEFIO_TAG_E__PC3, ADC_CHANNEL_1 }, + { DEFIO_TAG_E__PC4, ADC_CHANNEL_4 }, + { DEFIO_TAG_E__PC5, ADC_CHANNEL_8 }, + { DEFIO_TAG_E__PB0, ADC_CHANNEL_9 }, + { DEFIO_TAG_E__PB1, ADC_CHANNEL_5 }, + { DEFIO_TAG_E__PA0, ADC_CHANNEL_16 }, + { DEFIO_TAG_E__PA1, ADC_CHANNEL_17 }, + { DEFIO_TAG_E__PA2, ADC_CHANNEL_14 }, + { DEFIO_TAG_E__PA3, ADC_CHANNEL_15 }, + { DEFIO_TAG_E__PA4, ADC_CHANNEL_18 }, + { DEFIO_TAG_E__PA5, ADC_CHANNEL_19 }, + { DEFIO_TAG_E__PA6, ADC_CHANNEL_3 }, + { DEFIO_TAG_E__PA7, ADC_CHANNEL_7 }, +}; + +// Translate rank number x to ADC_REGULAR_RANK_x (Note that array index is 0-origin) +static const uint32_t adcRegularRankMap[] = { + ADC_REGULAR_RANK_1, + ADC_REGULAR_RANK_2, + ADC_REGULAR_RANK_3, + ADC_REGULAR_RANK_4, + ADC_REGULAR_RANK_5, + ADC_REGULAR_RANK_6, + ADC_REGULAR_RANK_7, + ADC_REGULAR_RANK_8, + ADC_REGULAR_RANK_9, + ADC_REGULAR_RANK_10, + ADC_REGULAR_RANK_11, + ADC_REGULAR_RANK_12, + ADC_REGULAR_RANK_13, + ADC_REGULAR_RANK_14, + ADC_REGULAR_RANK_15, + ADC_REGULAR_RANK_16, +}; + +ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) +{ + if (instance == ADC1) + return ADCDEV_1; + + if (instance == ADC2) + return ADCDEV_2; + + return ADCINVALID; +} + +static void adcInstanceInit(ADCDevice adcDevice) +{ + adcDevice_t * adc = &adcHardware[adcDevice]; + + RCC_ClockCmd(adc->rccDMA, ENABLE); + RCC_ClockCmd(adc->rccADC, ENABLE); + + adc->ADCHandle.Instance = adc->ADCx; + + adc->ADCHandle.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4; + adc->ADCHandle.Init.Resolution = ADC_RESOLUTION_12B; + adc->ADCHandle.Init.ContinuousConvMode = ENABLE; + adc->ADCHandle.Init.ExternalTrigConv = ADC_EXTERNALTRIG_T1_CC1; + adc->ADCHandle.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE; + adc->ADCHandle.Init.NbrOfConversion = adc->usedChannelCount; + adc->ADCHandle.Init.ScanConvMode = adc->usedChannelCount > 1 ? ENABLE : DISABLE; // 1=scan more that one channel in group + adc->ADCHandle.Init.DiscontinuousConvMode = DISABLE; + adc->ADCHandle.Init.NbrOfDiscConversion = 0; + adc->ADCHandle.Init.EOCSelection = DISABLE; + adc->ADCHandle.Init.LowPowerAutoWait = DISABLE; + + // Enable circular DMA. + adc->ADCHandle.Init.ConversionDataManagement = ADC_CONVERSIONDATA_DMA_CIRCULAR; + + adc->ADCHandle.Init.Overrun = ADC_OVR_DATA_OVERWRITTEN; + adc->ADCHandle.Init.OversamplingMode = DISABLE; + + if (HAL_ADC_Init(&adc->ADCHandle) != HAL_OK) { + return; + } + + if (HAL_ADCEx_Calibration_Start(&adc->ADCHandle, ADC_CALIB_OFFSET, ADC_SINGLE_ENDED) != HAL_OK) { + return; + } + + adc->DmaHandle.Init.Request = adc->channel; + adc->DmaHandle.Init.Direction = DMA_PERIPH_TO_MEMORY; + adc->DmaHandle.Init.PeriphInc = DMA_PINC_DISABLE; + adc->DmaHandle.Init.MemInc = ((adc->usedChannelCount > 1) || (ADC_AVERAGE_N_SAMPLES > 1)) ? DMA_MINC_ENABLE : DMA_MINC_DISABLE; + adc->DmaHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; + adc->DmaHandle.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; + adc->DmaHandle.Init.Mode = DMA_CIRCULAR; + adc->DmaHandle.Init.Priority = DMA_PRIORITY_HIGH; + adc->DmaHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE; + adc->DmaHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; + adc->DmaHandle.Init.MemBurst = DMA_MBURST_SINGLE; + adc->DmaHandle.Init.PeriphBurst = DMA_PBURST_SINGLE; + adc->DmaHandle.Instance = adc->DMAy_Streamx; + + if (HAL_DMA_Init(&adc->DmaHandle) != HAL_OK) { + return; + } + + __HAL_LINKDMA(&adc->ADCHandle, DMA_Handle, adc->DmaHandle); + + uint8_t rank = 0; + for (int i = ADC_CHN_1; i < ADC_CHN_COUNT; i++) { + if (!adcConfig[i].enabled || adcConfig[i].adcDevice != adcDevice) { + continue; + } + + ADC_ChannelConfTypeDef sConfig; + sConfig.Channel = adcConfig[i].adcChannel; + sConfig.Rank = adcRegularRankMap[rank++]; + sConfig.SamplingTime = adcConfig[i].sampleTime; + sConfig.SingleDiff = ADC_SINGLE_ENDED; + sConfig.OffsetNumber = ADC_OFFSET_NONE; + sConfig.Offset = 0; + + if (HAL_ADC_ConfigChannel(&adc->ADCHandle, &sConfig) != HAL_OK) { + return; + } + } + + if (HAL_ADC_Start_DMA(&adc->ADCHandle, (uint32_t*)&adcValues[adcDevice], adc->usedChannelCount * ADC_AVERAGE_N_SAMPLES) != HAL_OK) { + return; + } +} + +void adcHardwareInit(drv_adc_config_t *init) +{ + UNUSED(init); + int configuredAdcChannels = 0; + + for (int i = ADC_CHN_1; i < ADC_CHN_COUNT; i++) { + if (!adcConfig[i].tag) + continue; + + adcDevice_t * adc = &adcHardware[adcConfig[i].adcDevice]; + + IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_CH1 + (i - ADC_CHN_1), 0); + IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_MODE_ANALOG, 0, GPIO_NOPULL)); + + adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag); + adcConfig[i].dmaIndex = adc->usedChannelCount++; + adcConfig[i].sampleTime = ADC_SAMPLETIME_387CYCLES_5; + adcConfig[i].enabled = true; + + adc->enabled = true; + configuredAdcChannels++; + } + + if (configuredAdcChannels == 0) + return; + + for (int i = 0; i < ADCDEV_COUNT; i++) { + if (adcHardware[i].enabled) { + adcInstanceInit(i); + } + } +} diff --git a/src/main/target/MATEKH743/target.h b/src/main/target/MATEKH743/target.h index 21b7abf0e8..6380723d31 100644 --- a/src/main/target/MATEKH743/target.h +++ b/src/main/target/MATEKH743/target.h @@ -148,6 +148,24 @@ #define USE_RANGEFINDER #define RANGEFINDER_I2C_BUS BUS_I2C2 +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 + +#define ADC_CHANNEL_1_PIN PC0 //ADC123 VBAT1 +#define ADC_CHANNEL_2_PIN PC1 //ADC123 CURR1 +#define ADC_CHANNEL_3_PIN PC5 //ADC12 RSSI +#define ADC_CHANNEL_4_PIN PC4 //ADC12 AirS +#define ADC_CHANNEL_5_PIN PA4 //ADC12 VB2 +#define ADC_CHANNEL_6_PIN PA7 //ADC12 CU2 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 +#define AIRSPEED_ADC_CHANNEL ADC_CHN_4 + +#define CURRENT_METER_SCALE 250 + #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA 0xffff @@ -165,20 +183,6 @@ #define USE_EXTI #define USE_MPU_DATA_READY_SIGNAL -// *************** ADC ***************************** -#define USE_ADC -#define ADC_INSTANCE ADC1 - -#define ADC_CHANNEL_1_PIN PC2 -#define ADC_CHANNEL_2_PIN PC3 -#define ADC_CHANNEL_3_PIN PC1 -#define ADC_CHANNEL_4_PIN PC0 - -#define VBAT_ADC_CHANNEL ADC_CHN_1 -#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 -#define RSSI_ADC_CHANNEL ADC_CHN_3 -#define AIRSPEED_ADC_CHANNEL ADC_CHN_4 - // *************** PINIO *************************** #define USE_PINIO #define USE_PINIOBOX @@ -190,6 +194,5 @@ #define WS2811_PIN PA8 #define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) -#define CURRENT_METER_SCALE 250 #endif \ No newline at end of file From f117162206508dbc10281b17b779a9a16545d893 Mon Sep 17 00:00:00 2001 From: bkleiner Date: Mon, 31 May 2021 20:30:33 +0200 Subject: [PATCH 024/102] h7: move adc values to dma_ram section to ensure coherent reads --- src/main/drivers/adc_impl.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/adc_impl.h b/src/main/drivers/adc_impl.h index 41f2635ce9..290a9ef583 100644 --- a/src/main/drivers/adc_impl.h +++ b/src/main/drivers/adc_impl.h @@ -31,7 +31,7 @@ #endif #if defined(STM32H7) -#define ADC_VALUES_ALIGNMENT(def) def __attribute__ ((aligned (32))) +#define ADC_VALUES_ALIGNMENT(def) __attribute__ ((section(".DMA_RAM"))) def __attribute__ ((aligned (32))) #else #define ADC_VALUES_ALIGNMENT(def) def #endif From e4c5cb9be7958183e4b87271c420fe60857434d1 Mon Sep 17 00:00:00 2001 From: bkleiner Date: Sat, 29 May 2021 21:37:41 +0200 Subject: [PATCH 025/102] h7: enable exti support --- src/main/drivers/accgyro/accgyro.c | 2 +- src/main/drivers/exti.c | 29 +++++++++++++++++++---------- src/main/target/MATEKH743/target.h | 2 +- 3 files changed, 21 insertions(+), 12 deletions(-) diff --git a/src/main/drivers/accgyro/accgyro.c b/src/main/drivers/accgyro/accgyro.c index 23bd5c0b16..99c69a5c80 100644 --- a/src/main/drivers/accgyro/accgyro.c +++ b/src/main/drivers/accgyro/accgyro.c @@ -98,7 +98,7 @@ void gyroIntExtiInit(gyroDev_t *gyro) } #endif -#if defined (STM32F7) +#if defined (STM32F7) || defined (STM32H7) IOInit(gyro->busDev->irqPin, OWNER_MPU, RESOURCE_EXTI, 0); EXTIHandlerInit(&gyro->exti, gyroIntExtiHandler); diff --git a/src/main/drivers/exti.c b/src/main/drivers/exti.c index 9185257e95..6d3a36e5ed 100644 --- a/src/main/drivers/exti.c +++ b/src/main/drivers/exti.c @@ -24,7 +24,7 @@ extiChannelRec_t extiChannelRecs[16]; static const uint8_t extiGroups[16] = { 0, 1, 2, 3, 4, 5, 5, 5, 5, 5, 6, 6, 6, 6, 6, 6 }; static uint8_t extiGroupPriority[EXTI_IRQ_GROUPS]; -#if defined(STM32F4) || defined(STM32F7) +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = { EXTI0_IRQn, EXTI1_IRQn, @@ -48,6 +48,15 @@ static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = { # warning "Unknown CPU" #endif +// Absorb the difference in IMR and PR assignments to registers +#if defined(STM32H7) +#define EXTI_REG_IMR (EXTI_D1->IMR1) +#define EXTI_REG_PR (EXTI_D1->PR1) +#else +#define EXTI_REG_IMR (EXTI->IMR) +#define EXTI_REG_PR (EXTI->PR) +#endif + void EXTIInit(void) { @@ -64,7 +73,7 @@ void EXTIHandlerInit(extiCallbackRec_t *self, extiHandlerCallback *fn) self->fn = fn; } -#if defined(STM32F7) +#if defined(STM32F7) || defined(STM32H7) void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, ioConfig_t config) { (void)config; @@ -156,23 +165,23 @@ void EXTIRelease(IO_t io) void EXTIEnable(IO_t io, bool enable) { -#if defined(STM32F4) || defined(STM32F7) +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) uint32_t extiLine = IO_EXTI_Line(io); if (!extiLine) return; if (enable) - EXTI->IMR |= extiLine; + EXTI_REG_IMR |= extiLine; else - EXTI->IMR &= ~extiLine; + EXTI_REG_IMR &= ~extiLine; #elif defined(STM32F303xC) int extiLine = IO_EXTI_Line(io); if (extiLine < 0) return; // assume extiLine < 32 (valid for all EXTI pins) if (enable) - EXTI->IMR |= 1 << extiLine; + EXTI_REG_IMR |= 1 << extiLine; else - EXTI->IMR &= ~(1 << extiLine); + EXTI_REG_IMR &= ~(1 << extiLine); #else # error "Unsupported target" #endif @@ -180,13 +189,13 @@ void EXTIEnable(IO_t io, bool enable) void EXTI_IRQHandler(void) { - uint32_t exti_active = EXTI->IMR & EXTI->PR; + uint32_t exti_active = EXTI_REG_IMR & EXTI_REG_PR; while (exti_active) { unsigned idx = 31 - __builtin_clz(exti_active); uint32_t mask = 1 << idx; extiChannelRecs[idx].handler->fn(extiChannelRecs[idx].handler); - EXTI->PR = mask; // clear pending mask (by writing 1) + EXTI_REG_PR = mask; // clear pending mask (by writing 1) exti_active &= ~mask; } } @@ -201,7 +210,7 @@ void EXTI_IRQHandler(void) _EXTI_IRQ_HANDLER(EXTI0_IRQHandler); _EXTI_IRQ_HANDLER(EXTI1_IRQHandler); -#if defined(STM32F7) +#if defined(STM32F7) || defined(STM32H7) _EXTI_IRQ_HANDLER(EXTI2_IRQHandler); #elif defined(STM32F3) || defined(STM32F4) _EXTI_IRQ_HANDLER(EXTI2_TS_IRQHandler); diff --git a/src/main/target/MATEKH743/target.h b/src/main/target/MATEKH743/target.h index 6380723d31..931868ecc4 100644 --- a/src/main/target/MATEKH743/target.h +++ b/src/main/target/MATEKH743/target.h @@ -179,10 +179,10 @@ #define USE_ESC_SENSOR #define USE_SERIALSHOT -#if 0 #define USE_EXTI #define USE_MPU_DATA_READY_SIGNAL +#if 0 // *************** PINIO *************************** #define USE_PINIO #define USE_PINIOBOX From 662296fb59feb6e2ac84f59d21a35c69fd66e5d3 Mon Sep 17 00:00:00 2001 From: bkleiner Date: Tue, 1 Jun 2021 09:49:10 +0200 Subject: [PATCH 026/102] MATEKH743: fix target id, enable pinio & osd --- src/main/target/MATEKH743/target.c | 3 --- src/main/target/MATEKH743/target.h | 40 +++++++++++++----------------- 2 files changed, 17 insertions(+), 26 deletions(-) diff --git a/src/main/target/MATEKH743/target.c b/src/main/target/MATEKH743/target.c index 5a7f27b98d..5a77e56bcf 100644 --- a/src/main/target/MATEKH743/target.c +++ b/src/main/target/MATEKH743/target.c @@ -29,9 +29,6 @@ BUSDEV_REGISTER_SPI_TAG(busdev_imu1_6000, DEVHW_MPU6000, IMU1_SPI_BUS, IMU1_CS_PIN, IMU1_EXTI_PIN, 0, DEVFLAGS_NONE, IMU1_ALIGN); BUSDEV_REGISTER_SPI_TAG(busdev_imu2_6500, DEVHW_MPU6500, IMU2_SPI_BUS, IMU2_CS_PIN, IMU2_EXTI_PIN, 1, DEVFLAGS_NONE, IMU2_ALIGN); -//BUSDEV_REGISTER_SPI_TAG(busdev_imu1_6500, DEVHW_MPU6500, IMU1_SPI_BUS, IMU1_CS_PIN, IMU1_EXTI_PIN, 0, DEVFLAGS_NONE, IMU1_ALIGN); -//BUSDEV_REGISTER_SPI_TAG(busdev_imu2_6000, DEVHW_MPU6000, IMU2_SPI_BUS, IMU2_CS_PIN, IMU2_EXTI_PIN, 1, DEVFLAGS_NONE, IMU2_ALIGN); - const timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 2), // S1 DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 2), // S2 diff --git a/src/main/target/MATEKH743/target.h b/src/main/target/MATEKH743/target.h index 931868ecc4..ca99c9ddcc 100644 --- a/src/main/target/MATEKH743/target.h +++ b/src/main/target/MATEKH743/target.h @@ -18,8 +18,8 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "H765" -#define USBD_PRODUCT_STRING "MATEKH765" +#define TARGET_BOARD_IDENTIFIER "H743" +#define USBD_PRODUCT_STRING "MATEKH743" #define LED0 PE3 #define LED1 PE4 @@ -68,6 +68,9 @@ #define USE_DUAL_GYRO #define USE_TARGET_IMU_HARDWARE_DESCRIPTORS +#define USE_EXTI +#define USE_MPU_DATA_READY_SIGNAL + // *************** SPI1 IMU1 ************************* #define USE_SPI #define USE_SPI_DEVICE_1 @@ -89,12 +92,10 @@ #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 -/* #define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB12 -*/ // *************** SPI3 SD BLACKBOX******************* /* @@ -164,6 +165,17 @@ #define RSSI_ADC_CHANNEL ADC_CHN_3 #define AIRSPEED_ADC_CHANNEL ADC_CHN_4 +// *************** PINIO *************************** +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PE4 // VTX power switcher +#define PINIO2_PIN PE15 // 2xCamera switcher + +// *************** LEDSTRIP ************************ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) #define CURRENT_METER_SCALE 250 #define USE_SERIAL_4WAY_BLHELI_INTERFACE @@ -177,22 +189,4 @@ #define MAX_PWM_OUTPUT_PORTS 15 #define USE_DSHOT #define USE_ESC_SENSOR -#define USE_SERIALSHOT - -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL - -#if 0 -// *************** PINIO *************************** -#define USE_PINIO -#define USE_PINIOBOX -#define PINIO1_PIN PE4 // VTX power switcher -#define PINIO2_PIN PE15 // 2xCamera switcher - -// *************** LEDSTRIP ************************ -#define USE_LED_STRIP -#define WS2811_PIN PA8 - -#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) - -#endif \ No newline at end of file +#define USE_SERIALSHOT \ No newline at end of file From 2fcb1cb83d1df64400e8fe19c4caba0703b4f12e Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Wed, 2 Jun 2021 14:53:59 +0100 Subject: [PATCH 027/102] remove *.ld files differing only in case, as this confuses case-insensitive, case-preserving (cicp) file-systems (#7064) --- src/main/target/link/stm32_flash_F765xI.ld | 55 ------------------ src/main/target/link/stm32_flash_F765xI_bl.ld | 56 ------------------ .../target/link/stm32_flash_F765xI_for_bl.ld | 57 ------------------- 3 files changed, 168 deletions(-) delete mode 100644 src/main/target/link/stm32_flash_F765xI.ld delete mode 100644 src/main/target/link/stm32_flash_F765xI_bl.ld delete mode 100644 src/main/target/link/stm32_flash_F765xI_for_bl.ld diff --git a/src/main/target/link/stm32_flash_F765xI.ld b/src/main/target/link/stm32_flash_F765xI.ld deleted file mode 100644 index 130169290e..0000000000 --- a/src/main/target/link/stm32_flash_F765xI.ld +++ /dev/null @@ -1,55 +0,0 @@ -/* -***************************************************************************** -** -** File : stm32_flash_f765.ld -** -** Abstract : Linker script for STM32F765xITx Device with -** 2048KByte FLASH, 512KByte RAM -** -***************************************************************************** -*/ - -/* Stack & Heap sizes */ -_Min_Heap_Size = 0; -_Min_Stack_Size = 0x1800; - -/* Entry Point */ -ENTRY(Reset_Handler) - -/* -0x00000000 to 0x00003FFF 16K TCM RAM, - -0x08000000 to 0x081FFFFF 2048K full flash, -0x08000000 to 0x08007FFF 32K isr vector, startup code, -0x08008000 to 0x0800FFFF 32K config, -0x08010000 to 0x081FFFFF 1984K firmware, -*/ - -/* Specify the memory areas */ -MEMORY -{ - ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K - - ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K - ITCM_FLASH_CFG (r) : ORIGIN = 0x00208000, LENGTH = 32K - ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K - - AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K - AXIM_FLASH_CFG (r) : ORIGIN = 0x08008000, LENGTH = 32K - AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 1984K - - DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K - SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K - SRAM2 (rwx) : ORIGIN = 0x2007C000, LENGTH = 16K - MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K -} - -REGION_ALIAS("FLASH", AXIM_FLASH) -REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CFG) -REGION_ALIAS("FLASH1", AXIM_FLASH1) - -REGION_ALIAS("STACKRAM", DTCM_RAM) -REGION_ALIAS("FASTRAM", DTCM_RAM) -REGION_ALIAS("RAM", SRAM1) - -INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/link/stm32_flash_F765xI_bl.ld b/src/main/target/link/stm32_flash_F765xI_bl.ld deleted file mode 100644 index 45ced4e7dd..0000000000 --- a/src/main/target/link/stm32_flash_F765xI_bl.ld +++ /dev/null @@ -1,56 +0,0 @@ -/* -***************************************************************************** -** -** File : stm32_flash_f765.ld -** -** Abstract : Linker script for STM32F765xITx Device with -** 2048KByte FLASH, 512KByte RAM -** -***************************************************************************** -*/ - -/* Stack & Heap sizes */ -_Min_Heap_Size = 0; -_Min_Stack_Size = 0x1800; - -/* Entry Point */ -ENTRY(Reset_Handler) - -/* -0x00000000 to 0x00003FFF 16K TCM RAM, - -0x08000000 to 0x081FFFFF 2048K full flash, -0x08000000 to 0x08007FFF 32K isr vector, startup code, -0x08008000 to 0x0800FFFF 32K config, -0x08010000 to 0x081FFFFF 1984K firmware, -*/ - -/* Specify the memory areas */ -MEMORY -{ - ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K - - ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K - ITCM_FLASH_CFG (r) : ORIGIN = 0x00208000, LENGTH = 32K - ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K - - AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K - AXIM_FIRMWARE (rx) : ORIGIN = 0x08008000, LENGTH = 32K - AXIM_FLASH_CFG (r) : ORIGIN = 0x08010000, LENGTH = 32K - - DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K - SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K - SRAM2 (rwx) : ORIGIN = 0x2007C000, LENGTH = 16K - MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K -} - -REGION_ALIAS("FLASH", AXIM_FLASH) -REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CFG) - -REGION_ALIAS("STACKRAM", DTCM_RAM) -REGION_ALIAS("FASTRAM", DTCM_RAM) -REGION_ALIAS("RAM", SRAM1) - -__firmware_start = ORIGIN(AXIM_FIRMWARE); - -INCLUDE "stm32_flash_f7.ld" diff --git a/src/main/target/link/stm32_flash_F765xI_for_bl.ld b/src/main/target/link/stm32_flash_F765xI_for_bl.ld deleted file mode 100644 index 14f2a4bedf..0000000000 --- a/src/main/target/link/stm32_flash_F765xI_for_bl.ld +++ /dev/null @@ -1,57 +0,0 @@ -/* -***************************************************************************** -** -** File : stm32_flash_f765.ld -** -** Abstract : Linker script for STM32F765xITx Device with -** 2048KByte FLASH, 512KByte RAM -** -***************************************************************************** -*/ - -/* Stack & Heap sizes */ -_Min_Heap_Size = 0; -_Min_Stack_Size = 0x1800; - -/* Entry Point */ -ENTRY(Reset_Handler) - -/* -0x00000000 to 0x00003FFF 16K TCM RAM, - -0x08000000 to 0x081FFFFF 2048K full flash, -0x08000000 to 0x08007FFF 32K isr vector, startup code, -0x08008000 to 0x0800FFFF 32K config, -0x08010000 to 0x081FFFFF 1984K firmware, -*/ - -/* Specify the memory areas */ -MEMORY -{ - ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K - - ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K - ITCM_FLASH_CFG (r) : ORIGIN = 0x00208000, LENGTH = 32K - ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K - - AXIM_FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 32K - AXIM_FLASH_CFG (r) : ORIGIN = 0x08010000, LENGTH = 32K - AXIM_FLASH1 (rx) : ORIGIN = 0x08018000, LENGTH = 1984K - - DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K - SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K - SRAM2 (rwx) : ORIGIN = 0x2007C000, LENGTH = 16K - MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K -} - -REGION_ALIAS("FLASH", AXIM_FLASH) -REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CFG) -REGION_ALIAS("FLASH1", AXIM_FLASH1) - -REGION_ALIAS("STACKRAM", DTCM_RAM) -REGION_ALIAS("FASTRAM", DTCM_RAM) -REGION_ALIAS("RAM", SRAM1) - -__firmware_start = ORIGIN(AXIM_FLASH); - -INCLUDE "stm32_flash_f7_split.ld" From 79db68dc50c47c382a456495ad08ef3d3bf7c494 Mon Sep 17 00:00:00 2001 From: JuliooCesarMDM Date: Sat, 5 Jun 2021 22:24:49 -0300 Subject: [PATCH 028/102] do fast operations --- src/main/navigation/navigation.c | 6 +++--- src/main/navigation/navigation_fixedwing.c | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 37a6c3c000..a437b2f6cd 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -1041,7 +1041,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_COURSE_HOLD_IN_PROGRESS timeMs_t timeDifference = currentTimeMs - posControl.cruise.lastYawAdjustmentTime; if (timeDifference > 100) timeDifference = 0; // if adjustment was called long time ago, reset the time difference. float rateTarget = scaleRangef((float)rcCommand[YAW], -500.0f, 500.0f, -DEGREES_TO_CENTIDEGREES(navConfig()->fw.cruise_yaw_rate), DEGREES_TO_CENTIDEGREES(navConfig()->fw.cruise_yaw_rate)); - float centidegsPerIteration = rateTarget * timeDifference / 1000.0f; + float centidegsPerIteration = rateTarget * timeDifference * 0.001f; posControl.cruise.yaw = wrap_36000(posControl.cruise.yaw - centidegsPerIteration); DEBUG_SET(DEBUG_CRUISE, 1, CENTIDEGREES_TO_DEGREES(posControl.cruise.yaw)); posControl.cruise.lastYawAdjustmentTime = currentTimeMs; @@ -2144,8 +2144,8 @@ bool isWaypointReached(const navWaypointPosition_t * waypoint, const bool isWayp static void updateHomePositionCompatibility(void) { geoConvertLocalToGeodetic(&GPS_home, &posControl.gpsOrigin, &posControl.rthState.homePosition.pos); - GPS_distanceToHome = posControl.homeDistance / 100; - GPS_directionToHome = posControl.homeDirection / 100; + GPS_distanceToHome = posControl.homeDistance * 0.01f; + GPS_directionToHome = posControl.homeDirection * 0.01f; } // Backdoor for RTH estimator diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 6501cc7ea2..4340162710 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -132,10 +132,10 @@ static void updateAltitudeVelocityAndPitchController_FW(timeDelta_t deltaMicros) // velocity error. We use PID controller on altitude error and calculate desired pitch angle // Update energies - const float demSPE = (posControl.desiredState.pos.z / 100.0f) * GRAVITY_MSS; + const float demSPE = (posControl.desiredState.pos.z * 0.01f) * GRAVITY_MSS; const float demSKE = 0.0f; - const float estSPE = (navGetCurrentActualPositionAndVelocity()->pos.z / 100.0f) * GRAVITY_MSS; + const float estSPE = (navGetCurrentActualPositionAndVelocity()->pos.z * 0.01f) * GRAVITY_MSS; const float estSKE = 0.0f; // speedWeight controls balance between potential and kinetic energy used for pitch controller @@ -316,7 +316,7 @@ float processHeadingYawController(timeDelta_t deltaMicros, int32_t navHeadingErr -limit, limit, yawPidFlags - ) / 100.0f; + ) * 0.01f; DEBUG_SET(DEBUG_NAV_YAW, 0, posControl.pids.fw_heading.proportional); DEBUG_SET(DEBUG_NAV_YAW, 1, posControl.pids.fw_heading.integral); From b5734a3a46fd4685c163c4f10147f6f1f6b1a0bb Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sun, 6 Jun 2021 22:44:22 +0300 Subject: [PATCH 029/102] fix docker build under windows --- .gitattributes | 2 +- docs/development/Building in Docker.md | 4 +++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/.gitattributes b/.gitattributes index 0ec73feee9..4c09735408 100644 --- a/.gitattributes +++ b/.gitattributes @@ -10,4 +10,4 @@ Makefile text *.bat eol=crlf *.txt text -*.sh text +*.sh text eol=lf diff --git a/docs/development/Building in Docker.md b/docs/development/Building in Docker.md index 7e370cf91c..99a8784e6d 100755 --- a/docs/development/Building in Docker.md +++ b/docs/development/Building in Docker.md @@ -23,12 +23,14 @@ Where `` must be replaced with the name of the target that you want to b ## Windows 10 Docker on Windows requires full paths for mounting volumes in `docker run` commands. For example: `c:\Users\pspyc\Documents\Projects\inav` becomes `//c/Users/pspyc/Documents/Projects/inav` . +If you are getting error "standard_init_linux.go:219: exec user process caused: no such file or directory", make sure `\cmake\docker.sh` has lf (not crlf) line endings. You'll have to manually execute the same steps that the build script does: 1. `docker build -t inav-build .` + This step is only needed the first time. -2. `docker run --rm -it -v :/src inav-build ` +2. `docker run --rm -it -u root -v :/src inav-build ` + Where `` must be replaced with the absolute path of where you cloned this repo (see above), and `` with the name of the target that you want to build. + + Note that on Windows/WSL 2 mounted /src folder is writeable for root user only. You have to run build under root user. You can achieve this by using `-u root` option in the command line above, or by removing "USER inav" line from the .\DockerFile before building image. Refer to the [Linux](#Linux) instructions or the [build script](/build.sh) for more details. \ No newline at end of file From f5be74d1f33392017d4ff4b754cf4a8c0044664d Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sun, 6 Jun 2021 22:37:03 +0100 Subject: [PATCH 030/102] Revert "remove *.ld files differing only in case, as this confuses case-insensitive, case-preserving (cicp) file-systems (#7064)" This reverts commit 2fcb1cb83d1df64400e8fe19c4caba0703b4f12e. --- src/main/target/link/stm32_flash_F765xI.ld | 55 ++++++++++++++++++ src/main/target/link/stm32_flash_F765xI_bl.ld | 56 ++++++++++++++++++ .../target/link/stm32_flash_F765xI_for_bl.ld | 57 +++++++++++++++++++ 3 files changed, 168 insertions(+) create mode 100644 src/main/target/link/stm32_flash_F765xI.ld create mode 100644 src/main/target/link/stm32_flash_F765xI_bl.ld create mode 100644 src/main/target/link/stm32_flash_F765xI_for_bl.ld diff --git a/src/main/target/link/stm32_flash_F765xI.ld b/src/main/target/link/stm32_flash_F765xI.ld new file mode 100644 index 0000000000..130169290e --- /dev/null +++ b/src/main/target/link/stm32_flash_F765xI.ld @@ -0,0 +1,55 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f765.ld +** +** Abstract : Linker script for STM32F765xITx Device with +** 2048KByte FLASH, 512KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x00003FFF 16K TCM RAM, + +0x08000000 to 0x081FFFFF 2048K full flash, +0x08000000 to 0x08007FFF 32K isr vector, startup code, +0x08008000 to 0x0800FFFF 32K config, +0x08010000 to 0x081FFFFF 1984K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K + + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K + ITCM_FLASH_CFG (r) : ORIGIN = 0x00208000, LENGTH = 32K + ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K + + AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K + AXIM_FLASH_CFG (r) : ORIGIN = 0x08008000, LENGTH = 32K + AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 1984K + + DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K + SRAM2 (rwx) : ORIGIN = 0x2007C000, LENGTH = 16K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("FLASH", AXIM_FLASH) +REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CFG) +REGION_ALIAS("FLASH1", AXIM_FLASH1) + +REGION_ALIAS("STACKRAM", DTCM_RAM) +REGION_ALIAS("FASTRAM", DTCM_RAM) +REGION_ALIAS("RAM", SRAM1) + +INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/link/stm32_flash_F765xI_bl.ld b/src/main/target/link/stm32_flash_F765xI_bl.ld new file mode 100644 index 0000000000..45ced4e7dd --- /dev/null +++ b/src/main/target/link/stm32_flash_F765xI_bl.ld @@ -0,0 +1,56 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f765.ld +** +** Abstract : Linker script for STM32F765xITx Device with +** 2048KByte FLASH, 512KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x00003FFF 16K TCM RAM, + +0x08000000 to 0x081FFFFF 2048K full flash, +0x08000000 to 0x08007FFF 32K isr vector, startup code, +0x08008000 to 0x0800FFFF 32K config, +0x08010000 to 0x081FFFFF 1984K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K + + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K + ITCM_FLASH_CFG (r) : ORIGIN = 0x00208000, LENGTH = 32K + ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K + + AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K + AXIM_FIRMWARE (rx) : ORIGIN = 0x08008000, LENGTH = 32K + AXIM_FLASH_CFG (r) : ORIGIN = 0x08010000, LENGTH = 32K + + DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K + SRAM2 (rwx) : ORIGIN = 0x2007C000, LENGTH = 16K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("FLASH", AXIM_FLASH) +REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CFG) + +REGION_ALIAS("STACKRAM", DTCM_RAM) +REGION_ALIAS("FASTRAM", DTCM_RAM) +REGION_ALIAS("RAM", SRAM1) + +__firmware_start = ORIGIN(AXIM_FIRMWARE); + +INCLUDE "stm32_flash_f7.ld" diff --git a/src/main/target/link/stm32_flash_F765xI_for_bl.ld b/src/main/target/link/stm32_flash_F765xI_for_bl.ld new file mode 100644 index 0000000000..14f2a4bedf --- /dev/null +++ b/src/main/target/link/stm32_flash_F765xI_for_bl.ld @@ -0,0 +1,57 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f765.ld +** +** Abstract : Linker script for STM32F765xITx Device with +** 2048KByte FLASH, 512KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x00003FFF 16K TCM RAM, + +0x08000000 to 0x081FFFFF 2048K full flash, +0x08000000 to 0x08007FFF 32K isr vector, startup code, +0x08008000 to 0x0800FFFF 32K config, +0x08010000 to 0x081FFFFF 1984K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K + + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K + ITCM_FLASH_CFG (r) : ORIGIN = 0x00208000, LENGTH = 32K + ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K + + AXIM_FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 32K + AXIM_FLASH_CFG (r) : ORIGIN = 0x08010000, LENGTH = 32K + AXIM_FLASH1 (rx) : ORIGIN = 0x08018000, LENGTH = 1984K + + DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K + SRAM2 (rwx) : ORIGIN = 0x2007C000, LENGTH = 16K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("FLASH", AXIM_FLASH) +REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CFG) +REGION_ALIAS("FLASH1", AXIM_FLASH1) + +REGION_ALIAS("STACKRAM", DTCM_RAM) +REGION_ALIAS("FASTRAM", DTCM_RAM) +REGION_ALIAS("RAM", SRAM1) + +__firmware_start = ORIGIN(AXIM_FLASH); + +INCLUDE "stm32_flash_f7_split.ld" From aa50ad6353c7ad864f2ffa6084b9a6672d5396bc Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sun, 6 Jun 2021 22:41:28 +0100 Subject: [PATCH 031/102] Update beeper.c --- src/main/io/beeper.c | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index 0ef6f3a77b..f19797afc4 100644 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -339,8 +339,7 @@ void beeperUpdate(timeUs_t currentTimeUs) if (!beeperIsOn) { #ifdef USE_DSHOT - if (!areMotorsRunning() - && beeperConfig()->dshot_beeper_enabled + if (isMotorProtocolDshot() && !areMotorsRunning() && beeperConfig()->dshot_beeper_enabled && currentTimeUs - lastDshotBeeperCommandTimeUs > getDShotBeaconGuardDelayUs()) { lastDshotBeeperCommandTimeUs = currentTimeUs; From 00c8ff10c8bb11812e105fbe854bb7681c59af9c Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sun, 6 Jun 2021 22:45:32 +0100 Subject: [PATCH 032/102] Revert "Revert "remove *.ld files differing only in case, as this confuses case-insensitive, case-preserving (cicp) file-systems (#7064)"" This reverts commit f5be74d1f33392017d4ff4b754cf4a8c0044664d. --- src/main/target/link/stm32_flash_F765xI.ld | 55 ------------------ src/main/target/link/stm32_flash_F765xI_bl.ld | 56 ------------------ .../target/link/stm32_flash_F765xI_for_bl.ld | 57 ------------------- 3 files changed, 168 deletions(-) delete mode 100644 src/main/target/link/stm32_flash_F765xI.ld delete mode 100644 src/main/target/link/stm32_flash_F765xI_bl.ld delete mode 100644 src/main/target/link/stm32_flash_F765xI_for_bl.ld diff --git a/src/main/target/link/stm32_flash_F765xI.ld b/src/main/target/link/stm32_flash_F765xI.ld deleted file mode 100644 index 130169290e..0000000000 --- a/src/main/target/link/stm32_flash_F765xI.ld +++ /dev/null @@ -1,55 +0,0 @@ -/* -***************************************************************************** -** -** File : stm32_flash_f765.ld -** -** Abstract : Linker script for STM32F765xITx Device with -** 2048KByte FLASH, 512KByte RAM -** -***************************************************************************** -*/ - -/* Stack & Heap sizes */ -_Min_Heap_Size = 0; -_Min_Stack_Size = 0x1800; - -/* Entry Point */ -ENTRY(Reset_Handler) - -/* -0x00000000 to 0x00003FFF 16K TCM RAM, - -0x08000000 to 0x081FFFFF 2048K full flash, -0x08000000 to 0x08007FFF 32K isr vector, startup code, -0x08008000 to 0x0800FFFF 32K config, -0x08010000 to 0x081FFFFF 1984K firmware, -*/ - -/* Specify the memory areas */ -MEMORY -{ - ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K - - ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K - ITCM_FLASH_CFG (r) : ORIGIN = 0x00208000, LENGTH = 32K - ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K - - AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K - AXIM_FLASH_CFG (r) : ORIGIN = 0x08008000, LENGTH = 32K - AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 1984K - - DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K - SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K - SRAM2 (rwx) : ORIGIN = 0x2007C000, LENGTH = 16K - MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K -} - -REGION_ALIAS("FLASH", AXIM_FLASH) -REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CFG) -REGION_ALIAS("FLASH1", AXIM_FLASH1) - -REGION_ALIAS("STACKRAM", DTCM_RAM) -REGION_ALIAS("FASTRAM", DTCM_RAM) -REGION_ALIAS("RAM", SRAM1) - -INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/link/stm32_flash_F765xI_bl.ld b/src/main/target/link/stm32_flash_F765xI_bl.ld deleted file mode 100644 index 45ced4e7dd..0000000000 --- a/src/main/target/link/stm32_flash_F765xI_bl.ld +++ /dev/null @@ -1,56 +0,0 @@ -/* -***************************************************************************** -** -** File : stm32_flash_f765.ld -** -** Abstract : Linker script for STM32F765xITx Device with -** 2048KByte FLASH, 512KByte RAM -** -***************************************************************************** -*/ - -/* Stack & Heap sizes */ -_Min_Heap_Size = 0; -_Min_Stack_Size = 0x1800; - -/* Entry Point */ -ENTRY(Reset_Handler) - -/* -0x00000000 to 0x00003FFF 16K TCM RAM, - -0x08000000 to 0x081FFFFF 2048K full flash, -0x08000000 to 0x08007FFF 32K isr vector, startup code, -0x08008000 to 0x0800FFFF 32K config, -0x08010000 to 0x081FFFFF 1984K firmware, -*/ - -/* Specify the memory areas */ -MEMORY -{ - ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K - - ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K - ITCM_FLASH_CFG (r) : ORIGIN = 0x00208000, LENGTH = 32K - ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K - - AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K - AXIM_FIRMWARE (rx) : ORIGIN = 0x08008000, LENGTH = 32K - AXIM_FLASH_CFG (r) : ORIGIN = 0x08010000, LENGTH = 32K - - DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K - SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K - SRAM2 (rwx) : ORIGIN = 0x2007C000, LENGTH = 16K - MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K -} - -REGION_ALIAS("FLASH", AXIM_FLASH) -REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CFG) - -REGION_ALIAS("STACKRAM", DTCM_RAM) -REGION_ALIAS("FASTRAM", DTCM_RAM) -REGION_ALIAS("RAM", SRAM1) - -__firmware_start = ORIGIN(AXIM_FIRMWARE); - -INCLUDE "stm32_flash_f7.ld" diff --git a/src/main/target/link/stm32_flash_F765xI_for_bl.ld b/src/main/target/link/stm32_flash_F765xI_for_bl.ld deleted file mode 100644 index 14f2a4bedf..0000000000 --- a/src/main/target/link/stm32_flash_F765xI_for_bl.ld +++ /dev/null @@ -1,57 +0,0 @@ -/* -***************************************************************************** -** -** File : stm32_flash_f765.ld -** -** Abstract : Linker script for STM32F765xITx Device with -** 2048KByte FLASH, 512KByte RAM -** -***************************************************************************** -*/ - -/* Stack & Heap sizes */ -_Min_Heap_Size = 0; -_Min_Stack_Size = 0x1800; - -/* Entry Point */ -ENTRY(Reset_Handler) - -/* -0x00000000 to 0x00003FFF 16K TCM RAM, - -0x08000000 to 0x081FFFFF 2048K full flash, -0x08000000 to 0x08007FFF 32K isr vector, startup code, -0x08008000 to 0x0800FFFF 32K config, -0x08010000 to 0x081FFFFF 1984K firmware, -*/ - -/* Specify the memory areas */ -MEMORY -{ - ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K - - ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K - ITCM_FLASH_CFG (r) : ORIGIN = 0x00208000, LENGTH = 32K - ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K - - AXIM_FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 32K - AXIM_FLASH_CFG (r) : ORIGIN = 0x08010000, LENGTH = 32K - AXIM_FLASH1 (rx) : ORIGIN = 0x08018000, LENGTH = 1984K - - DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K - SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K - SRAM2 (rwx) : ORIGIN = 0x2007C000, LENGTH = 16K - MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K -} - -REGION_ALIAS("FLASH", AXIM_FLASH) -REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CFG) -REGION_ALIAS("FLASH1", AXIM_FLASH1) - -REGION_ALIAS("STACKRAM", DTCM_RAM) -REGION_ALIAS("FASTRAM", DTCM_RAM) -REGION_ALIAS("RAM", SRAM1) - -__firmware_start = ORIGIN(AXIM_FLASH); - -INCLUDE "stm32_flash_f7_split.ld" From 734ff4c12ff76c7b355c61c966d0ff517ae4cf4a Mon Sep 17 00:00:00 2001 From: bkleiner Date: Wed, 9 Jun 2021 15:40:06 +0200 Subject: [PATCH 033/102] MATEKH743: statically assign motor pins to DMAMUX streams --- src/main/target/MATEKH743/target.c | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/src/main/target/MATEKH743/target.c b/src/main/target/MATEKH743/target.c index 5a77e56bcf..94b2ff7b75 100644 --- a/src/main/target/MATEKH743/target.c +++ b/src/main/target/MATEKH743/target.c @@ -30,21 +30,21 @@ BUSDEV_REGISTER_SPI_TAG(busdev_imu1_6000, DEVHW_MPU6000, IMU1_SPI_BUS, IMU1 BUSDEV_REGISTER_SPI_TAG(busdev_imu2_6500, DEVHW_MPU6500, IMU2_SPI_BUS, IMU2_CS_PIN, IMU2_EXTI_PIN, 1, DEVFLAGS_NONE, IMU2_ALIGN); const timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 2), // S1 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S1 DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 2), // S2 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 3), // S3 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 4), // S4 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 5), // S5 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 6), // S6 - DEF_TIM(TIM4, CH1, PD12, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 1), // S7 - DEF_TIM(TIM4, CH2, PD13, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 1), // S8 - DEF_TIM(TIM4, CH3, PD14, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 1), // S9 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 7), // S7 + DEF_TIM(TIM4, CH2, PD13, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 8), // S8 + DEF_TIM(TIM4, CH3, PD14, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S9 DEF_TIM(TIM4, CH4, PD15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S10 DMA_NONE - DEF_TIM(TIM15, CH1, PE5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S11 - DEF_TIM(TIM15, CH2, PE6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S12 + DEF_TIM(TIM15, CH1, PE5, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S11 + DEF_TIM(TIM15, CH2, PE6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S12 DMA_NONE DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED_2812 DEF_TIM(TIM2, CH1, PA15, TIM_USE_BEEPER, 0, 0), // BEEPER PWM From 15be7e1621f70e13838666765926f56959bba356 Mon Sep 17 00:00:00 2001 From: wenzhicode Date: Thu, 10 Jun 2021 10:58:10 +0800 Subject: [PATCH 034/102] add BETAFPVF722 target --- src/main/target/BETAFPVF722/CMakeLists.txt | 1 + src/main/target/BETAFPVF722/target.c | 44 ++++++ src/main/target/BETAFPVF722/target.h | 165 +++++++++++++++++++++ 3 files changed, 210 insertions(+) create mode 100644 src/main/target/BETAFPVF722/CMakeLists.txt create mode 100755 src/main/target/BETAFPVF722/target.c create mode 100755 src/main/target/BETAFPVF722/target.h diff --git a/src/main/target/BETAFPVF722/CMakeLists.txt b/src/main/target/BETAFPVF722/CMakeLists.txt new file mode 100644 index 0000000000..bad557907d --- /dev/null +++ b/src/main/target/BETAFPVF722/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(BETAFPVF722) diff --git a/src/main/target/BETAFPVF722/target.c b/src/main/target/BETAFPVF722/target.c new file mode 100755 index 0000000000..2d02a8a71e --- /dev/null +++ b/src/main/target/BETAFPVF722/target.c @@ -0,0 +1,44 @@ +/* +* This file is part of Cleanflight. +* +* Cleanflight is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* Cleanflight is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with Cleanflight. If not, see . +*/ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + +const timerHardware_t timerHardware[] = { + DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), // PPM + + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 0, 0), // S1 D(1, 4, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 0, 0), // S2 D(2, 3, 7) + DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR, 0, 0), // S3 D(2, 4, 7) + DEF_TIM(TIM2, CH1, PA0, TIM_USE_MC_MOTOR, 0, 0), // S4 D(2, 7, 7) + + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR, 0, 0), // S5 DMA1_ST2 + + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR, 0, 0), // S6 DMA2_ST6 + + DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0), //camera + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP D(1, 5, 3) +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/BETAFPVF722/target.h b/src/main/target/BETAFPVF722/target.h new file mode 100755 index 0000000000..cdedf65f31 --- /dev/null +++ b/src/main/target/BETAFPVF722/target.h @@ -0,0 +1,165 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "BHF7" + +#define USBD_PRODUCT_STRING "BETAFPVF722" + +#define LED0 PC15 + +#define BEEPER PC14 +#define BEEPER_INVERTED + +// *************** Gyro & ACC ********************** +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_BUS BUS_SPI1 + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW180_DEG + +#define USE_EXTI +#define GYRO_INT_EXTI PC4 +#define USE_MPU_DATA_READY_SIGNAL + + +// *************** I2C/Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 // SCL pad +#define I2C1_SDA PB9 // SDA pad + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_BMP085 +#define USE_BARO_DPS310 +#define USE_BARO_SPL06 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +#define TEMPERATURE_I2C_BUS BUS_I2C1 + +#define PITOT_I2C_BUS BUS_I2C1 + + +// *************** OSD************************* +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI3 +#define MAX7456_CS_PIN PA15 + + +// *************** UART ***************************** +#define USE_VCP + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 + +#define USE_UART4 +#define UART4_RX_PIN PC11 +#define UART4_TX_PIN PC10 + +#define USE_UART5 +#define UART5_RX_PIN PD2 +#define UART5_TX_PIN PC12 + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 + +#define SERIAL_PORT_COUNT 7 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART3 + + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC2 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 + + +// *************** FLASH ***************************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_CS_PIN PB12 +#define M25P16_SPI_BUS BUS_SPI2 + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY| FEATURE_VBAT | FEATURE_OSD ) + + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + +#define MAX_PWM_OUTPUT_PORTS 6 +#define TARGET_MOTOR_COUNT 4 + +// ESC-related features +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIALSHOT From f0e36c3cf8c4a33138e8a17b2b5c534dec6a7c68 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Thu, 10 Jun 2021 12:45:04 +0200 Subject: [PATCH 035/102] add 4th digit for negative altitudes --- src/main/io/osd.c | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index f0c4af8c24..f455a43bf8 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -449,29 +449,30 @@ static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid) */ void osdFormatAltitudeSymbol(char *buff, int32_t alt) { + int digits = alt < 0 ? 4 : 3; switch ((osd_unit_e)osdConfig()->units) { case OSD_UNIT_UK: FALLTHROUGH; case OSD_UNIT_IMPERIAL: - if (osdFormatCentiNumber(buff , CENTIMETERS_TO_CENTIFEET(alt), 1000, 0, 2, 3)) { + if (osdFormatCentiNumber(buff , CENTIMETERS_TO_CENTIFEET(alt), 1000, 0, 2, digits)) { // Scaled to kft - buff[3] = SYM_ALT_KFT; + buff[digits] = SYM_ALT_KFT; } else { // Formatted in feet - buff[3] = SYM_ALT_FT; + buff[digits] = SYM_ALT_FT; } - buff[4] = '\0'; + buff[digits + 1] = '\0'; break; case OSD_UNIT_METRIC: // alt is alredy in cm - if (osdFormatCentiNumber(buff, alt, 1000, 0, 2, 3)) { + if (osdFormatCentiNumber(buff, alt, 1000, 0, 2, digits)) { // Scaled to km - buff[3] = SYM_ALT_KM; + buff[digits] = SYM_ALT_KM; } else { // Formatted in m - buff[3] = SYM_ALT_M; + buff[digits] = SYM_ALT_M; } - buff[4] = '\0'; + buff[digits + 1] = '\0'; break; } } From bf69cb83ab6405343d2d45c1547bdd2e6748662a Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Thu, 10 Jun 2021 16:00:18 +0100 Subject: [PATCH 036/102] Update cms_menu_navigation.c --- src/main/cms/cms_menu_navigation.c | 25 +++++++++++++++++++++++++ 1 file changed, 25 insertions(+) diff --git a/src/main/cms/cms_menu_navigation.c b/src/main/cms/cms_menu_navigation.c index ff9d246ee2..6060ba40d7 100644 --- a/src/main/cms/cms_menu_navigation.c +++ b/src/main/cms/cms_menu_navigation.c @@ -181,6 +181,30 @@ static const CMS_Menu cmsx_menuFWSettings = { .entries = cmsx_menuFWSettingsEntries }; +static const OSD_Entry cmsx_menuMissionSettingsEntries[] = +{ + OSD_LABEL_ENTRY("-- MISSIONS --"), + + OSD_SETTING_ENTRY("MC WP SLOWDOWN", SETTING_NAV_MC_WP_SLOWDOWN), + OSD_SETTING_ENTRY("MISSION FAILSAFE", SETTING_FAILSAFE_MISSION), + OSD_SETTING_ENTRY("WP LOAD ON BOOT", SETTING_NAV_WP_LOAD_ON_BOOT), + OSD_SETTING_ENTRY("WP REACHED RADIUS", SETTING_NAV_WP_RADIUS), + OSD_SETTING_ENTRY("WP SAFE DISTANCE", SETTING_NAV_WP_SAFE_DISTANCE), + + OSD_BACK_AND_END_ENTRY, + }; + +static const CMS_Menu cmsx_menuMissionSettings = { +#ifdef CMS_MENU_DEBUG + .GUARD_text = "MENUMISSIONSETTINGS", + .GUARD_type = OME_MENU, +#endif + .onEnter = NULL, + .onExit = NULL, + .onGlobalExit = NULL, + .entries = cmsx_menuMissionSettingsEntries +}; + static const OSD_Entry cmsx_menuNavigationEntries[] = { OSD_LABEL_ENTRY("-- NAVIGATION --"), @@ -188,6 +212,7 @@ static const OSD_Entry cmsx_menuNavigationEntries[] = OSD_SUBMENU_ENTRY("BASIC SETTINGS", &cmsx_menuNavSettings), OSD_SUBMENU_ENTRY("RTH", &cmsx_menuRTH), OSD_SUBMENU_ENTRY("FIXED WING", &cmsx_menuFWSettings), + OSD_SUBMENU_ENTRY("MISSIONS", &cmsx_menuMissionSettings), OSD_BACK_AND_END_ENTRY, }; From beb72ddf1a4fae749172fef285363ba287a01633 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Fri, 11 Jun 2021 23:36:07 +0100 Subject: [PATCH 037/102] First build --- src/main/io/osd.c | 8 +++++++- src/main/io/osd.h | 1 - src/main/navigation/navigation.c | 11 +++++------ src/main/navigation/navigation_private.h | 2 ++ 4 files changed, 14 insertions(+), 8 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index f0c4af8c24..a868c923ed 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -654,6 +654,9 @@ static void osdFormatCraftName(char *buff) static const char * osdArmingDisabledReasonMessage(void) { + const char *message = NULL; + char messageBuf[MAX(SETTING_MAX_NAME_LENGTH, OSD_MESSAGE_LENGTH+1)]; + switch (isArmingDisabledReason()) { case ARMING_DISABLED_FAILSAFE_SYSTEM: // See handling of FAILSAFE_RX_LOSS_MONITORING in failsafe.c @@ -678,6 +681,7 @@ static const char * osdArmingDisabledReasonMessage(void) #if defined(USE_NAV) // Check the exact reason switch (navigationIsBlockingArming(NULL)) { + char buf[6]; case NAV_ARMING_BLOCKER_NONE: break; case NAV_ARMING_BLOCKER_MISSING_GPS_FIX: @@ -685,7 +689,9 @@ static const char * osdArmingDisabledReasonMessage(void) case NAV_ARMING_BLOCKER_NAV_IS_ALREADY_ACTIVE: return OSD_MESSAGE_STR(OSD_MSG_DISABLE_NAV_FIRST); case NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR: - return OSD_MESSAGE_STR(OSD_MSG_1ST_WP_TOO_FAR); + osdFormatDistanceSymbol(buf, posControl.distanceToFirstWP, 0); + tfp_sprintf(messageBuf, "FIRST WP TOO FAR (%s)", buf); + return message = messageBuf; case NAV_ARMING_BLOCKER_JUMP_WAYPOINT_ERROR: return OSD_MESSAGE_STR(OSD_MSG_JUMP_WP_MISCONFIG); } diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 8f4e4d4bf9..0c53bbed16 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -53,7 +53,6 @@ #define OSD_MSG_SYS_OVERLOADED "SYSTEM OVERLOADED" #define OSD_MSG_WAITING_GPS_FIX "WAITING FOR GPS FIX" #define OSD_MSG_DISABLE_NAV_FIRST "DISABLE NAVIGATION FIRST" -#define OSD_MSG_1ST_WP_TOO_FAR "FIRST WAYPOINT IS TOO FAR" #define OSD_MSG_JUMP_WP_MISCONFIG "JUMP WAYPOINT MISCONFIGURED" #define OSD_MSG_MAG_NOT_CAL "COMPASS NOT CALIBRATED" #define OSD_MSG_ACC_NOT_CAL "ACCELEROMETER NOT CALIBRATED" diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 37a6c3c000..da4e96108b 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -2579,11 +2579,11 @@ void updateClimbRateToAltitudeController(float desiredClimbRate, climbRateToAlti } else { - /* + /* * If max altitude is set, reset climb rate if altitude is reached and climb rate is > 0 * In other words, when altitude is reached, allow it only to shrink */ - if (navConfig()->general.max_altitude > 0 && + if (navConfig()->general.max_altitude > 0 && altitudeToUse >= navConfig()->general.max_altitude && desiredClimbRate > 0 ) { @@ -3343,7 +3343,7 @@ navArmingBlocker_e navigationIsBlockingArming(bool *usedBypass) // Apply extra arming safety only if pilot has any of GPS modes configured if ((isUsingNavigationModes() || failsafeMayRequireNavigationMode()) && !((posControl.flags.estPosStatus >= EST_USABLE) && STATE(GPS_FIX_HOME))) { if (navConfig()->general.flags.extra_arming_safety == NAV_EXTRA_ARMING_SAFETY_ALLOW_BYPASS && - (STATE(NAV_EXTRA_ARMING_SAFETY_BYPASSED) || rxGetChannelValue(YAW) > 1750)) { + (STATE(NAV_EXTRA_ARMING_SAFETY_BYPASSED) || checkStickPosition(YAW_HI))) { if (usedBypass) { *usedBypass = true; } @@ -3361,10 +3361,9 @@ navArmingBlocker_e navigationIsBlockingArming(bool *usedBypass) if ((posControl.waypointCount > 0) && (navConfig()->general.waypoint_safe_distance != 0)) { fpVector3_t startingWaypointPos; mapWaypointToLocalPosition(&startingWaypointPos, &posControl.waypointList[0], GEO_ALT_RELATIVE); + posControl.distanceToFirstWP = calculateDistanceToDestination(&startingWaypointPos); - const bool navWpMissionStartTooFar = calculateDistanceToDestination(&startingWaypointPos) > navConfig()->general.waypoint_safe_distance; - - if (navWpMissionStartTooFar) { + if (posControl.distanceToFirstWP > navConfig()->general.waypoint_safe_distance && !checkStickPosition(YAW_HI)) { return NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR; } } diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h index b26299e707..0fd6c731c6 100755 --- a/src/main/navigation/navigation_private.h +++ b/src/main/navigation/navigation_private.h @@ -364,6 +364,8 @@ typedef struct { float wpDistance; // Distance to active WP timeMs_t wpReachedTime; // Time the waypoint was reached + uint32_t distanceToFirstWP; // Distance to first waypoint from arming location + /* Internals & statistics */ int16_t rcAdjustment[4]; float totalTripDistance; From ed95ca9d2371e008d049afe1e3152429c32b86a9 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sat, 12 Jun 2021 11:44:30 +0100 Subject: [PATCH 038/102] Change to function --- src/main/io/osd.c | 2 +- src/main/navigation/navigation.c | 13 ++++++++----- src/main/navigation/navigation.h | 1 + src/main/navigation/navigation_private.h | 2 -- 4 files changed, 10 insertions(+), 8 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index a868c923ed..22ad0e5686 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -689,7 +689,7 @@ static const char * osdArmingDisabledReasonMessage(void) case NAV_ARMING_BLOCKER_NAV_IS_ALREADY_ACTIVE: return OSD_MESSAGE_STR(OSD_MSG_DISABLE_NAV_FIRST); case NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR: - osdFormatDistanceSymbol(buf, posControl.distanceToFirstWP, 0); + osdFormatDistanceSymbol(buf, distanceToFirstWP(), 0); tfp_sprintf(messageBuf, "FIRST WP TOO FAR (%s)", buf); return message = messageBuf; case NAV_ARMING_BLOCKER_JUMP_WAYPOINT_ERROR: diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index da4e96108b..2c6594f70b 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -3327,6 +3327,13 @@ bool navigationTerrainFollowingEnabled(void) return posControl.flags.isTerrainFollowEnabled; } +uint32_t distanceToFirstWP(void) +{ + fpVector3_t startingWaypointPos; + mapWaypointToLocalPosition(&startingWaypointPos, &posControl.waypointList[0], GEO_ALT_RELATIVE); + return calculateDistanceToDestination(&startingWaypointPos); +} + navArmingBlocker_e navigationIsBlockingArming(bool *usedBypass) { const bool navBoxModesEnabled = IS_RC_MODE_ACTIVE(BOXNAVRTH) || IS_RC_MODE_ACTIVE(BOXNAVWP) || IS_RC_MODE_ACTIVE(BOXNAVPOSHOLD) || (STATE(FIXED_WING_LEGACY) && IS_RC_MODE_ACTIVE(BOXNAVALTHOLD)) || (STATE(FIXED_WING_LEGACY) && (IS_RC_MODE_ACTIVE(BOXNAVCOURSEHOLD) || IS_RC_MODE_ACTIVE(BOXNAVCRUISE))); @@ -3359,11 +3366,7 @@ navArmingBlocker_e navigationIsBlockingArming(bool *usedBypass) // Don't allow arming if first waypoint is farther than configured safe distance if ((posControl.waypointCount > 0) && (navConfig()->general.waypoint_safe_distance != 0)) { - fpVector3_t startingWaypointPos; - mapWaypointToLocalPosition(&startingWaypointPos, &posControl.waypointList[0], GEO_ALT_RELATIVE); - posControl.distanceToFirstWP = calculateDistanceToDestination(&startingWaypointPos); - - if (posControl.distanceToFirstWP > navConfig()->general.waypoint_safe_distance && !checkStickPosition(YAW_HI)) { + if (distanceToFirstWP() > navConfig()->general.waypoint_safe_distance && !checkStickPosition(YAW_HI)) { return NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR; } } diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index b71f932f99..fa674bdbc2 100755 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -513,6 +513,7 @@ geoAltitudeConversionMode_e waypointMissionAltConvMode(geoAltitudeDatumFlag_e da /* Distance/bearing calculation */ bool navCalculatePathToDestination(navDestinationPath_t *result, const fpVector3_t * destinationPos); +uint32_t distanceToFirstWP(void); /* Failsafe-forced RTH mode */ void activateForcedRTH(void); diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h index 0fd6c731c6..b26299e707 100755 --- a/src/main/navigation/navigation_private.h +++ b/src/main/navigation/navigation_private.h @@ -364,8 +364,6 @@ typedef struct { float wpDistance; // Distance to active WP timeMs_t wpReachedTime; // Time the waypoint was reached - uint32_t distanceToFirstWP; // Distance to first waypoint from arming location - /* Internals & statistics */ int16_t rcAdjustment[4]; float totalTripDistance; From 1b2d75dec78ab7daae8d76c1c7b0770bc339f811 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sun, 13 Jun 2021 14:07:45 +0100 Subject: [PATCH 039/102] WP mission Home WP option (#6920) * Initial build * Add new waypoint type FlyBy Home (FBH) * Revert "Add new waypoint type FlyBy Home (FBH)" This reverts commit a37dec56956a2c6a131e26dcd700ba6219d623e1. * Remove FBH WP type, use Home flag instead * Fixes --- src/main/fc/cli.c | 26 +++++++++++++------------- src/main/navigation/navigation.c | 11 +++++++++-- src/main/navigation/navigation.h | 1 + 3 files changed, 23 insertions(+), 15 deletions(-) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index e74e1b9813..5edafca5d9 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -1460,7 +1460,7 @@ static void cliWaypoints(char *cmdline) if (!(validArgumentCount == 6 || validArgumentCount == 8)) { cliShowParseError(); - } else if (!(action == 0 || action == NAV_WP_ACTION_WAYPOINT || action == NAV_WP_ACTION_RTH || action == NAV_WP_ACTION_JUMP || action == NAV_WP_ACTION_HOLD_TIME || action == NAV_WP_ACTION_LAND || action == NAV_WP_ACTION_SET_POI || action == NAV_WP_ACTION_SET_HEAD) || !(flag == 0 || flag == NAV_WP_FLAG_LAST)) { + } else if (!(action == 0 || action == NAV_WP_ACTION_WAYPOINT || action == NAV_WP_ACTION_RTH || action == NAV_WP_ACTION_JUMP || action == NAV_WP_ACTION_HOLD_TIME || action == NAV_WP_ACTION_LAND || action == NAV_WP_ACTION_SET_POI || action == NAV_WP_ACTION_SET_HEAD) || !(flag == 0 || flag == NAV_WP_FLAG_LAST || flag == NAV_WP_FLAG_HOME)) { cliShowParseError(); } else { posControl.waypointList[i].action = action; @@ -2930,28 +2930,28 @@ static void printImu2Status(void) cliPrintLinef("Acc: %d", secondaryImuState.calibrationStatus.acc); cliPrintLinef("Mag: %d", secondaryImuState.calibrationStatus.mag); cliPrintLine("Calibration gains:"); - + cliPrintLinef( - "Gyro: %d %d %d", - secondaryImuConfig()->calibrationOffsetGyro[X], - secondaryImuConfig()->calibrationOffsetGyro[Y], + "Gyro: %d %d %d", + secondaryImuConfig()->calibrationOffsetGyro[X], + secondaryImuConfig()->calibrationOffsetGyro[Y], secondaryImuConfig()->calibrationOffsetGyro[Z] ); cliPrintLinef( - "Acc: %d %d %d", - secondaryImuConfig()->calibrationOffsetAcc[X], - secondaryImuConfig()->calibrationOffsetAcc[Y], + "Acc: %d %d %d", + secondaryImuConfig()->calibrationOffsetAcc[X], + secondaryImuConfig()->calibrationOffsetAcc[Y], secondaryImuConfig()->calibrationOffsetAcc[Z] ); cliPrintLinef( - "Mag: %d %d %d", - secondaryImuConfig()->calibrationOffsetMag[X], - secondaryImuConfig()->calibrationOffsetMag[Y], + "Mag: %d %d %d", + secondaryImuConfig()->calibrationOffsetMag[X], + secondaryImuConfig()->calibrationOffsetMag[Y], secondaryImuConfig()->calibrationOffsetMag[Z] ); cliPrintLinef( - "Radius: %d %d", - secondaryImuConfig()->calibrationRadiusAcc, + "Radius: %d %d", + secondaryImuConfig()->calibrationRadiusAcc, secondaryImuConfig()->calibrationRadiusMag ); } diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 1492451b0b..ad81703e21 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -2933,8 +2933,15 @@ static void mapWaypointToLocalPosition(fpVector3_t * localPos, const navWaypoint { gpsLocation_t wpLLH; - wpLLH.lat = waypoint->lat; - wpLLH.lon = waypoint->lon; + /* Default to home position if lat & lon = 0 or HOME flag set + * Applicable to WAYPOINT, HOLD_TIME & LANDING WP types */ + if ((waypoint->lat == 0 && waypoint->lon == 0) || waypoint->flag == NAV_WP_FLAG_HOME) { + wpLLH.lat = GPS_home.lat; + wpLLH.lon = GPS_home.lon; + } else { + wpLLH.lat = waypoint->lat; + wpLLH.lon = waypoint->lon; + } wpLLH.alt = waypoint->alt; geoConvertGeodeticToLocal(localPos, &posControl.gpsOrigin, &wpLLH, altConv); diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 6f87ce3909..a29a4485ce 100755 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -306,6 +306,7 @@ typedef enum { } navWaypointHeadings_e; typedef enum { + NAV_WP_FLAG_HOME = 0x48, NAV_WP_FLAG_LAST = 0xA5 } navWaypointFlags_e; From f1d866b069b9caeb5ffed0bc72236d08734c096f Mon Sep 17 00:00:00 2001 From: scavanger Date: Sun, 30 May 2021 11:42:19 +0200 Subject: [PATCH 040/102] DJI HD FPY improvements --- src/main/fc/rc_adjustments.c | 11 + src/main/fc/rc_adjustments.h | 1 + src/main/fc/settings.yaml | 30 +- src/main/io/osd_dji_hd.c | 571 ++++++++++++++++++++++++----------- src/main/io/osd_dji_hd.h | 13 + 5 files changed, 453 insertions(+), 173 deletions(-) diff --git a/src/main/fc/rc_adjustments.c b/src/main/fc/rc_adjustments.c index c5c67436a1..7019869591 100644 --- a/src/main/fc/rc_adjustments.c +++ b/src/main/fc/rc_adjustments.c @@ -722,3 +722,14 @@ bool isAdjustmentFunctionSelected(uint8_t adjustmentFunction) { } return false; } + +uint8_t getActiveAdjustmentFunctions(uint8_t *adjustmentFunctions) { + uint8_t adjustmentCount = 0; + for (uint8_t i = 0; i < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT; i++) { + if (adjustmentStates[i].config) { + adjustmentCount++; + adjustmentFunctions[i] = adjustmentStates[i].config->adjustmentFunction; + } + } + return adjustmentCount; +} diff --git a/src/main/fc/rc_adjustments.h b/src/main/fc/rc_adjustments.h index 8736978825..93dd3d7e61 100644 --- a/src/main/fc/rc_adjustments.h +++ b/src/main/fc/rc_adjustments.h @@ -144,3 +144,4 @@ void updateAdjustmentStates(bool canUseRxData); struct controlRateConfig_s; void processRcAdjustments(struct controlRateConfig_s *controlRateConfig, bool canUseRxData); bool isAdjustmentFunctionSelected(uint8_t adjustmentFunction); +uint8_t getActiveAdjustmentFunctions(uint8_t *adjustmentFunctions); diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 8bf61790e3..343437bcb4 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -179,6 +179,10 @@ tables: - name: nav_rth_climb_first enum: navRTHClimbFirst_e values: ["OFF", "ON", "ON_FW_SPIRAL"] + - name: djiRssiSource + values: ["RSSI", "CRSF_LQ"] + enum: djiRssiSource_e + constants: RPYL_PID_MIN: 0 @@ -3634,7 +3638,7 @@ groups: max: UINT8_MAX default_value: 1 - name: dji_use_name_for_messages - description: "Re-purpose the craft name field for messages. Replace craft name with :WTSED for Warnings|Throttle|Speed|Efficiency|Trip distance" + description: "Re-purpose the craft name field for messages." default_value: ON field: use_name_for_messages type: bool @@ -3644,6 +3648,30 @@ groups: field: esc_temperature_source table: djiOsdTempSource type: uint8_t + - name: dji_message_speed_source + description: "Sets the speed type displayed by the DJI OSD in craft name: GROUND, 3D, AIR" + default_value: "3D" + field: messageSpeedSource + table: osdSpeedSource + type: uint8_t + - name: dji_rssi_source + description: "Source of the DJI RSSI field: RSSI, CRSF_LQ" + default_value: "RSSI" + field: rssi_source + table: djiRssiSource + type: uint8_t + - name: dji_use_adjustments + description: "Show inflight adjustments in craft name field" + default_value: OFF + type: bool + field: useAdjustments + - name: dji_cn_alternating_duration + description: "Alternating duration of craft name elements, in tenths of a second" + default_value: 30 + min: 1 + max: 150 + field: craftNameAlternatingDuration + type: uint8_t - name: PG_BEEPER_CONFIG type: beeperConfig_t diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index 0c9916d33a..8697b46e9d 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -49,6 +49,7 @@ #include "fc/fc_msp_box.h" #include "fc/runtime_config.h" #include "fc/settings.h" +#include "fc/rc_adjustments.h" #include "flight/imu.h" #include "flight/pid.h" @@ -70,6 +71,7 @@ #include "sensors/esc_sensor.h" #include "sensors/temperature.h" #include "sensors/pitotmeter.h" +#include "sensors/boardalignment.h" #include "msp/msp.h" #include "msp/msp_protocol.h" @@ -125,8 +127,25 @@ PG_RESET_TEMPLATE(djiOsdConfig_t, djiOsdConfig, .use_name_for_messages = SETTING_DJI_USE_NAME_FOR_MESSAGES_DEFAULT, .esc_temperature_source = SETTING_DJI_ESC_TEMP_SOURCE_DEFAULT, .proto_workarounds = SETTING_DJI_WORKAROUNDS_DEFAULT, + .messageSpeedSource = SETTING_DJI_MESSAGE_SPEED_SOURCE_DEFAULT, + .rssi_source = SETTING_DJI_RSSI_SOURCE_DEFAULT, + .useAdjustments = SETTING_DJI_USE_ADJUSTMENTS_DEFAULT, + .craftNameAlternatingDuration = SETTING_DJI_CN_ALTERNATING_DURATION_DEFAULT ); +#define RSSI_BOUNDARY(PERCENT) (RSSI_MAX_VALUE / 100 * PERCENT) + +typedef enum { + DJI_OSD_CN_MESSAGES, + DJI_OSD_CN_THROTTLE, + DJI_OSD_CN_THROTTLE_AUTO_THR, + DJI_OSD_CN_AIR_SPEED, + DJI_OSD_CN_EFFICIENCY, + DJI_OSD_CN_DISTANCE, + DJI_OSD_CN_ADJUSTEMNTS, + DJI_OSD_CN_MAX_ELEMENTS +} DjiCraftNameElements_t; + // External dependency on looptime extern timeDelta_t cycleTime; @@ -413,7 +432,7 @@ static void djiSerializeOSDConfigReply(sbuf_t *dst) //sbufWriteU8(dst, DJI_OSD_SCREEN_HEIGHT); // osdConfig()->camera_frame_height } -static const char * osdArmingDisabledReasonMessage(void) +static char * osdArmingDisabledReasonMessage(void) { switch (isArmingDisabledReason()) { case ARMING_DISABLED_FAILSAFE_SYSTEM: @@ -522,7 +541,7 @@ static const char * osdArmingDisabledReasonMessage(void) return NULL; } -static const char * osdFailsafePhaseMessage(void) +static char * osdFailsafePhaseMessage(void) { // See failsafe.h for each phase explanation switch (failsafePhase()) { @@ -563,7 +582,7 @@ static const char * osdFailsafePhaseMessage(void) return NULL; } -static const char * osdFailsafeInfoMessage(void) +static char * osdFailsafeInfoMessage(void) { if (failsafeIsReceivingRxData()) { // User must move sticks to exit FS mode @@ -573,7 +592,7 @@ static const char * osdFailsafeInfoMessage(void) return OSD_MESSAGE_STR(RC_RX_LINK_LOST_MSG); } -static const char * navigationStateMessage(void) +static char * navigationStateMessage(void) { switch (NAV_Status.state) { case MW_NAV_STATE_NONE: @@ -649,16 +668,35 @@ static int32_t osdConvertVelocityToUnit(int32_t vel) * Converts velocity into a string based on the current unit system. * @param alt Raw velocity (i.e. as taken from gpsSol.groundSpeed in centimeters/seconds) */ -void osdDJIFormatVelocityStr(char* buff, int32_t vel ) +void osdDJIFormatVelocityStr(char* buff) { + char sourceBuf[4]; + int vel = 0; + switch (djiOsdConfig()->messageSpeedSource) { + case OSD_SPEED_SOURCE_GROUND: + strcpy(sourceBuf, "GRD"); + vel = gpsSol.groundSpeed; + break; + case OSD_SPEED_SOURCE_3D: + strcpy(sourceBuf, "3D"); + vel = osdGet3DSpeed(); + break; + case OSD_SPEED_SOURCE_AIR: + strcpy(sourceBuf, "AIR"); +#ifdef USE_PITOT + vel = pitot.airSpeed; +#endif + break; + } + switch (osdConfig()->units) { case OSD_UNIT_UK: FALLTHROUGH; case OSD_UNIT_IMPERIAL: - tfp_sprintf(buff, "%3d%s", (int)osdConvertVelocityToUnit(vel), "MPH"); + tfp_sprintf(buff, "%s %3d MPH", sourceBuf, (int)osdConvertVelocityToUnit(vel)); break; case OSD_UNIT_METRIC: - tfp_sprintf(buff, "%3d%s", (int)osdConvertVelocityToUnit(vel), "KMH"); + tfp_sprintf(buff, "%s %3d KPH", sourceBuf, (int)osdConvertVelocityToUnit(vel)); break; } } @@ -726,175 +764,353 @@ static void osdDJIEfficiencyMahPerKM(char *buff) 1, US2S(efficiencyTimeDelta)); efficiencyUpdated = currentTimeUs; - } - else { + } else { value = eFilterState.state; } } if (value > 0 && value <= 999) { tfp_sprintf(buff, "%3d%s", (int)value, "mAhKM"); - } - else { + } else { tfp_sprintf(buff, "%s", "---mAhKM"); } } -static void djiSerializeCraftNameOverride(sbuf_t *dst, const char * name) +static void osdDJIAdjustmentMessage(char *buff, uint8_t adjustmentFunction) { - // :W T S E D - // | | | | Distance Trip - // | | | Efficiency mA/KM - // | | S 3dSpeed - // | Throttle - // Warnings - const char *message = " "; - const char *enabledElements = name + 1; - char djibuf[24]; - - // clear name from chars : and leading W - if (enabledElements[0] == 'W') { - enabledElements += 1; - } - - int elemLen = strlen(enabledElements); - - if (elemLen > 0) { - switch (enabledElements[OSD_ALTERNATING_CHOICES(3000, elemLen)]){ - case 'T': - osdDJIFormatThrottlePosition(djibuf,true); - break; - case 'S': - osdDJIFormatVelocityStr(djibuf, osdGet3DSpeed()); - break; - case 'E': - osdDJIEfficiencyMahPerKM(djibuf); - break; - case 'D': - osdDJIFormatDistanceStr(djibuf, getTotalTravelDistance()); - break; - case 'W': - tfp_sprintf(djibuf, "%s", "MAKE_W_FIRST"); - break; - default: - tfp_sprintf(djibuf, "%s", "UNKOWN_ELEM"); - break; - } - - if (djibuf[0] != '\0') { - message = djibuf; - } - } - - if (name[1] == 'W') { - char messageBuf[MAX(SETTING_MAX_NAME_LENGTH, OSD_MESSAGE_LENGTH+1)]; - if (ARMING_FLAG(ARMED)) { - // Aircraft is armed. We might have up to 5 - // messages to show. - const char *messages[5]; - unsigned messageCount = 0; - - if (FLIGHT_MODE(FAILSAFE_MODE)) { - // In FS mode while being armed too - const char *failsafePhaseMessage = osdFailsafePhaseMessage(); - const char *failsafeInfoMessage = osdFailsafeInfoMessage(); - const char *navStateFSMessage = navigationStateMessage(); - - if (failsafePhaseMessage) { - messages[messageCount++] = failsafePhaseMessage; - } - - if (failsafeInfoMessage) { - messages[messageCount++] = failsafeInfoMessage; - } - - if (navStateFSMessage) { - messages[messageCount++] = navStateFSMessage; - } - - if (messageCount > 0) { - message = messages[OSD_ALTERNATING_CHOICES(1000, messageCount)]; - if (message == failsafeInfoMessage) { - // failsafeInfoMessage is not useful for recovering - // a lost model, but might help avoiding a crash. - // Blink to grab user attention. - //doesnt work TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - // We're shoing either failsafePhaseMessage or - // navStateFSMessage. Don't BLINK here since - // having this text available might be crucial - // during a lost aircraft recovery and blinking - // will cause it to be missing from some frames. - } - } - else { - if (FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding()) { - const char *navStateMessage = navigationStateMessage(); - if (navStateMessage) { - messages[messageCount++] = navStateMessage; - } - } - else if (STATE(FIXED_WING_LEGACY) && (navGetCurrentStateFlags() & NAV_CTL_LAUNCH)) { - messages[messageCount++] = "AUTOLAUNCH"; - } - else { - if (FLIGHT_MODE(NAV_ALTHOLD_MODE) && !navigationRequiresAngleMode()) { - // ALTHOLD might be enabled alongside ANGLE/HORIZON/ACRO - // when it doesn't require ANGLE mode (required only in FW - // right now). If if requires ANGLE, its display is handled - // by OSD_FLYMODE. - messages[messageCount++] = "(ALT HOLD)"; - } - if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM)) { - messages[messageCount++] = "(AUTOTRIM)"; - } - if (IS_RC_MODE_ACTIVE(BOXAUTOTUNE)) { - messages[messageCount++] = "(AUTOTUNE)"; - } - if (FLIGHT_MODE(HEADFREE_MODE)) { - messages[messageCount++] = "(HEADFREE)"; - } - } - // Pick one of the available messages. Each message lasts - // a second. - if (messageCount > 0) { - message = messages[OSD_ALTERNATING_CHOICES(1000, messageCount)]; - } - } - } - else if (ARMING_FLAG(ARMING_DISABLED_ALL_FLAGS)) { - unsigned invalidIndex; - // Check if we're unable to arm for some reason - if (ARMING_FLAG(ARMING_DISABLED_INVALID_SETTING) && !settingsValidate(&invalidIndex)) { - if (OSD_ALTERNATING_CHOICES(1000, 2) == 0) { - const setting_t *setting = settingGet(invalidIndex); - settingGetName(setting, messageBuf); - for (int ii = 0; messageBuf[ii]; ii++) { - messageBuf[ii] = sl_toupper(messageBuf[ii]); - } - message = messageBuf; - } - else { - message = "ERR SETTING"; - // TEXT_ATTRIBUTES_ADD_INVERTED(elemAttr); - } - } - else { - if (OSD_ALTERNATING_CHOICES(1000, 2) == 0) { - message = "CANT ARM"; - // TEXT_ATTRIBUTES_ADD_INVERTED(elemAttr); - } else { - // Show the reason for not arming - message = osdArmingDisabledReasonMessage(); - } - } - } - } - - if (message[0] != '\0') { - sbufWriteData(dst, message, strlen(message)); + switch (adjustmentFunction) { + case ADJUSTMENT_RC_EXPO: + tfp_sprintf(buff, "RC EXP %d", currentControlRateProfile->stabilized.rcExpo8); + break; + case ADJUSTMENT_RC_YAW_EXPO: + tfp_sprintf(buff, "RC Y EXP %3d", currentControlRateProfile->stabilized.rcYawExpo8); + break; + case ADJUSTMENT_MANUAL_RC_EXPO: + tfp_sprintf(buff, "M RC EXP %3d", currentControlRateProfile->manual.rcExpo8); + break; + case ADJUSTMENT_MANUAL_RC_YAW_EXPO: + tfp_sprintf(buff, "M RC Y EXP %3d", currentControlRateProfile->manual.rcYawExpo8); + break; + case ADJUSTMENT_THROTTLE_EXPO: + tfp_sprintf(buff, "THR EXP %3d", currentControlRateProfile->throttle.rcExpo8); + break; + case ADJUSTMENT_PITCH_ROLL_RATE: + tfp_sprintf(buff, "PR %3d RR %3d", currentControlRateProfile->stabilized.rates[FD_PITCH], currentControlRateProfile->stabilized.rates[FD_ROLL]); + break; + case ADJUSTMENT_PITCH_RATE: + tfp_sprintf(buff, "PR %3d", currentControlRateProfile->stabilized.rates[FD_PITCH]); + break; + case ADJUSTMENT_ROLL_RATE: + tfp_sprintf(buff, "RR %3d", currentControlRateProfile->stabilized.rates[FD_ROLL]); + break; + case ADJUSTMENT_MANUAL_PITCH_ROLL_RATE: + tfp_sprintf(buff, "M PR %3d RR %3d", currentControlRateProfile->manual.rates[FD_PITCH], currentControlRateProfile->manual.rates[FD_ROLL]); + break; + case ADJUSTMENT_MANUAL_PITCH_RATE: + tfp_sprintf(buff, "M PR %3d", currentControlRateProfile->manual.rates[FD_PITCH]); + break; + case ADJUSTMENT_MANUAL_ROLL_RATE: + tfp_sprintf(buff, "M RR %3d", currentControlRateProfile->manual.rates[FD_ROLL]); + break; + case ADJUSTMENT_YAW_RATE: + tfp_sprintf(buff, "YR %3d", currentControlRateProfile->stabilized.rates[FD_YAW]); + break; + case ADJUSTMENT_MANUAL_YAW_RATE: + tfp_sprintf(buff, "M YR %3d", currentControlRateProfile->manual.rates[FD_YAW]); + break; + case ADJUSTMENT_PITCH_ROLL_P: + tfp_sprintf(buff, "PP %3d RP %3d", pidBankMutable()->pid[PID_PITCH].P, pidBankMutable()->pid[PID_ROLL].P); + break; + case ADJUSTMENT_PITCH_P: + tfp_sprintf(buff, "PP %3d", pidBankMutable()->pid[PID_PITCH].P); + break; + case ADJUSTMENT_ROLL_P: + tfp_sprintf(buff, "RP %3d", pidBankMutable()->pid[PID_ROLL].P); + break; + case ADJUSTMENT_PITCH_ROLL_I: + tfp_sprintf(buff, "PI %3d RI %3d", pidBankMutable()->pid[PID_PITCH].I, pidBankMutable()->pid[PID_ROLL].I); + break; + case ADJUSTMENT_PITCH_I: + tfp_sprintf(buff, "PI %3d", pidBankMutable()->pid[PID_PITCH].I); + break; + case ADJUSTMENT_ROLL_I: + tfp_sprintf(buff, "RI %3d", pidBankMutable()->pid[PID_ROLL].I); + break; + case ADJUSTMENT_PITCH_ROLL_D: + tfp_sprintf(buff, "PD %3d RD %3d", pidBankMutable()->pid[PID_PITCH].D, pidBankMutable()->pid[PID_ROLL].D); + break; + case ADJUSTMENT_PITCH_ROLL_FF: + tfp_sprintf(buff, "PFF %3d RFF %3d", pidBankMutable()->pid[PID_PITCH].FF, pidBankMutable()->pid[PID_ROLL].FF); + break; + case ADJUSTMENT_PITCH_D: + tfp_sprintf(buff, "PD %3d", pidBankMutable()->pid[PID_PITCH].D); + break; + case ADJUSTMENT_PITCH_FF: + tfp_sprintf(buff, "PFF %3d", pidBankMutable()->pid[PID_PITCH].FF); + break; + case ADJUSTMENT_ROLL_D: + tfp_sprintf(buff, "RD %3d", pidBankMutable()->pid[PID_ROLL].D); + break; + case ADJUSTMENT_ROLL_FF: + tfp_sprintf(buff, "RFF %3d", pidBankMutable()->pid[PID_ROLL].FF); + break; + case ADJUSTMENT_YAW_P: + tfp_sprintf(buff, "Y P %3d", pidBankMutable()->pid[PID_YAW].P); + break; + case ADJUSTMENT_YAW_I: + tfp_sprintf(buff, "YI %3d", pidBankMutable()->pid[PID_YAW].I); + break; + case ADJUSTMENT_YAW_D: + tfp_sprintf(buff, "YD %3d", pidBankMutable()->pid[PID_YAW].D); + break; + case ADJUSTMENT_YAW_FF: + tfp_sprintf(buff, "YFF %3d", pidBankMutable()->pid[PID_YAW].FF); + break; + case ADJUSTMENT_NAV_FW_CRUISE_THR: + tfp_sprintf(buff, "CRS THR %4d", navConfigMutable()->fw.cruise_throttle); + break; + case ADJUSTMENT_NAV_FW_PITCH2THR: + tfp_sprintf(buff, "P2THR %3d", navConfigMutable()->fw.pitch_to_throttle); + break; + case ADJUSTMENT_ROLL_BOARD_ALIGNMENT: + tfp_sprintf(buff, "BA R %3d", boardAlignment()->rollDeciDegrees); + break; + case ADJUSTMENT_PITCH_BOARD_ALIGNMENT: + tfp_sprintf(buff, "BA P %3d", boardAlignment()->pitchDeciDegrees); + break; + case ADJUSTMENT_LEVEL_P: + tfp_sprintf(buff, "LVL P %3d", pidBankMutable()->pid[PID_LEVEL].P); + break; + case ADJUSTMENT_LEVEL_I: + tfp_sprintf(buff, "LVL I %3d", pidBankMutable()->pid[PID_LEVEL].I); + break; + case ADJUSTMENT_LEVEL_D: + tfp_sprintf(buff, "LVL D %3d", pidBankMutable()->pid[PID_LEVEL].D); + break; + case ADJUSTMENT_POS_XY_P: + tfp_sprintf(buff, "POS XY P %3d", pidBankMutable()->pid[PID_POS_XY].P); + break; + case ADJUSTMENT_POS_XY_I: + tfp_sprintf(buff, "POS XY I %3d", pidBankMutable()->pid[PID_POS_XY].I); + break; + case ADJUSTMENT_POS_XY_D: + tfp_sprintf(buff, "POS XY D %3d", pidBankMutable()->pid[PID_POS_XY].D); + break; + case ADJUSTMENT_POS_Z_P: + tfp_sprintf(buff, "POS Z P %3d", pidBankMutable()->pid[PID_POS_Z].P); + break; + case ADJUSTMENT_POS_Z_I: + tfp_sprintf(buff, "POS Z I %3d", pidBankMutable()->pid[PID_POS_Z].I); + break; + case ADJUSTMENT_POS_Z_D: + tfp_sprintf(buff, "POS Z D %3d", pidBankMutable()->pid[PID_POS_Z].D); + break; + case ADJUSTMENT_HEADING_P: + tfp_sprintf(buff, "HEAD P %3d", pidBankMutable()->pid[PID_HEADING].P); + break; + case ADJUSTMENT_VEL_XY_P: + tfp_sprintf(buff, "VEL XY P %3d", pidBankMutable()->pid[PID_VEL_XY].P); + break; + case ADJUSTMENT_VEL_XY_I: + tfp_sprintf(buff, "VEL XY I %3d", pidBankMutable()->pid[PID_VEL_XY].I); + break; + case ADJUSTMENT_VEL_XY_D: + tfp_sprintf(buff, "VEL XY D %3d", pidBankMutable()->pid[PID_VEL_XY].D); + break; + case ADJUSTMENT_VEL_Z_P: + tfp_sprintf(buff, "VEL Z P %3d", pidBankMutable()->pid[PID_VEL_Z].P); + break; + case ADJUSTMENT_VEL_Z_I: + tfp_sprintf(buff, "VEL Z I %3d", pidBankMutable()->pid[PID_VEL_Z].I); + break; + case ADJUSTMENT_VEL_Z_D: + tfp_sprintf(buff, "VEL Z D %3d", pidBankMutable()->pid[PID_VEL_Z].D); + break; + case ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE: + tfp_sprintf(buff, "MIN THR DPA %4d", mixerConfigMutable()->fwMinThrottleDownPitchAngle); + break; + case ADJUSTMENT_TPA: + tfp_sprintf(buff, "TPA %3d", currentControlRateProfile->throttle.dynPID); + break; + case ADJUSTMENT_TPA_BREAKPOINT: + tfp_sprintf(buff, "TPA BP %4d", currentControlRateProfile->throttle.pa_breakpoint); + break; + case ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS: + tfp_sprintf(buff, "CTR SMOTH %3d", navConfigMutable()->fw.control_smoothness); + break; + default: + tfp_sprintf(buff, "UNSUPPORTED"); + break; } } + +static bool osdDJIFormatAdjustments(char *buff) +{ + uint8_t adjustmentFunctions[MAX_SIMULTANEOUS_ADJUSTMENT_COUNT]; + uint8_t adjustmentCount = getActiveAdjustmentFunctions(adjustmentFunctions); + + if (adjustmentCount > 0 && buff != NULL) { + osdDJIAdjustmentMessage(buff, adjustmentFunctions[OSD_ALTERNATING_CHOICES(DJI_ALTERNATING_DURATION_LONG, adjustmentCount)]); + } + + return adjustmentCount > 0; +} + + +static bool djiFormatMessages(char *buff) +{ + bool haveMessage = false; + char messageBuf[MAX(SETTING_MAX_NAME_LENGTH, OSD_MESSAGE_LENGTH+1)]; + if (ARMING_FLAG(ARMED)) { + // Aircraft is armed. We might have up to 5 + // messages to show. + char *messages[5]; + unsigned messageCount = 0; + + if (FLIGHT_MODE(FAILSAFE_MODE)) { + // In FS mode while being armed too + char *failsafePhaseMessage = osdFailsafePhaseMessage(); + char *failsafeInfoMessage = osdFailsafeInfoMessage(); + char *navStateFSMessage = navigationStateMessage(); + + if (failsafePhaseMessage) { + messages[messageCount++] = failsafePhaseMessage; + } + + if (failsafeInfoMessage) { + messages[messageCount++] = failsafeInfoMessage; + } + + if (navStateFSMessage) { + messages[messageCount++] = navStateFSMessage; + } + } else { + if (FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding()) { + char *navStateMessage = navigationStateMessage(); + if (navStateMessage) { + messages[messageCount++] = navStateMessage; + } + } else if (STATE(FIXED_WING_LEGACY) && (navGetCurrentStateFlags() & NAV_CTL_LAUNCH)) { + messages[messageCount++] = "AUTOLAUNCH"; + } else { + if (FLIGHT_MODE(NAV_ALTHOLD_MODE) && !navigationRequiresAngleMode()) { + // ALTHOLD might be enabled alongside ANGLE/HORIZON/ACRO + // when it doesn't require ANGLE mode (required only in FW + // right now). If if requires ANGLE, its display is handled + // by OSD_FLYMODE. + messages[messageCount++] = "(ALT HOLD)"; + } + + if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM)) { + messages[messageCount++] = "(AUTOTRIM)"; + } + + if (IS_RC_MODE_ACTIVE(BOXAUTOTUNE)) { + messages[messageCount++] = "(AUTOTUNE)"; + } + + if (FLIGHT_MODE(HEADFREE_MODE)) { + messages[messageCount++] = "(HEADFREE)"; + } + + if (FLIGHT_MODE(MANUAL_MODE)) { + messages[messageCount++] = "(MANUAL)"; + } + } + } + // Pick one of the available messages. Each message lasts + // a second. + if (messageCount > 0) { + strcpy(buff, messages[OSD_ALTERNATING_CHOICES(DJI_ALTERNATING_DURATION_SHORT, messageCount)]);; + haveMessage = true; + } + } else if (ARMING_FLAG(ARMING_DISABLED_ALL_FLAGS)) { + unsigned invalidIndex; + // Check if we're unable to arm for some reason + if (ARMING_FLAG(ARMING_DISABLED_INVALID_SETTING) && !settingsValidate(&invalidIndex)) { + if (OSD_ALTERNATING_CHOICES(DJI_ALTERNATING_DURATION_SHORT, 2) == 0) { + const setting_t *setting = settingGet(invalidIndex); + settingGetName(setting, messageBuf); + for (int ii = 0; messageBuf[ii]; ii++) { + messageBuf[ii] = sl_toupper(messageBuf[ii]); + } + strcpy(buff, messageBuf); + } else { + strcpy(buff, "ERR SETTING"); + // TEXT_ATTRIBUTES_ADD_INVERTED(elemAttr); + } + } else { + if (OSD_ALTERNATING_CHOICES(DJI_ALTERNATING_DURATION_SHORT, 2) == 0) { + strcpy(buff, "CANT ARM"); + // TEXT_ATTRIBUTES_ADD_INVERTED(elemAttr); + } else { + // Show the reason for not arming + strcpy(buff, osdArmingDisabledReasonMessage()); + } + } + haveMessage = true; + } + return haveMessage; +} + +static void djiSerializeCraftNameOverride(sbuf_t *dst) +{ + char djibuf[DJI_CRAFT_NAME_LENGTH] = "\0"; + uint16_t *osdLayoutConfig = (uint16_t*)(osdLayoutsConfig()->item_pos[0]); + + if (!(OSD_VISIBLE(osdLayoutConfig[OSD_MESSAGES]) && djiFormatMessages(djibuf)) + && !(djiOsdConfig()->useAdjustments && osdDJIFormatAdjustments(djibuf))) { + + DjiCraftNameElements_t activeElements[DJI_OSD_CN_MAX_ELEMENTS]; + uint8_t activeElementsCount = 0; + + if (OSD_VISIBLE(osdLayoutConfig[OSD_THROTTLE_POS])) { + activeElements[activeElementsCount++] = DJI_OSD_CN_THROTTLE; + } + + if (OSD_VISIBLE(osdLayoutConfig[OSD_THROTTLE_POS_AUTO_THR])) { + activeElements[activeElementsCount++] = DJI_OSD_CN_THROTTLE_AUTO_THR; + } + + if (OSD_VISIBLE(osdLayoutConfig[OSD_3D_SPEED])) { + activeElements[activeElementsCount++] = DJI_OSD_CN_AIR_SPEED; + } + + if (OSD_VISIBLE(osdLayoutConfig[OSD_EFFICIENCY_MAH_PER_KM])) { + activeElements[activeElementsCount++] = DJI_OSD_CN_EFFICIENCY; + } + + if (OSD_VISIBLE(osdLayoutConfig[OSD_TRIP_DIST])) { + activeElements[activeElementsCount++] = DJI_OSD_CN_DISTANCE; + } + + switch (activeElements[OSD_ALTERNATING_CHOICES(DJI_ALTERNATING_DURATION_LONG, activeElementsCount)]) + { + case DJI_OSD_CN_THROTTLE: + osdDJIFormatThrottlePosition(djibuf, false); + break; + case DJI_OSD_CN_THROTTLE_AUTO_THR: + osdDJIFormatThrottlePosition(djibuf, true); + break; + case DJI_OSD_CN_AIR_SPEED: + osdDJIFormatVelocityStr(djibuf); + break; + case DJI_OSD_CN_EFFICIENCY: + osdDJIEfficiencyMahPerKM(djibuf); + break; + case DJI_OSD_CN_DISTANCE: + osdDJIFormatDistanceStr(djibuf, getTotalTravelDistance()); + break; + default: + break; + } + } + + if (djibuf[0] != '\0') { + sbufWriteData(dst, djibuf, strlen(djibuf)); + } +} + #endif @@ -935,14 +1151,7 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms #if defined(USE_OSD) if (djiOsdConfig()->use_name_for_messages) { - if (name[0] == ':') { - // If craft name starts with a semicolon - use it as a template for what we want to show - djiSerializeCraftNameOverride(dst, name); - } - else { - // Otherwise fall back to just warnings - djiSerializeCraftNameOverride(dst, ":W"); - } + djiSerializeCraftNameOverride(dst); } else #endif @@ -1027,7 +1236,25 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms case DJI_MSP_ANALOG: sbufWriteU8(dst, constrain(getBatteryVoltage() / 10, 0, 255)); sbufWriteU16(dst, constrain(getMAhDrawn(), 0, 0xFFFF)); // milliamp hours drawn from battery - sbufWriteU16(dst, getRSSI()); +#ifdef USE_SERIALRX_CRSF + // Range of RSSI field: 0-99: 99 = 150 hz , 70 - 98 50 hz, <70 4 hz + if (djiOsdConfig()->rssi_source == DJI_CRSF_LQ) { + uint16_t scaledLq = 0; + if (rxLinkStatistics.rfMode == 2) { + scaledLq = RSSI_MAX_VALUE; + } else if (rxLinkStatistics.rfMode == 1) { + scaledLq = scaleRange(constrain(rxLinkStatistics.uplinkLQ, 0, 100), 0, 100, RSSI_BOUNDARY(70), RSSI_BOUNDARY(99)); + } else if (rxLinkStatistics.rfMode == 0) { + scaledLq = scaleRange(constrain(rxLinkStatistics.uplinkLQ, 0, 100), 0, 100, 0, RSSI_BOUNDARY(69)); + } + sbufWriteU16(dst, scaledLq); + } else { +#else + sbufWriteU16(dst, getRSSI()); +#endif +#ifdef USE_SERIALRX_CRSF + } +#endif sbufWriteU16(dst, constrain(getAmperage(), -0x8000, 0x7FFF)); // send amperage in 0.01 A steps, range is -320A to 320A sbufWriteU16(dst, getBatteryVoltage()); break; diff --git a/src/main/io/osd_dji_hd.h b/src/main/io/osd_dji_hd.h index d105b275b6..4b3e0a1479 100644 --- a/src/main/io/osd_dji_hd.h +++ b/src/main/io/osd_dji_hd.h @@ -62,12 +62,21 @@ #define DJI_MSP_SET_PID 202 #define DJI_MSP_SET_RC_TUNING 204 +#define DJI_CRAFT_NAME_LENGTH 24 +#define DJI_ALTERNATING_DURATION_LONG (djiOsdConfig()->craftNameAlternatingDuration * 100) +#define DJI_ALTERNATING_DURATION_SHORT 1000 + enum djiOsdTempSource_e { DJI_OSD_TEMP_ESC = 0, DJI_OSD_TEMP_CORE = 1, DJI_OSD_TEMP_BARO = 2 }; +enum djiRssiSource_e { + DJI_RSSI = 0, + DJI_CRSF_LQ = 1 +}; + enum djiOsdProtoWorkarounds_e { DJI_OSD_USE_NON_STANDARD_MSP_ESC_SENSOR_DATA = 1 << 0, }; @@ -76,6 +85,10 @@ typedef struct djiOsdConfig_s { uint8_t use_name_for_messages; uint8_t esc_temperature_source; uint8_t proto_workarounds; + uint8_t messageSpeedSource; + uint8_t rssi_source; + uint8_t useAdjustments; + uint8_t craftNameAlternatingDuration; } djiOsdConfig_t; PG_DECLARE(djiOsdConfig_t, djiOsdConfig); From 566e84144bfebb434014a1150aaafc970a792e2c Mon Sep 17 00:00:00 2001 From: scavanger Date: Tue, 8 Jun 2021 10:15:21 +0200 Subject: [PATCH 041/102] Add message for autolevel, adjustment messages shortened --- src/main/io/osd_dji_hd.c | 80 +++++++++++++++++++++------------------- 1 file changed, 42 insertions(+), 38 deletions(-) diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index 8697b46e9d..c81683ecc8 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -780,22 +780,22 @@ static void osdDJIAdjustmentMessage(char *buff, uint8_t adjustmentFunction) { switch (adjustmentFunction) { case ADJUSTMENT_RC_EXPO: - tfp_sprintf(buff, "RC EXP %d", currentControlRateProfile->stabilized.rcExpo8); + tfp_sprintf(buff, "RCE %d", currentControlRateProfile->stabilized.rcExpo8); break; case ADJUSTMENT_RC_YAW_EXPO: - tfp_sprintf(buff, "RC Y EXP %3d", currentControlRateProfile->stabilized.rcYawExpo8); + tfp_sprintf(buff, "RCYE %3d", currentControlRateProfile->stabilized.rcYawExpo8); break; case ADJUSTMENT_MANUAL_RC_EXPO: - tfp_sprintf(buff, "M RC EXP %3d", currentControlRateProfile->manual.rcExpo8); + tfp_sprintf(buff, "MRCE %3d", currentControlRateProfile->manual.rcExpo8); break; case ADJUSTMENT_MANUAL_RC_YAW_EXPO: - tfp_sprintf(buff, "M RC Y EXP %3d", currentControlRateProfile->manual.rcYawExpo8); + tfp_sprintf(buff, "MRCYE %3d", currentControlRateProfile->manual.rcYawExpo8); break; case ADJUSTMENT_THROTTLE_EXPO: - tfp_sprintf(buff, "THR EXP %3d", currentControlRateProfile->throttle.rcExpo8); + tfp_sprintf(buff, "TE %3d", currentControlRateProfile->throttle.rcExpo8); break; case ADJUSTMENT_PITCH_ROLL_RATE: - tfp_sprintf(buff, "PR %3d RR %3d", currentControlRateProfile->stabilized.rates[FD_PITCH], currentControlRateProfile->stabilized.rates[FD_ROLL]); + tfp_sprintf(buff, "PRR %3d %3d", currentControlRateProfile->stabilized.rates[FD_PITCH], currentControlRateProfile->stabilized.rates[FD_ROLL]); break; case ADJUSTMENT_PITCH_RATE: tfp_sprintf(buff, "PR %3d", currentControlRateProfile->stabilized.rates[FD_PITCH]); @@ -804,22 +804,22 @@ static void osdDJIAdjustmentMessage(char *buff, uint8_t adjustmentFunction) tfp_sprintf(buff, "RR %3d", currentControlRateProfile->stabilized.rates[FD_ROLL]); break; case ADJUSTMENT_MANUAL_PITCH_ROLL_RATE: - tfp_sprintf(buff, "M PR %3d RR %3d", currentControlRateProfile->manual.rates[FD_PITCH], currentControlRateProfile->manual.rates[FD_ROLL]); + tfp_sprintf(buff, "MPRR %3d %3d", currentControlRateProfile->manual.rates[FD_PITCH], currentControlRateProfile->manual.rates[FD_ROLL]); break; case ADJUSTMENT_MANUAL_PITCH_RATE: - tfp_sprintf(buff, "M PR %3d", currentControlRateProfile->manual.rates[FD_PITCH]); + tfp_sprintf(buff, "MPR %3d", currentControlRateProfile->manual.rates[FD_PITCH]); break; case ADJUSTMENT_MANUAL_ROLL_RATE: - tfp_sprintf(buff, "M RR %3d", currentControlRateProfile->manual.rates[FD_ROLL]); + tfp_sprintf(buff, "MRR %3d", currentControlRateProfile->manual.rates[FD_ROLL]); break; case ADJUSTMENT_YAW_RATE: tfp_sprintf(buff, "YR %3d", currentControlRateProfile->stabilized.rates[FD_YAW]); break; case ADJUSTMENT_MANUAL_YAW_RATE: - tfp_sprintf(buff, "M YR %3d", currentControlRateProfile->manual.rates[FD_YAW]); + tfp_sprintf(buff, "MYR %3d", currentControlRateProfile->manual.rates[FD_YAW]); break; case ADJUSTMENT_PITCH_ROLL_P: - tfp_sprintf(buff, "PP %3d RP %3d", pidBankMutable()->pid[PID_PITCH].P, pidBankMutable()->pid[PID_ROLL].P); + tfp_sprintf(buff, "PRP %3d %3d", pidBankMutable()->pid[PID_PITCH].P, pidBankMutable()->pid[PID_ROLL].P); break; case ADJUSTMENT_PITCH_P: tfp_sprintf(buff, "PP %3d", pidBankMutable()->pid[PID_PITCH].P); @@ -828,7 +828,7 @@ static void osdDJIAdjustmentMessage(char *buff, uint8_t adjustmentFunction) tfp_sprintf(buff, "RP %3d", pidBankMutable()->pid[PID_ROLL].P); break; case ADJUSTMENT_PITCH_ROLL_I: - tfp_sprintf(buff, "PI %3d RI %3d", pidBankMutable()->pid[PID_PITCH].I, pidBankMutable()->pid[PID_ROLL].I); + tfp_sprintf(buff, "PRI %3d %3d", pidBankMutable()->pid[PID_PITCH].I, pidBankMutable()->pid[PID_ROLL].I); break; case ADJUSTMENT_PITCH_I: tfp_sprintf(buff, "PI %3d", pidBankMutable()->pid[PID_PITCH].I); @@ -837,10 +837,10 @@ static void osdDJIAdjustmentMessage(char *buff, uint8_t adjustmentFunction) tfp_sprintf(buff, "RI %3d", pidBankMutable()->pid[PID_ROLL].I); break; case ADJUSTMENT_PITCH_ROLL_D: - tfp_sprintf(buff, "PD %3d RD %3d", pidBankMutable()->pid[PID_PITCH].D, pidBankMutable()->pid[PID_ROLL].D); + tfp_sprintf(buff, "PRD %3d %3d", pidBankMutable()->pid[PID_PITCH].D, pidBankMutable()->pid[PID_ROLL].D); break; case ADJUSTMENT_PITCH_ROLL_FF: - tfp_sprintf(buff, "PFF %3d RFF %3d", pidBankMutable()->pid[PID_PITCH].FF, pidBankMutable()->pid[PID_ROLL].FF); + tfp_sprintf(buff, "PRFF %3d %3d", pidBankMutable()->pid[PID_PITCH].FF, pidBankMutable()->pid[PID_ROLL].FF); break; case ADJUSTMENT_PITCH_D: tfp_sprintf(buff, "PD %3d", pidBankMutable()->pid[PID_PITCH].D); @@ -855,7 +855,7 @@ static void osdDJIAdjustmentMessage(char *buff, uint8_t adjustmentFunction) tfp_sprintf(buff, "RFF %3d", pidBankMutable()->pid[PID_ROLL].FF); break; case ADJUSTMENT_YAW_P: - tfp_sprintf(buff, "Y P %3d", pidBankMutable()->pid[PID_YAW].P); + tfp_sprintf(buff, "YP %3d", pidBankMutable()->pid[PID_YAW].P); break; case ADJUSTMENT_YAW_I: tfp_sprintf(buff, "YI %3d", pidBankMutable()->pid[PID_YAW].I); @@ -867,76 +867,76 @@ static void osdDJIAdjustmentMessage(char *buff, uint8_t adjustmentFunction) tfp_sprintf(buff, "YFF %3d", pidBankMutable()->pid[PID_YAW].FF); break; case ADJUSTMENT_NAV_FW_CRUISE_THR: - tfp_sprintf(buff, "CRS THR %4d", navConfigMutable()->fw.cruise_throttle); + tfp_sprintf(buff, "CR %4d", navConfigMutable()->fw.cruise_throttle); break; case ADJUSTMENT_NAV_FW_PITCH2THR: - tfp_sprintf(buff, "P2THR %3d", navConfigMutable()->fw.pitch_to_throttle); + tfp_sprintf(buff, "P2T %3d", navConfigMutable()->fw.pitch_to_throttle); break; case ADJUSTMENT_ROLL_BOARD_ALIGNMENT: - tfp_sprintf(buff, "BA R %3d", boardAlignment()->rollDeciDegrees); + tfp_sprintf(buff, "RBA %3d", boardAlignment()->rollDeciDegrees); break; case ADJUSTMENT_PITCH_BOARD_ALIGNMENT: - tfp_sprintf(buff, "BA P %3d", boardAlignment()->pitchDeciDegrees); + tfp_sprintf(buff, "PBA %3d", boardAlignment()->pitchDeciDegrees); break; case ADJUSTMENT_LEVEL_P: - tfp_sprintf(buff, "LVL P %3d", pidBankMutable()->pid[PID_LEVEL].P); + tfp_sprintf(buff, "LP %3d", pidBankMutable()->pid[PID_LEVEL].P); break; case ADJUSTMENT_LEVEL_I: - tfp_sprintf(buff, "LVL I %3d", pidBankMutable()->pid[PID_LEVEL].I); + tfp_sprintf(buff, "LI %3d", pidBankMutable()->pid[PID_LEVEL].I); break; case ADJUSTMENT_LEVEL_D: - tfp_sprintf(buff, "LVL D %3d", pidBankMutable()->pid[PID_LEVEL].D); + tfp_sprintf(buff, "LD %3d", pidBankMutable()->pid[PID_LEVEL].D); break; case ADJUSTMENT_POS_XY_P: - tfp_sprintf(buff, "POS XY P %3d", pidBankMutable()->pid[PID_POS_XY].P); + tfp_sprintf(buff, "PXYP %3d", pidBankMutable()->pid[PID_POS_XY].P); break; case ADJUSTMENT_POS_XY_I: - tfp_sprintf(buff, "POS XY I %3d", pidBankMutable()->pid[PID_POS_XY].I); + tfp_sprintf(buff, "PXYI %3d", pidBankMutable()->pid[PID_POS_XY].I); break; case ADJUSTMENT_POS_XY_D: - tfp_sprintf(buff, "POS XY D %3d", pidBankMutable()->pid[PID_POS_XY].D); + tfp_sprintf(buff, "PXYD %3d", pidBankMutable()->pid[PID_POS_XY].D); break; case ADJUSTMENT_POS_Z_P: - tfp_sprintf(buff, "POS Z P %3d", pidBankMutable()->pid[PID_POS_Z].P); + tfp_sprintf(buff, "PZP %3d", pidBankMutable()->pid[PID_POS_Z].P); break; case ADJUSTMENT_POS_Z_I: - tfp_sprintf(buff, "POS Z I %3d", pidBankMutable()->pid[PID_POS_Z].I); + tfp_sprintf(buff, "PZI %3d", pidBankMutable()->pid[PID_POS_Z].I); break; case ADJUSTMENT_POS_Z_D: - tfp_sprintf(buff, "POS Z D %3d", pidBankMutable()->pid[PID_POS_Z].D); + tfp_sprintf(buff, "PZD %3d", pidBankMutable()->pid[PID_POS_Z].D); break; case ADJUSTMENT_HEADING_P: - tfp_sprintf(buff, "HEAD P %3d", pidBankMutable()->pid[PID_HEADING].P); + tfp_sprintf(buff, "HP %3d", pidBankMutable()->pid[PID_HEADING].P); break; case ADJUSTMENT_VEL_XY_P: - tfp_sprintf(buff, "VEL XY P %3d", pidBankMutable()->pid[PID_VEL_XY].P); + tfp_sprintf(buff, "VXYP %3d", pidBankMutable()->pid[PID_VEL_XY].P); break; case ADJUSTMENT_VEL_XY_I: - tfp_sprintf(buff, "VEL XY I %3d", pidBankMutable()->pid[PID_VEL_XY].I); + tfp_sprintf(buff, "VXYI %3d", pidBankMutable()->pid[PID_VEL_XY].I); break; case ADJUSTMENT_VEL_XY_D: - tfp_sprintf(buff, "VEL XY D %3d", pidBankMutable()->pid[PID_VEL_XY].D); + tfp_sprintf(buff, "VXYD %3d", pidBankMutable()->pid[PID_VEL_XY].D); break; case ADJUSTMENT_VEL_Z_P: - tfp_sprintf(buff, "VEL Z P %3d", pidBankMutable()->pid[PID_VEL_Z].P); + tfp_sprintf(buff, "VZP %3d", pidBankMutable()->pid[PID_VEL_Z].P); break; case ADJUSTMENT_VEL_Z_I: - tfp_sprintf(buff, "VEL Z I %3d", pidBankMutable()->pid[PID_VEL_Z].I); + tfp_sprintf(buff, "VZI %3d", pidBankMutable()->pid[PID_VEL_Z].I); break; case ADJUSTMENT_VEL_Z_D: - tfp_sprintf(buff, "VEL Z D %3d", pidBankMutable()->pid[PID_VEL_Z].D); + tfp_sprintf(buff, "VZD %3d", pidBankMutable()->pid[PID_VEL_Z].D); break; case ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE: - tfp_sprintf(buff, "MIN THR DPA %4d", mixerConfigMutable()->fwMinThrottleDownPitchAngle); + tfp_sprintf(buff, "MTDPA %4d", mixerConfigMutable()->fwMinThrottleDownPitchAngle); break; case ADJUSTMENT_TPA: tfp_sprintf(buff, "TPA %3d", currentControlRateProfile->throttle.dynPID); break; case ADJUSTMENT_TPA_BREAKPOINT: - tfp_sprintf(buff, "TPA BP %4d", currentControlRateProfile->throttle.pa_breakpoint); + tfp_sprintf(buff, "TPABP %4d", currentControlRateProfile->throttle.pa_breakpoint); break; case ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS: - tfp_sprintf(buff, "CTR SMOTH %3d", navConfigMutable()->fw.control_smoothness); + tfp_sprintf(buff, "CSM %3d", navConfigMutable()->fw.control_smoothness); break; default: tfp_sprintf(buff, "UNSUPPORTED"); @@ -1009,6 +1009,10 @@ static bool djiFormatMessages(char *buff) messages[messageCount++] = "(AUTOTUNE)"; } + if (IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) { + messages[messageCount++] = "(AUTOLEVEL)"; + }) + if (FLIGHT_MODE(HEADFREE_MODE)) { messages[messageCount++] = "(HEADFREE)"; } From 0ee8d7828d158d984032062534bf9168bb2081b3 Mon Sep 17 00:00:00 2001 From: scavanger Date: Tue, 8 Jun 2021 11:45:11 +0200 Subject: [PATCH 042/102] Typo --- src/main/io/osd_dji_hd.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index c81683ecc8..695d212050 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -1009,9 +1009,9 @@ static bool djiFormatMessages(char *buff) messages[messageCount++] = "(AUTOTUNE)"; } - if (IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) { + if (IS_RC_MODE_ACTIVE(BOXAUTOLEVEL)) { messages[messageCount++] = "(AUTOLEVEL)"; - }) + } if (FLIGHT_MODE(HEADFREE_MODE)) { messages[messageCount++] = "(HEADFREE)"; From e780a3153f6e18fa3eac3a3762e1da4023cfa7b3 Mon Sep 17 00:00:00 2001 From: scavanger Date: Tue, 8 Jun 2021 13:03:19 +0200 Subject: [PATCH 043/102] Don't show autotrim message when autotrim feature is enabled --- src/main/io/osd_dji_hd.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index 695d212050..a0a9ee7098 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -1001,7 +1001,7 @@ static bool djiFormatMessages(char *buff) messages[messageCount++] = "(ALT HOLD)"; } - if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM)) { + if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM) && !feature(FEATURE_FW_AUTOTRIM)) { messages[messageCount++] = "(AUTOTRIM)"; } From 3a8e67563148fc2f3ee5447d59cb56fdbc4978bc Mon Sep 17 00:00:00 2001 From: scavanger Date: Wed, 9 Jun 2021 12:10:06 +0200 Subject: [PATCH 044/102] Crossfire LQ scale --- src/main/io/osd_dji_hd.c | 21 +++++++++++---------- 1 file changed, 11 insertions(+), 10 deletions(-) diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index a0a9ee7098..322a603467 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -962,9 +962,9 @@ static bool djiFormatMessages(char *buff) bool haveMessage = false; char messageBuf[MAX(SETTING_MAX_NAME_LENGTH, OSD_MESSAGE_LENGTH+1)]; if (ARMING_FLAG(ARMED)) { - // Aircraft is armed. We might have up to 5 + // Aircraft is armed. We might have up to 6 // messages to show. - char *messages[5]; + char *messages[6]; unsigned messageCount = 0; if (FLIGHT_MODE(FAILSAFE_MODE)) { @@ -985,6 +985,10 @@ static bool djiFormatMessages(char *buff) messages[messageCount++] = navStateFSMessage; } } else { + if (rxLinkStatistics.rfMode == 0) { + messages[messageCount++] = "CRSF LOW RF"; + } + if (FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding()) { char *navStateMessage = navigationStateMessage(); if (navStateMessage) { @@ -1241,21 +1245,18 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms sbufWriteU8(dst, constrain(getBatteryVoltage() / 10, 0, 255)); sbufWriteU16(dst, constrain(getMAhDrawn(), 0, 0xFFFF)); // milliamp hours drawn from battery #ifdef USE_SERIALRX_CRSF - // Range of RSSI field: 0-99: 99 = 150 hz , 70 - 98 50 hz, <70 4 hz + // Range of RSSI field: 0-99: 99 = 150 hz , 0 - 98 50 hz / 4 hz if (djiOsdConfig()->rssi_source == DJI_CRSF_LQ) { uint16_t scaledLq = 0; - if (rxLinkStatistics.rfMode == 2) { + if (rxLinkStatistics.rfMode >= 2) { scaledLq = RSSI_MAX_VALUE; - } else if (rxLinkStatistics.rfMode == 1) { - scaledLq = scaleRange(constrain(rxLinkStatistics.uplinkLQ, 0, 100), 0, 100, RSSI_BOUNDARY(70), RSSI_BOUNDARY(99)); - } else if (rxLinkStatistics.rfMode == 0) { - scaledLq = scaleRange(constrain(rxLinkStatistics.uplinkLQ, 0, 100), 0, 100, 0, RSSI_BOUNDARY(69)); + } else { + scaledLq = scaleRange(constrain(rxLinkStatistics.uplinkLQ, 0, 100), 0, 100, 0, RSSI_BOUNDARY(98)); } sbufWriteU16(dst, scaledLq); } else { -#else - sbufWriteU16(dst, getRSSI()); #endif + sbufWriteU16(dst, getRSSI()); #ifdef USE_SERIALRX_CRSF } #endif From b3a882db94e9460f87edce5ad2c245983f34f165 Mon Sep 17 00:00:00 2001 From: scavanger Date: Wed, 9 Jun 2021 12:40:29 +0200 Subject: [PATCH 045/102] #ifdef for Crossfire LQ warning --- src/main/io/osd_dji_hd.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index 322a603467..7b42b72fc2 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -985,10 +985,11 @@ static bool djiFormatMessages(char *buff) messages[messageCount++] = navStateFSMessage; } } else { +#ifdef USE_SERIALRX_CRSF if (rxLinkStatistics.rfMode == 0) { messages[messageCount++] = "CRSF LOW RF"; } - +#endif if (FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding()) { char *navStateMessage = navigationStateMessage(); if (navStateMessage) { From 095a886063f8bff6bc4bd4605347199508eb1921 Mon Sep 17 00:00:00 2001 From: scavanger Date: Sun, 13 Jun 2021 19:56:20 +0200 Subject: [PATCH 046/102] Docs --- docs/Settings.md | 42 +++++++++++++++++++++++++++++++++++++++++- 1 file changed, 41 insertions(+), 1 deletion(-) diff --git a/docs/Settings.md b/docs/Settings.md index de9cc0ea45..a0def4ccc9 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -622,6 +622,16 @@ OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values a --- +### dji_cn_alternating_duration + +Alternating duration of craft name elements, in tenths of a second + +| Default | Min | Max | +| --- | --- | --- | +| 30 | 1 | 150 | + +--- + ### dji_esc_temp_source Re-purpose the ESC temperature field for IMU/BARO temperature @@ -632,9 +642,39 @@ Re-purpose the ESC temperature field for IMU/BARO temperature --- +### dji_message_speed_source + +Sets the speed type displayed by the DJI OSD in craft name: GROUND, 3D, AIR + +| Default | Min | Max | +| --- | --- | --- | +| 3D | | | + +--- + +### dji_rssi_source + +Source of the DJI RSSI field: RSSI, CRSF_LQ + +| Default | Min | Max | +| --- | --- | --- | +| RSSI | | | + +--- + +### dji_use_adjustments + +Show inflight adjustments in craft name field + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + ### dji_use_name_for_messages -Re-purpose the craft name field for messages. Replace craft name with :WTSED for Warnings|Throttle|Speed|Efficiency|Trip distance +Re-purpose the craft name field for messages. | Default | Min | Max | | --- | --- | --- | From bd3f6efadbed76dca24f059f2dec42ffaf053b62 Mon Sep 17 00:00:00 2001 From: scavanger Date: Tue, 15 Jun 2021 09:52:51 +0200 Subject: [PATCH 047/102] Enable OSD for all targets --- src/main/io/osd.c | 12 +++++++++--- src/main/target/AIKONF4/target.h | 1 - src/main/target/AIRBOTF7/target.h | 1 - src/main/target/ALIENFLIGHTNGF7/target.h | 1 - src/main/target/ANYFCF7/target.h | 1 - src/main/target/ANYFCM7/target.h | 1 - src/main/target/ASGARD32F4/target.h | 1 - src/main/target/ASGARD32F7/target.h | 1 - src/main/target/BEEROTORF4/target.h | 1 - src/main/target/BETAFLIGHTF3/target.h | 1 - src/main/target/BETAFLIGHTF4/target.h | 1 - src/main/target/CLRACINGF4AIR/target.h | 1 - src/main/target/DALRCF405/target.h | 1 - src/main/target/DALRCF722DUAL/target.h | 1 - src/main/target/FF_F35_LIGHTNING/target.h | 1 - src/main/target/FF_FORTINIF4/target.h | 1 - src/main/target/FF_PIKOF4/target.h | 1 - src/main/target/FIREWORKSV2/target.h | 1 - src/main/target/FISHDRONEF4/target.h | 1 - src/main/target/FLYWOOF411/target.h | 1 - src/main/target/FLYWOOF745/target.h | 1 - src/main/target/FLYWOOF7DUAL/target.h | 1 - src/main/target/FOXEERF405/target.h | 4 ++-- src/main/target/FOXEERF722DUAL/target.h | 4 ++-- src/main/target/FRSKYF3/target.h | 1 - src/main/target/FRSKYF4/target.h | 1 - src/main/target/FRSKYPILOT/target.h | 1 - src/main/target/FRSKY_ROVERF7/target.h | 1 - src/main/target/FURYF4OSD/target.h | 1 - src/main/target/HGLRCF722/target.h | 4 ++-- src/main/target/IFLIGHTF4_SUCCEXD/target.h | 1 - src/main/target/IFLIGHTF4_TWING/target.h | 1 - src/main/target/IFLIGHTF7_TWING/target.h | 1 - src/main/target/KAKUTEF4/target.h | 1 - src/main/target/KAKUTEF7/target.h | 4 ++-- src/main/target/KAKUTEF7MINIV3/target.h | 4 ++-- src/main/target/KROOZX/target.h | 1 - src/main/target/MAMBAF405US/target.h | 4 ++-- src/main/target/MAMBAF722/target.h | 4 ++-- src/main/target/MATEKF405/target.h | 1 - src/main/target/MATEKF405SE/target.h | 1 - src/main/target/MATEKF411/target.h | 1 - src/main/target/MATEKF411SE/target.h | 1 - src/main/target/MATEKF722/target.h | 1 - src/main/target/MATEKF722PX/target.h | 1 - src/main/target/MATEKF722SE/target.h | 4 ++-- src/main/target/MATEKF765/target.h | 1 - src/main/target/MATEKH743/target.h | 4 ++-- src/main/target/NOX/target.h | 1 - src/main/target/OMNIBUS/target.h | 1 - src/main/target/OMNIBUSF4/target.h | 1 - src/main/target/OMNIBUSF7/target.h | 1 - src/main/target/OMNIBUSF7NXT/target.h | 1 - src/main/target/RUSH_BLADE_F7/target.h | 1 - src/main/target/SPEEDYBEEF4/target.h | 4 ++-- src/main/target/SPEEDYBEEF7/target.h | 1 - src/main/target/SPRACINGF4EVO/target.h | 1 - src/main/target/SPRACINGF7DUAL/target.h | 2 -- src/main/target/YUPIF4/target.h | 1 - src/main/target/YUPIF7/target.h | 1 - src/main/target/ZEEZF7/target.h | 1 - src/main/target/common.h | 1 + 62 files changed, 30 insertions(+), 74 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 855ff9e840..1c3965c1d3 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1755,10 +1755,11 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH: { - static timeUs_t updatedTimestamp = 0; /*static int32_t updatedTimeSeconds = 0;*/ - timeUs_t currentTimeUs = micros(); static int32_t timeSeconds = -1; +#if defined(USE_ADC) && defined(USE_GPS) + static timeUs_t updatedTimestamp = 0; + timeUs_t currentTimeUs = micros(); if (cmpTimeUs(currentTimeUs, updatedTimestamp) >= MS2US(1000)) { #ifdef USE_WIND_ESTIMATOR timeSeconds = calculateRemainingFlightTimeBeforeRTH(osdConfig()->estimations_wind_compensation); @@ -1767,10 +1768,13 @@ static bool osdDrawSingleElement(uint8_t item) #endif updatedTimestamp = currentTimeUs; } +#endif if ((!ARMING_FLAG(ARMED)) || (timeSeconds == -1)) { buff[0] = SYM_FLY_M; strcpy(buff + 1, "--:--"); +#if defined(USE_ADC) && defined(USE_GPS) updatedTimestamp = 0; +#endif } else if (timeSeconds == -2) { // Wind is too strong to come back with cruise throttle buff[0] = SYM_FLY_M; @@ -1787,9 +1791,10 @@ static bool osdDrawSingleElement(uint8_t item) break; case OSD_REMAINING_DISTANCE_BEFORE_RTH:; + static int32_t distanceMeters = -1; +#if defined(USE_ADC) && defined(USE_GPS) static timeUs_t updatedTimestamp = 0; timeUs_t currentTimeUs = micros(); - static int32_t distanceMeters = -1; if (cmpTimeUs(currentTimeUs, updatedTimestamp) >= MS2US(1000)) { #ifdef USE_WIND_ESTIMATOR distanceMeters = calculateRemainingDistanceBeforeRTH(osdConfig()->estimations_wind_compensation); @@ -1798,6 +1803,7 @@ static bool osdDrawSingleElement(uint8_t item) #endif updatedTimestamp = currentTimeUs; } +#endif buff[0] = SYM_TRIP_DIST; if ((!ARMING_FLAG(ARMED)) || (distanceMeters == -1)) { buff[4] = SYM_DIST_M; diff --git a/src/main/target/AIKONF4/target.h b/src/main/target/AIKONF4/target.h index d0e13b8a12..28ee33cf22 100644 --- a/src/main/target/AIKONF4/target.h +++ b/src/main/target/AIKONF4/target.h @@ -146,7 +146,6 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD 0xffff -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN SPI3_NSS_PIN diff --git a/src/main/target/AIRBOTF7/target.h b/src/main/target/AIRBOTF7/target.h index 4a554cdd56..460d2ae820 100644 --- a/src/main/target/AIRBOTF7/target.h +++ b/src/main/target/AIRBOTF7/target.h @@ -59,7 +59,6 @@ #endif // *************** OSD ***************************** -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PC15 diff --git a/src/main/target/ALIENFLIGHTNGF7/target.h b/src/main/target/ALIENFLIGHTNGF7/target.h index 9f48f87c37..8e727f1171 100644 --- a/src/main/target/ALIENFLIGHTNGF7/target.h +++ b/src/main/target/ALIENFLIGHTNGF7/target.h @@ -138,7 +138,6 @@ #define I2C1_SCL PB6 #define I2C1_SDA PB7 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN PB12 diff --git a/src/main/target/ANYFCF7/target.h b/src/main/target/ANYFCF7/target.h index fbd9683c92..0d9b879e04 100644 --- a/src/main/target/ANYFCF7/target.h +++ b/src/main/target/ANYFCF7/target.h @@ -125,7 +125,6 @@ #define SPI4_MISO_PIN PE13 #define SPI4_MOSI_PIN PE14 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN SPI3_NSS_PIN diff --git a/src/main/target/ANYFCM7/target.h b/src/main/target/ANYFCM7/target.h index 0bb51355ec..2ba9486297 100644 --- a/src/main/target/ANYFCM7/target.h +++ b/src/main/target/ANYFCM7/target.h @@ -111,7 +111,6 @@ #define USE_FLASH_M25P16 #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN SPI3_NSS_PIN diff --git a/src/main/target/ASGARD32F4/target.h b/src/main/target/ASGARD32F4/target.h index d9018a5cd9..ea2699dc2f 100644 --- a/src/main/target/ASGARD32F4/target.h +++ b/src/main/target/ASGARD32F4/target.h @@ -117,7 +117,6 @@ #define SPI3_MISO_PIN PB4 #define SPI3_MOSI_PIN PB5 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN PA15 diff --git a/src/main/target/ASGARD32F7/target.h b/src/main/target/ASGARD32F7/target.h index 97e2ad210e..dc82fb74be 100644 --- a/src/main/target/ASGARD32F7/target.h +++ b/src/main/target/ASGARD32F7/target.h @@ -119,7 +119,6 @@ #define SPI3_MISO_PIN PB4 #define SPI3_MOSI_PIN PB5 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN PA15 diff --git a/src/main/target/BEEROTORF4/target.h b/src/main/target/BEEROTORF4/target.h index 9d86514f9d..9c78cf7738 100644 --- a/src/main/target/BEEROTORF4/target.h +++ b/src/main/target/BEEROTORF4/target.h @@ -57,7 +57,6 @@ #define TEMPERATURE_I2C_BUS BUS_I2C1 #define BNO055_I2C_BUS BUS_I2C1 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN SPI3_NSS_PIN diff --git a/src/main/target/BETAFLIGHTF3/target.h b/src/main/target/BETAFLIGHTF3/target.h index 1c4cc3fe68..71e469db2c 100755 --- a/src/main/target/BETAFLIGHTF3/target.h +++ b/src/main/target/BETAFLIGHTF3/target.h @@ -79,7 +79,6 @@ #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI1 #define MAX7456_CS_PIN PA1 diff --git a/src/main/target/BETAFLIGHTF4/target.h b/src/main/target/BETAFLIGHTF4/target.h index 872327b41a..4116a52001 100755 --- a/src/main/target/BETAFLIGHTF4/target.h +++ b/src/main/target/BETAFLIGHTF4/target.h @@ -45,7 +45,6 @@ #define BMP280_SPI_BUS BUS_SPI2 #define BMP280_CS_PIN PB3 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB12 diff --git a/src/main/target/CLRACINGF4AIR/target.h b/src/main/target/CLRACINGF4AIR/target.h index 56c3918aff..45778103a9 100644 --- a/src/main/target/CLRACINGF4AIR/target.h +++ b/src/main/target/CLRACINGF4AIR/target.h @@ -64,7 +64,6 @@ #define BMP280_SPI_BUS BUS_SPI3 #define BMP280_CS_PIN PB3 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN PA15 diff --git a/src/main/target/DALRCF405/target.h b/src/main/target/DALRCF405/target.h index c2787f71ef..a36a59a63a 100644 --- a/src/main/target/DALRCF405/target.h +++ b/src/main/target/DALRCF405/target.h @@ -66,7 +66,6 @@ #define SPI3_MISO_PIN PC11 #define SPI3_MOSI_PIN PB5 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN PA15 diff --git a/src/main/target/DALRCF722DUAL/target.h b/src/main/target/DALRCF722DUAL/target.h index ca29604c6c..2ff18eeccb 100644 --- a/src/main/target/DALRCF722DUAL/target.h +++ b/src/main/target/DALRCF722DUAL/target.h @@ -103,7 +103,6 @@ #define SPI3_MISO_PIN PB4 #define SPI3_MOSI_PIN PB5 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN SPI2_NSS_PIN diff --git a/src/main/target/FF_F35_LIGHTNING/target.h b/src/main/target/FF_F35_LIGHTNING/target.h index a916b186d7..a415ae541a 100644 --- a/src/main/target/FF_F35_LIGHTNING/target.h +++ b/src/main/target/FF_F35_LIGHTNING/target.h @@ -48,7 +48,6 @@ #define BMP280_CS_PIN PC5 #define BMP280_SPI_BUS BUS_SPI3 -#define USE_OSD #define USE_MAX7456 #define MAX7456_CS_PIN PA4 #define MAX7456_SPI_BUS BUS_SPI1 diff --git a/src/main/target/FF_FORTINIF4/target.h b/src/main/target/FF_FORTINIF4/target.h index 669f4bd440..00c154dd94 100644 --- a/src/main/target/FF_FORTINIF4/target.h +++ b/src/main/target/FF_FORTINIF4/target.h @@ -58,7 +58,6 @@ /*---------------------------------*/ /*-------------OSD-----------------*/ -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN PB3 diff --git a/src/main/target/FF_PIKOF4/target.h b/src/main/target/FF_PIKOF4/target.h index 59337ad53b..244ddec53b 100644 --- a/src/main/target/FF_PIKOF4/target.h +++ b/src/main/target/FF_PIKOF4/target.h @@ -73,7 +73,6 @@ #if defined(FF_PIKOF4OSD) /*-------------OSD-----------------*/ -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI1 #define MAX7456_CS_PIN PA4 diff --git a/src/main/target/FIREWORKSV2/target.h b/src/main/target/FIREWORKSV2/target.h index a0ea4428da..51ea748abc 100644 --- a/src/main/target/FIREWORKSV2/target.h +++ b/src/main/target/FIREWORKSV2/target.h @@ -175,7 +175,6 @@ #define SPI3_MISO_PIN PC11 #define SPI3_MOSI_PIN PC12 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN PA15 diff --git a/src/main/target/FISHDRONEF4/target.h b/src/main/target/FISHDRONEF4/target.h index 45b8b5b865..331de0d918 100644 --- a/src/main/target/FISHDRONEF4/target.h +++ b/src/main/target/FISHDRONEF4/target.h @@ -78,7 +78,6 @@ #define SPI2_MISO_PIN PC2 #define SPI2_MOSI_PIN PC3 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN SPI2_NSS_PIN diff --git a/src/main/target/FLYWOOF411/target.h b/src/main/target/FLYWOOF411/target.h index 34d110d7a5..f949cbf4f6 100644 --- a/src/main/target/FLYWOOF411/target.h +++ b/src/main/target/FLYWOOF411/target.h @@ -88,7 +88,6 @@ #define USE_MAG_LIS3MDL // *************** SPI OSD ***************************** -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB12 diff --git a/src/main/target/FLYWOOF745/target.h b/src/main/target/FLYWOOF745/target.h index c58690f9b8..c129a87c0b 100644 --- a/src/main/target/FLYWOOF745/target.h +++ b/src/main/target/FLYWOOF745/target.h @@ -107,7 +107,6 @@ #define SPI4_MISO_PIN PE5 #define SPI4_MOSI_PIN PE6 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 diff --git a/src/main/target/FLYWOOF7DUAL/target.h b/src/main/target/FLYWOOF7DUAL/target.h index 10b8d285bb..8cae941538 100644 --- a/src/main/target/FLYWOOF7DUAL/target.h +++ b/src/main/target/FLYWOOF7DUAL/target.h @@ -73,7 +73,6 @@ #define M25P16_SPI_BUS BUS_SPI3 /*** OSD ***/ -#define USE_OSD #define USE_MAX7456 #define MAX7456_CS_PIN PB12 #define MAX7456_SPI_BUS BUS_SPI2 diff --git a/src/main/target/FOXEERF405/target.h b/src/main/target/FOXEERF405/target.h index 2b8d4e2ac0..2b9f5ae7a0 100644 --- a/src/main/target/FOXEERF405/target.h +++ b/src/main/target/FOXEERF405/target.h @@ -72,7 +72,6 @@ #define M25P16_SPI_BUS BUS_SPI2 /*** OSD ***/ -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN PA15 @@ -147,4 +146,5 @@ #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) \ No newline at end of file +#define TARGET_IO_PORTD (BIT(2)) + diff --git a/src/main/target/FOXEERF722DUAL/target.h b/src/main/target/FOXEERF722DUAL/target.h index b339cef7a9..f946150985 100644 --- a/src/main/target/FOXEERF722DUAL/target.h +++ b/src/main/target/FOXEERF722DUAL/target.h @@ -81,7 +81,6 @@ #define M25P16_SPI_BUS BUS_SPI2 /*** OSD ***/ -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN PC3 @@ -158,4 +157,5 @@ #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) \ No newline at end of file +#define TARGET_IO_PORTD (BIT(2)) + diff --git a/src/main/target/FRSKYF3/target.h b/src/main/target/FRSKYF3/target.h index b046c399cb..304fa22214 100644 --- a/src/main/target/FRSKYF3/target.h +++ b/src/main/target/FRSKYF3/target.h @@ -56,7 +56,6 @@ #define I2C1_SDA PB7 #define USE_SPI -#define USE_OSD // include the max7456 driver #define USE_MAX7456 diff --git a/src/main/target/FRSKYF4/target.h b/src/main/target/FRSKYF4/target.h index 4d950a18a7..9b6cee6b39 100755 --- a/src/main/target/FRSKYF4/target.h +++ b/src/main/target/FRSKYF4/target.h @@ -37,7 +37,6 @@ #define BMP280_SPI_BUS BUS_SPI3 #define BMP280_CS_PIN PB3 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN PA15 diff --git a/src/main/target/FRSKYPILOT/target.h b/src/main/target/FRSKYPILOT/target.h index d4da84dde0..2dd56aa73d 100644 --- a/src/main/target/FRSKYPILOT/target.h +++ b/src/main/target/FRSKYPILOT/target.h @@ -152,7 +152,6 @@ #define UART5_AF 1 // OSD -#define USE_OSD #define USE_UART6 #define UART6_TX_PIN PC6 #define UART6_RX_PIN PC7 diff --git a/src/main/target/FRSKY_ROVERF7/target.h b/src/main/target/FRSKY_ROVERF7/target.h index 6347cd9bd9..f729d2bd60 100755 --- a/src/main/target/FRSKY_ROVERF7/target.h +++ b/src/main/target/FRSKY_ROVERF7/target.h @@ -87,7 +87,6 @@ #define SPI3_MISO_PIN PB4 #define SPI3_MOSI_PIN PB5 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN PD2 diff --git a/src/main/target/FURYF4OSD/target.h b/src/main/target/FURYF4OSD/target.h index d5ccf15a95..5b7b75dd5b 100644 --- a/src/main/target/FURYF4OSD/target.h +++ b/src/main/target/FURYF4OSD/target.h @@ -67,7 +67,6 @@ #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB12 diff --git a/src/main/target/HGLRCF722/target.h b/src/main/target/HGLRCF722/target.h index 440a657c1b..a2453b1e61 100644 --- a/src/main/target/HGLRCF722/target.h +++ b/src/main/target/HGLRCF722/target.h @@ -92,7 +92,6 @@ #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB12 @@ -177,4 +176,5 @@ #define MAX_PWM_OUTPUT_PORTS 8 #define USE_DSHOT #define USE_SERIALSHOT -#define USE_ESC_SENSOR \ No newline at end of file +#define USE_ESC_SENSOR + diff --git a/src/main/target/IFLIGHTF4_SUCCEXD/target.h b/src/main/target/IFLIGHTF4_SUCCEXD/target.h index aee436548c..7d603cc116 100644 --- a/src/main/target/IFLIGHTF4_SUCCEXD/target.h +++ b/src/main/target/IFLIGHTF4_SUCCEXD/target.h @@ -49,7 +49,6 @@ #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB12 diff --git a/src/main/target/IFLIGHTF4_TWING/target.h b/src/main/target/IFLIGHTF4_TWING/target.h index ab5d0bf5f3..5a3943e11a 100644 --- a/src/main/target/IFLIGHTF4_TWING/target.h +++ b/src/main/target/IFLIGHTF4_TWING/target.h @@ -87,7 +87,6 @@ #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB12 diff --git a/src/main/target/IFLIGHTF7_TWING/target.h b/src/main/target/IFLIGHTF7_TWING/target.h index 2fb765bce7..fb74f2d530 100644 --- a/src/main/target/IFLIGHTF7_TWING/target.h +++ b/src/main/target/IFLIGHTF7_TWING/target.h @@ -100,7 +100,6 @@ #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB12 diff --git a/src/main/target/KAKUTEF4/target.h b/src/main/target/KAKUTEF4/target.h index 2b0f908a91..f64101ea75 100755 --- a/src/main/target/KAKUTEF4/target.h +++ b/src/main/target/KAKUTEF4/target.h @@ -75,7 +75,6 @@ # define USE_MAG #endif -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN PB14 diff --git a/src/main/target/KAKUTEF7/target.h b/src/main/target/KAKUTEF7/target.h index 0d42c7e2d6..97764f6e92 100644 --- a/src/main/target/KAKUTEF7/target.h +++ b/src/main/target/KAKUTEF7/target.h @@ -104,7 +104,6 @@ #define SPI4_MISO_PIN PE5 #define SPI4_MOSI_PIN PE6 -#define USE_OSD #ifndef KAKUTEF7HDV #define USE_MAX7456 @@ -179,4 +178,5 @@ #define MAX_PWM_OUTPUT_PORTS 6 -#define BNO055_I2C_BUS BUS_I2C1 \ No newline at end of file +#define BNO055_I2C_BUS BUS_I2C1 + diff --git a/src/main/target/KAKUTEF7MINIV3/target.h b/src/main/target/KAKUTEF7MINIV3/target.h index 7ecc7a3d1e..6e7188f9f7 100644 --- a/src/main/target/KAKUTEF7MINIV3/target.h +++ b/src/main/target/KAKUTEF7MINIV3/target.h @@ -106,7 +106,6 @@ /* * OSD */ -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN PA15 @@ -173,4 +172,5 @@ #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) \ No newline at end of file +#define TARGET_IO_PORTD (BIT(2)) + diff --git a/src/main/target/KROOZX/target.h b/src/main/target/KROOZX/target.h index 4f5eac5f7c..cde87e45d2 100755 --- a/src/main/target/KROOZX/target.h +++ b/src/main/target/KROOZX/target.h @@ -61,7 +61,6 @@ #define SDCARD_DETECT_INVERTED #define SDCARD_DETECT_PIN PC13 -#define USE_OSD #ifdef USE_MSP_DISPLAYPORT #undef USE_MSP_DISPLAYPORT #endif diff --git a/src/main/target/MAMBAF405US/target.h b/src/main/target/MAMBAF405US/target.h index adb4c09f1e..969b725bf4 100644 --- a/src/main/target/MAMBAF405US/target.h +++ b/src/main/target/MAMBAF405US/target.h @@ -158,7 +158,6 @@ #define VBAT_SCALE_DEFAULT 1100 // ******* OSD ******** -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB12 @@ -199,4 +198,5 @@ #define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS #define PITOT_I2C_BUS DEFAULT_I2C_BUS #define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS -#define BNO055_I2C_BUS DEFAULT_I2C_BUS \ No newline at end of file +#define BNO055_I2C_BUS DEFAULT_I2C_BUS + diff --git a/src/main/target/MAMBAF722/target.h b/src/main/target/MAMBAF722/target.h index 2c1cb07cf7..3efdde2835 100644 --- a/src/main/target/MAMBAF722/target.h +++ b/src/main/target/MAMBAF722/target.h @@ -156,7 +156,6 @@ #define VBAT_SCALE_DEFAULT 1100 // ******* OSD ******** -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN SPI2_NSS_PIN @@ -207,4 +206,5 @@ #define BNO055_I2C_BUS DEFAULT_I2C_BUS -#endif \ No newline at end of file +#endif + diff --git a/src/main/target/MATEKF405/target.h b/src/main/target/MATEKF405/target.h index a70cc55583..c3dd007b4d 100644 --- a/src/main/target/MATEKF405/target.h +++ b/src/main/target/MATEKF405/target.h @@ -76,7 +76,6 @@ #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB10 diff --git a/src/main/target/MATEKF405SE/target.h b/src/main/target/MATEKF405SE/target.h index 75afdea322..805f6cea42 100644 --- a/src/main/target/MATEKF405SE/target.h +++ b/src/main/target/MATEKF405SE/target.h @@ -85,7 +85,6 @@ #define SPI2_MISO_PIN PC2 #define SPI2_MOSI_PIN PC3 -#define USE_OSD #define USE_MAX7456 #define MAX7456_CS_PIN PB12 #define MAX7456_SPI_BUS BUS_SPI2 diff --git a/src/main/target/MATEKF411/target.h b/src/main/target/MATEKF411/target.h index ac6962a350..b73c6013c7 100755 --- a/src/main/target/MATEKF411/target.h +++ b/src/main/target/MATEKF411/target.h @@ -55,7 +55,6 @@ #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB12 diff --git a/src/main/target/MATEKF411SE/target.h b/src/main/target/MATEKF411SE/target.h index 2da0393f54..8bb3e933ef 100755 --- a/src/main/target/MATEKF411SE/target.h +++ b/src/main/target/MATEKF411SE/target.h @@ -50,7 +50,6 @@ #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB12 diff --git a/src/main/target/MATEKF722/target.h b/src/main/target/MATEKF722/target.h index 331ad65821..b1b657e424 100755 --- a/src/main/target/MATEKF722/target.h +++ b/src/main/target/MATEKF722/target.h @@ -90,7 +90,6 @@ #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB10 diff --git a/src/main/target/MATEKF722PX/target.h b/src/main/target/MATEKF722PX/target.h index ca9dd843a6..83d7d669cb 100755 --- a/src/main/target/MATEKF722PX/target.h +++ b/src/main/target/MATEKF722PX/target.h @@ -169,7 +169,6 @@ #define TARGET_IO_PORTD 0xffff #define MAX_PWM_OUTPUT_PORTS 10 -#define USE_OSD #define USE_DSHOT #define USE_SERIALSHOT #define USE_ESC_SENSOR diff --git a/src/main/target/MATEKF722SE/target.h b/src/main/target/MATEKF722SE/target.h index ecff68fa66..6f62d53406 100644 --- a/src/main/target/MATEKF722SE/target.h +++ b/src/main/target/MATEKF722SE/target.h @@ -95,7 +95,6 @@ #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB12 @@ -195,4 +194,5 @@ #define USE_SERIALSHOT #define USE_ESC_SENSOR -#define BNO055_I2C_BUS BUS_I2C1 \ No newline at end of file +#define BNO055_I2C_BUS BUS_I2C1 + diff --git a/src/main/target/MATEKF765/target.h b/src/main/target/MATEKF765/target.h index 8f5b256026..449801cc50 100644 --- a/src/main/target/MATEKF765/target.h +++ b/src/main/target/MATEKF765/target.h @@ -98,7 +98,6 @@ #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB12 diff --git a/src/main/target/MATEKH743/target.h b/src/main/target/MATEKH743/target.h index ca99c9ddcc..cf49efb232 100644 --- a/src/main/target/MATEKH743/target.h +++ b/src/main/target/MATEKH743/target.h @@ -92,7 +92,6 @@ #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB12 @@ -189,4 +188,5 @@ #define MAX_PWM_OUTPUT_PORTS 15 #define USE_DSHOT #define USE_ESC_SENSOR -#define USE_SERIALSHOT \ No newline at end of file +#define USE_SERIALSHOT + diff --git a/src/main/target/NOX/target.h b/src/main/target/NOX/target.h index 9a40ea5050..764e889bb4 100755 --- a/src/main/target/NOX/target.h +++ b/src/main/target/NOX/target.h @@ -61,7 +61,6 @@ #define BMP280_CS_PIN PA9 // *************** SPI OSD ***************************** -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PA10 diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index 3338db998e..273f41097f 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -103,7 +103,6 @@ #define SDCARD_SPI_BUS BUS_SPI2 #define SDCARD_CS_PIN SPI2_NSS_PIN -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI1 #define MAX7456_CS_PIN PB1 diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h index 4027144c8d..fd0991fb94 100644 --- a/src/main/target/OMNIBUSF4/target.h +++ b/src/main/target/OMNIBUSF4/target.h @@ -213,7 +213,6 @@ #define SPI3_MISO_PIN PC11 #define SPI3_MOSI_PIN PC12 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN PA15 diff --git a/src/main/target/OMNIBUSF7/target.h b/src/main/target/OMNIBUSF7/target.h index 50e10578b4..8296e531e5 100644 --- a/src/main/target/OMNIBUSF7/target.h +++ b/src/main/target/OMNIBUSF7/target.h @@ -126,7 +126,6 @@ #define SPI4_MISO_PIN PE5 #define SPI4_MOSI_PIN PE6 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN SPI2_NSS_PIN diff --git a/src/main/target/OMNIBUSF7NXT/target.h b/src/main/target/OMNIBUSF7NXT/target.h index 241322b5d6..de7da72927 100644 --- a/src/main/target/OMNIBUSF7NXT/target.h +++ b/src/main/target/OMNIBUSF7NXT/target.h @@ -128,7 +128,6 @@ #define SPI3_MISO_PIN PC11 #define SPI3_MOSI_PIN PC12 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PA15 diff --git a/src/main/target/RUSH_BLADE_F7/target.h b/src/main/target/RUSH_BLADE_F7/target.h index cdae1860b3..1a701ed987 100644 --- a/src/main/target/RUSH_BLADE_F7/target.h +++ b/src/main/target/RUSH_BLADE_F7/target.h @@ -141,7 +141,6 @@ #define TARGET_IO_PORTD 0xffff #define MAX_PWM_OUTPUT_PORTS 10 -#define USE_OSD #define USE_DSHOT #define USE_SERIALSHOT #define USE_ESC_SENSOR diff --git a/src/main/target/SPEEDYBEEF4/target.h b/src/main/target/SPEEDYBEEF4/target.h index 3920653df7..0258ac2974 100644 --- a/src/main/target/SPEEDYBEEF4/target.h +++ b/src/main/target/SPEEDYBEEF4/target.h @@ -73,7 +73,6 @@ #define USE_FLASH_M25P16 /*** OSD ***/ -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB10 @@ -171,4 +170,5 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(2)) -#define RANGEFINDER_I2C_BUS BUS_I2C1 \ No newline at end of file +#define RANGEFINDER_I2C_BUS BUS_I2C1 + diff --git a/src/main/target/SPEEDYBEEF7/target.h b/src/main/target/SPEEDYBEEF7/target.h index 71e855af0a..559ad0924e 100644 --- a/src/main/target/SPEEDYBEEF7/target.h +++ b/src/main/target/SPEEDYBEEF7/target.h @@ -73,7 +73,6 @@ // OSD -- SPI2 #define USE_SPI_DEVICE_2 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB12 diff --git a/src/main/target/SPRACINGF4EVO/target.h b/src/main/target/SPRACINGF4EVO/target.h index efe89add1e..8722883d01 100755 --- a/src/main/target/SPRACINGF4EVO/target.h +++ b/src/main/target/SPRACINGF4EVO/target.h @@ -143,7 +143,6 @@ // PC4 - NC - Free for ADC12_IN14 / VTX CS // PC5 - NC - Free for ADC12_IN15 / VTX Enable / OSD VSYNC -//#define USE_OSD //#define USE_MAX7456 //#define USE_OSD_OVER_MSP_DISPLAYPORT diff --git a/src/main/target/SPRACINGF7DUAL/target.h b/src/main/target/SPRACINGF7DUAL/target.h index 9bbc2a7455..c41c61732a 100644 --- a/src/main/target/SPRACINGF7DUAL/target.h +++ b/src/main/target/SPRACINGF7DUAL/target.h @@ -168,8 +168,6 @@ #define CURRENT_METER_SCALE 300 -#define USE_OSD - #define USE_LED_STRIP #define WS2811_PIN PA1 diff --git a/src/main/target/YUPIF4/target.h b/src/main/target/YUPIF4/target.h index 741f224252..97e389826c 100644 --- a/src/main/target/YUPIF4/target.h +++ b/src/main/target/YUPIF4/target.h @@ -74,7 +74,6 @@ #define USE_BARO_MS5611 #define USE_BARO_BMP280 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI1 #define MAX7456_CS_PIN PA14 diff --git a/src/main/target/YUPIF7/target.h b/src/main/target/YUPIF7/target.h index a95336a738..6a146a1c50 100644 --- a/src/main/target/YUPIF7/target.h +++ b/src/main/target/YUPIF7/target.h @@ -115,7 +115,6 @@ #define I2C_DEVICE (I2CDEV_1) // OSD -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI1 #define MAX7456_CS_PIN PA14 diff --git a/src/main/target/ZEEZF7/target.h b/src/main/target/ZEEZF7/target.h index 4558922417..5ad4f85e6e 100755 --- a/src/main/target/ZEEZF7/target.h +++ b/src/main/target/ZEEZF7/target.h @@ -140,7 +140,6 @@ #define SPI3_MISO_PIN PC11 #define SPI3_MOSI_PIN PB5 -#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN PA15 diff --git a/src/main/target/common.h b/src/main/target/common.h index 068e6b8dde..c110a6112f 100755 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -127,6 +127,7 @@ #define USE_PWM_DRIVER_PCA9685 +#define USE_OSD #define USE_FRSKYOSD #define USE_DJI_HD_OSD #define USE_SMARTPORT_MASTER From 1b0c567267ff3c1bc6decbf4d28eb7f9037db408 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 15 Jun 2021 13:19:22 +0200 Subject: [PATCH 048/102] Fix DSHOT on H7 by moving to DMA_RAM --- src/main/build/build_config.h | 6 ++++++ src/main/drivers/adc_impl.h | 2 +- src/main/drivers/pwm_output.c | 10 +++++----- 3 files changed, 12 insertions(+), 6 deletions(-) diff --git a/src/main/build/build_config.h b/src/main/build/build_config.h index b6a561fecd..ae4eb1a3a4 100644 --- a/src/main/build/build_config.h +++ b/src/main/build/build_config.h @@ -51,5 +51,11 @@ #define EXTENDED_FASTRAM #endif +#ifdef STM32H7 +#define DMA_RAM __attribute__ ((section(".DMA_RAM"))) +#else +#define DMA_RAM +#endif + #define STATIC_FASTRAM static FASTRAM #define STATIC_FASTRAM_UNIT_TESTED STATIC_UNIT_TESTED FASTRAM diff --git a/src/main/drivers/adc_impl.h b/src/main/drivers/adc_impl.h index 290a9ef583..3a1783a04d 100644 --- a/src/main/drivers/adc_impl.h +++ b/src/main/drivers/adc_impl.h @@ -31,7 +31,7 @@ #endif #if defined(STM32H7) -#define ADC_VALUES_ALIGNMENT(def) __attribute__ ((section(".DMA_RAM"))) def __attribute__ ((aligned (32))) +#define ADC_VALUES_ALIGNMENT(def) DMA_RAM def __attribute__ ((aligned (32))) #else #define ADC_VALUES_ALIGNMENT(def) def #endif diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 48f7a10d5c..c02a14672c 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -91,7 +91,7 @@ typedef struct { bool requestTelemetry; } pwmOutputMotor_t; -static pwmOutputPort_t pwmOutputPorts[MAX_PWM_OUTPUT_PORTS]; +static DMA_RAM pwmOutputPort_t pwmOutputPorts[MAX_PWM_OUTPUT_PORTS]; static pwmOutputMotor_t motors[MAX_MOTORS]; static motorPwmProtocolTypes_e initMotorProtocol; @@ -142,7 +142,7 @@ static pwmOutputPort_t *pwmOutAllocatePort(void) return NULL; } - pwmOutputPort_t *p = &pwmOutputPorts[allocatedOutputPortCount++]; + volatile pwmOutputPort_t *p = &pwmOutputPorts[allocatedOutputPortCount++]; p->tch = NULL; p->configured = false; @@ -150,7 +150,7 @@ static pwmOutputPort_t *pwmOutAllocatePort(void) return p; } -static pwmOutputPort_t *pwmOutConfigMotor(const timerHardware_t *timHw, uint32_t hz, uint16_t period, uint16_t value, bool enableOutput) +volatile static pwmOutputPort_t *pwmOutConfigMotor(const timerHardware_t *timHw, uint32_t hz, uint16_t period, uint16_t value, bool enableOutput) { // Attempt to allocate TCH TCH_t * tch = timerGetTCH(timHw); @@ -159,7 +159,7 @@ static pwmOutputPort_t *pwmOutConfigMotor(const timerHardware_t *timHw, uint32_t } // Allocate motor output port - pwmOutputPort_t *p = pwmOutAllocatePort(); + volatile pwmOutputPort_t *p = pwmOutAllocatePort(); if (p == NULL) { return NULL; } @@ -232,7 +232,7 @@ static pwmOutputPort_t * motorConfigPwm(const timerHardware_t *timerHardware, fl const uint32_t timerHz = baseClockHz / prescaler; const uint32_t period = timerHz / motorPwmRateHz; - pwmOutputPort_t * port = pwmOutConfigMotor(timerHardware, timerHz, period, 0, enableOutput); + volatile pwmOutputPort_t * port = pwmOutConfigMotor(timerHardware, timerHz, period, 0, enableOutput); if (port) { port->pulseScale = ((sLen == 0) ? period : (sLen * timerHz)) / 1000.0f; From 0c1f319773047721809a34036a7a92cd2925723c Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 15 Jun 2021 13:21:05 +0200 Subject: [PATCH 049/102] Too volatile --- src/main/drivers/pwm_output.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index c02a14672c..620c25a22a 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -142,7 +142,7 @@ static pwmOutputPort_t *pwmOutAllocatePort(void) return NULL; } - volatile pwmOutputPort_t *p = &pwmOutputPorts[allocatedOutputPortCount++]; + pwmOutputPort_t *p = &pwmOutputPorts[allocatedOutputPortCount++]; p->tch = NULL; p->configured = false; @@ -150,7 +150,7 @@ static pwmOutputPort_t *pwmOutAllocatePort(void) return p; } -volatile static pwmOutputPort_t *pwmOutConfigMotor(const timerHardware_t *timHw, uint32_t hz, uint16_t period, uint16_t value, bool enableOutput) +static pwmOutputPort_t *pwmOutConfigMotor(const timerHardware_t *timHw, uint32_t hz, uint16_t period, uint16_t value, bool enableOutput) { // Attempt to allocate TCH TCH_t * tch = timerGetTCH(timHw); @@ -159,7 +159,7 @@ volatile static pwmOutputPort_t *pwmOutConfigMotor(const timerHardware_t *timHw, } // Allocate motor output port - volatile pwmOutputPort_t *p = pwmOutAllocatePort(); + pwmOutputPort_t *p = pwmOutAllocatePort(); if (p == NULL) { return NULL; } @@ -232,7 +232,7 @@ static pwmOutputPort_t * motorConfigPwm(const timerHardware_t *timerHardware, fl const uint32_t timerHz = baseClockHz / prescaler; const uint32_t period = timerHz / motorPwmRateHz; - volatile pwmOutputPort_t * port = pwmOutConfigMotor(timerHardware, timerHz, period, 0, enableOutput); + pwmOutputPort_t * port = pwmOutConfigMotor(timerHardware, timerHz, period, 0, enableOutput); if (port) { port->pulseScale = ((sLen == 0) ? period : (sLen * timerHz)) / 1000.0f; From 7968308797ccd80765355e12b85e76b790b73b28 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Tue, 15 Jun 2021 13:24:45 +0100 Subject: [PATCH 050/102] Updated baro in description --- docs/Board - Matek F411-WSE.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/Board - Matek F411-WSE.md b/docs/Board - Matek F411-WSE.md index f7e4bc88f5..9fca091932 100644 --- a/docs/Board - Matek F411-WSE.md +++ b/docs/Board - Matek F411-WSE.md @@ -6,7 +6,7 @@ * STM32F411 CPU * OSD -* BMP280 barometer +* BMP280 barometer (DSP310 with new FCs from around June 2021) * Integrated PDB for 2 motors * 2 UART ports * 6 servos From 787853cbf9b7eb8138176f058647f238cc8db251 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Tue, 15 Jun 2021 15:12:40 +0200 Subject: [PATCH 051/102] Add the possibility to switch control rate profile upon automatic battery profile switching (#7048) --- docs/Settings.md | 10 ++++ src/main/CMakeLists.txt | 1 + src/main/fc/controlrate_profile.h | 31 ++--------- .../fc/controlrate_profile_config_struct.h | 52 +++++++++++++++++++ src/main/fc/settings.yaml | 10 +++- src/main/sensors/battery.c | 10 +++- src/main/sensors/battery.h | 2 + 7 files changed, 85 insertions(+), 31 deletions(-) create mode 100644 src/main/fc/controlrate_profile_config_struct.h diff --git a/docs/Settings.md b/docs/Settings.md index a0def4ccc9..9f8c1611f7 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -492,6 +492,16 @@ Stick deadband in [r/c points], applied after r/c deadband and expo. Used to che --- +### controlrate_profile + +Control rate profile to switch to when the battery profile is selected, 0 to disable and keep the currently selected control rate profile + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 3 | + +--- + ### cpu_underclock This option is only available on certain architectures (F3 CPUs at the moment). It makes CPU clock lower to reduce interference to long-range RC systems working at 433MHz diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 75e03ea448..13e1b564f1 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -280,6 +280,7 @@ main_sources(COMMON_SRC fc/config.h fc/controlrate_profile.c fc/controlrate_profile.h + fc/controlrate_profile_config_struct.h fc/fc_core.c fc/fc_core.h fc/fc_init.c diff --git a/src/main/fc/controlrate_profile.h b/src/main/fc/controlrate_profile.h index 4dc84dafe3..424e80f1ad 100644 --- a/src/main/fc/controlrate_profile.h +++ b/src/main/fc/controlrate_profile.h @@ -21,35 +21,10 @@ #include "config/parameter_group.h" -#define MAX_CONTROL_RATE_PROFILE_COUNT 3 +#include "fc/controlrate_profile_config_struct.h" +#include "fc/settings.h" -typedef struct controlRateConfig_s { - - struct { - uint8_t rcMid8; - uint8_t rcExpo8; - uint8_t dynPID; - uint16_t pa_breakpoint; // Breakpoint where TPA is activated - uint16_t fixedWingTauMs; // Time constant of airplane TPA PT1-filter - } throttle; - - struct { - uint8_t rcExpo8; - uint8_t rcYawExpo8; - uint8_t rates[3]; - } stabilized; - - struct { - uint8_t rcExpo8; - uint8_t rcYawExpo8; - uint8_t rates[3]; - } manual; - - struct { - uint8_t fpvCamAngleDegrees; // Camera angle to treat as "forward" base axis in ACRO (Roll and Yaw sticks will command rotation considering this axis) - } misc; - -} controlRateConfig_t; +#define MAX_CONTROL_RATE_PROFILE_COUNT SETTING_CONSTANT_MAX_CONTROL_RATE_PROFILE_COUNT PG_DECLARE_ARRAY(controlRateConfig_t, MAX_CONTROL_RATE_PROFILE_COUNT, controlRateProfiles); diff --git a/src/main/fc/controlrate_profile_config_struct.h b/src/main/fc/controlrate_profile_config_struct.h new file mode 100644 index 0000000000..30e50d2a2b --- /dev/null +++ b/src/main/fc/controlrate_profile_config_struct.h @@ -0,0 +1,52 @@ +/* + * This file is part of iNav + * + * iNav free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * iNav distributed in the hope that it + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +#include +#include + +typedef struct controlRateConfig_s { + + struct { + uint8_t rcMid8; + uint8_t rcExpo8; + uint8_t dynPID; + uint16_t pa_breakpoint; // Breakpoint where TPA is activated + uint16_t fixedWingTauMs; // Time constant of airplane TPA PT1-filter + } throttle; + + struct { + uint8_t rcExpo8; + uint8_t rcYawExpo8; + uint8_t rates[3]; + } stabilized; + + struct { + uint8_t rcExpo8; + uint8_t rcYawExpo8; + uint8_t rates[3]; + } manual; + + struct { + uint8_t fpvCamAngleDegrees; // Camera angle to treat as "forward" base axis in ACRO (Roll and Yaw sticks will command rotation considering this axis) + } misc; + +} controlRateConfig_t; diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 343437bcb4..4e5cf71ceb 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -194,6 +194,8 @@ constants: ROLL_PITCH_RATE_MIN: 4 ROLL_PITCH_RATE_MAX: 180 + MAX_CONTROL_RATE_PROFILE_COUNT: 3 + groups: - name: PG_GYRO_CONFIG type: gyroConfig_t @@ -1131,6 +1133,12 @@ groups: field: capacity.unit table: bat_capacity_unit type: uint8_t + - name: controlrate_profile + description: "Control rate profile to switch to when the battery profile is selected, 0 to disable and keep the currently selected control rate profile" + default_value: 0 + field: controlRateProfile + min: 0 + max: MAX_CONTROL_RATE_PROFILE_COUNT - name: PG_MIXER_CONFIG type: mixerConfig_t @@ -1230,7 +1238,7 @@ groups: - name: PG_CONTROL_RATE_PROFILES type: controlRateConfig_t - headers: ["fc/controlrate_profile.h"] + headers: ["fc/controlrate_profile_config_struct.h"] value_type: CONTROL_RATE_VALUE members: - name: thr_mid diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index feaf9c46ba..ebac2987d4 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -36,6 +36,7 @@ #include "drivers/time.h" #include "fc/config.h" +#include "fc/controlrate_profile.h" #include "fc/fc_core.h" #include "fc/runtime_config.h" #include "fc/stats.h" @@ -93,7 +94,7 @@ static int32_t mWhDrawn = 0; // energy (milliWatt hours) draw batteryState_e batteryState; const batteryProfile_t *currentBatteryProfile; -PG_REGISTER_ARRAY_WITH_RESET_FN(batteryProfile_t, MAX_BATTERY_PROFILE_COUNT, batteryProfiles, PG_BATTERY_PROFILES, 0); +PG_REGISTER_ARRAY_WITH_RESET_FN(batteryProfile_t, MAX_BATTERY_PROFILE_COUNT, batteryProfiles, PG_BATTERY_PROFILES, 1); void pgResetFn_batteryProfiles(batteryProfile_t *instance) { @@ -115,7 +116,9 @@ void pgResetFn_batteryProfiles(batteryProfile_t *instance) .warning = SETTING_BATTERY_CAPACITY_WARNING_DEFAULT, .critical = SETTING_BATTERY_CAPACITY_CRITICAL_DEFAULT, .unit = SETTING_BATTERY_CAPACITY_UNIT_DEFAULT, - } + }, + + .controlRateProfile = 0, ); } } @@ -197,6 +200,9 @@ void setBatteryProfile(uint8_t profileIndex) profileIndex = 0; } currentBatteryProfile = batteryProfiles(profileIndex); + if ((currentBatteryProfile->controlRateProfile > 0) && (currentBatteryProfile->controlRateProfile < MAX_CONTROL_RATE_PROFILE_COUNT)) { + setConfigProfile(currentBatteryProfile->controlRateProfile - 1); + } } void activateBatteryProfile(void) diff --git a/src/main/sensors/battery.h b/src/main/sensors/battery.h index 6c4cd1bede..9efef60c5a 100644 --- a/src/main/sensors/battery.h +++ b/src/main/sensors/battery.h @@ -112,6 +112,8 @@ typedef struct batteryProfile_s { batCapacityUnit_e unit; // Describes unit of capacity.value, capacity.warning and capacity.critical } capacity; + uint8_t controlRateProfile; + } batteryProfile_t; PG_DECLARE(batteryMetersConfig_t, batteryMetersConfig); From 04f4887c67401ff10ddab24c522bddc26960e787 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Tue, 15 Jun 2021 16:34:10 +0200 Subject: [PATCH 052/102] Make battery profile count configurable from settings.yaml (#7072) --- docs/Settings.md | 2 +- src/main/CMakeLists.txt | 3 +- src/main/fc/settings.h | 6 +- src/main/fc/settings.yaml | 12 +-- src/main/sensors/battery.h | 82 ++----------------- src/main/sensors/battery_config_structs.h | 99 +++++++++++++++++++++++ 6 files changed, 118 insertions(+), 86 deletions(-) create mode 100644 src/main/sensors/battery_config_structs.h diff --git a/docs/Settings.md b/docs/Settings.md index 9f8c1611f7..577247afa4 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -5558,7 +5558,7 @@ Battery voltage calibration value. 1100 = 11:1 voltage divider (10k:1k) x 100. A | Default | Min | Max | | --- | --- | --- | -| _target default_ | VBAT_SCALE_MIN | VBAT_SCALE_MAX | +| _target default_ | 0 | 65535 | --- diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 13e1b564f1..00968141ee 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -242,7 +242,7 @@ main_sources(COMMON_SRC drivers/rangefinder/rangefinder_virtual.h drivers/rangefinder/rangefinder_us42.c drivers/rangefinder/rangefinder_us42.h - + drivers/resource.c drivers/resource.h drivers/rcc.c @@ -441,6 +441,7 @@ main_sources(COMMON_SRC sensors/acceleration.h sensors/battery.c sensors/battery.h + sensors/battery_config_structs.h sensors/boardalignment.c sensors/boardalignment.h sensors/compass.c diff --git a/src/main/fc/settings.h b/src/main/fc/settings.h index e73f7d65c1..b14289ba27 100644 --- a/src/main/fc/settings.h +++ b/src/main/fc/settings.h @@ -67,9 +67,9 @@ typedef struct { } __attribute__((packed)) setting_t; -static inline setting_type_e SETTING_TYPE(const setting_t *s) { return s->type & SETTING_TYPE_MASK; } -static inline setting_section_e SETTING_SECTION(const setting_t *s) { return s->type & SETTING_SECTION_MASK; } -static inline setting_mode_e SETTING_MODE(const setting_t *s) { return s->type & SETTING_MODE_MASK; } +static inline setting_type_e SETTING_TYPE(const setting_t *s) { return (setting_type_e)(s->type & SETTING_TYPE_MASK); } +static inline setting_section_e SETTING_SECTION(const setting_t *s) { return (setting_section_e)(s->type & SETTING_SECTION_MASK); } +static inline setting_mode_e SETTING_MODE(const setting_t *s) { return (setting_mode_e)(s->type & SETTING_MODE_MASK); } void settingGetName(const setting_t *val, char *buf); bool settingNameContains(const setting_t *val, char *buf, const char *cmdline); diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 4e5cf71ceb..bb8a3640a0 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -181,7 +181,7 @@ tables: values: ["OFF", "ON", "ON_FW_SPIRAL"] - name: djiRssiSource values: ["RSSI", "CRSF_LQ"] - enum: djiRssiSource_e + enum: djiRssiSource_e constants: @@ -195,6 +195,8 @@ constants: ROLL_PITCH_RATE_MAX: 180 MAX_CONTROL_RATE_PROFILE_COUNT: 3 + MAX_BATTERY_PROFILE_COUNT: 3 + groups: - name: PG_GYRO_CONFIG @@ -1005,7 +1007,7 @@ groups: - name: PG_BATTERY_METERS_CONFIG type: batteryMetersConfig_t - headers: ["sensors/battery.h"] + headers: ["sensors/battery_config_structs.h"] members: - name: vbat_meter_type description: "Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running" @@ -1019,8 +1021,8 @@ groups: default_value: :target field: voltage.scale condition: USE_ADC - min: VBAT_SCALE_MIN - max: VBAT_SCALE_MAX + min: 0 + max: 65535 - name: current_meter_scale description: "This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt." default_value: :target @@ -1071,7 +1073,7 @@ groups: - name: PG_BATTERY_PROFILES type: batteryProfile_t - headers: ["sensors/battery.h"] + headers: ["sensors/battery_config_structs.h"] value_type: BATTERY_CONFIG_VALUE members: - name: bat_cells diff --git a/src/main/sensors/battery.h b/src/main/sensors/battery.h index 9efef60c5a..04e25e993b 100644 --- a/src/main/sensors/battery.h +++ b/src/main/sensors/battery.h @@ -18,13 +18,16 @@ #pragma once #include "config/parameter_group.h" + #include "drivers/time.h" +#include "fc/settings.h" + +#include "sensors/battery_config_structs.h" + #ifndef VBAT_SCALE_DEFAULT #define VBAT_SCALE_DEFAULT 1100 #endif -#define VBAT_SCALE_MIN 0 -#define VBAT_SCALE_MAX 65535 #ifndef CURRENT_METER_SCALE #define CURRENT_METER_SCALE 400 // for Allegro ACS758LCB-100U (40mV/A) @@ -35,87 +38,14 @@ #endif #ifndef MAX_BATTERY_PROFILE_COUNT -#define MAX_BATTERY_PROFILE_COUNT 3 +#define MAX_BATTERY_PROFILE_COUNT SETTING_CONSTANT_MAX_BATTERY_PROFILE_COUNT #endif -typedef enum { - CURRENT_SENSOR_NONE = 0, - CURRENT_SENSOR_ADC, - CURRENT_SENSOR_VIRTUAL, - CURRENT_SENSOR_ESC, - CURRENT_SENSOR_MAX = CURRENT_SENSOR_VIRTUAL -} currentSensor_e; - -typedef enum { - VOLTAGE_SENSOR_NONE = 0, - VOLTAGE_SENSOR_ADC, - VOLTAGE_SENSOR_ESC -} voltageSensor_e; - -typedef enum { - BAT_CAPACITY_UNIT_MAH, - BAT_CAPACITY_UNIT_MWH, -} batCapacityUnit_e; - typedef struct { uint8_t profile_index; uint16_t max_voltage; } profile_comp_t; -typedef enum { - BAT_VOLTAGE_RAW, - BAT_VOLTAGE_SAG_COMP -} batVoltageSource_e; - -typedef struct batteryMetersConfig_s { - -#ifdef USE_ADC - struct { - uint16_t scale; - voltageSensor_e type; - } voltage; -#endif - - struct { - int16_t scale; // scale the current sensor output voltage to milliamps. Value in 1/10th mV/A - int16_t offset; // offset of the current sensor in millivolt steps - currentSensor_e type; // type of current meter used, either ADC or virtual - } current; - - batVoltageSource_e voltageSource; - - uint32_t cruise_power; // power drawn by the motor(s) at cruise throttle/speed (cW) - uint16_t idle_power; // power drawn by the system when the motor(s) are stopped (cW) - uint8_t rth_energy_margin; // Energy that should be left after RTH (%), used for remaining time/distance before RTH - - float throttle_compensation_weight; - -} batteryMetersConfig_t; - -typedef struct batteryProfile_s { - -#ifdef USE_ADC - uint8_t cells; - - struct { - uint16_t cellDetect; // maximum voltage per cell, used for auto-detecting battery cell count in 0.01V units, default is 430 (4.3V) - uint16_t cellMax; // maximum voltage per cell, used for auto-detecting battery voltage in 0.01V units, default is 421 (4.21V) - uint16_t cellMin; // minimum voltage per cell, this triggers battery critical alarm, in 0.01V units, default is 330 (3.3V) - uint16_t cellWarning; // warning voltage per cell, this triggers battery warning alarm, in 0.01V units, default is 350 (3.5V) - } voltage; -#endif - - struct { - uint32_t value; // mAh or mWh (see capacity.unit) - uint32_t warning; // mAh or mWh (see capacity.unit) - uint32_t critical; // mAh or mWh (see capacity.unit) - batCapacityUnit_e unit; // Describes unit of capacity.value, capacity.warning and capacity.critical - } capacity; - - uint8_t controlRateProfile; - -} batteryProfile_t; - PG_DECLARE(batteryMetersConfig_t, batteryMetersConfig); PG_DECLARE_ARRAY(batteryProfile_t, MAX_BATTERY_PROFILE_COUNT, batteryProfiles); diff --git a/src/main/sensors/battery_config_structs.h b/src/main/sensors/battery_config_structs.h new file mode 100644 index 0000000000..5b6d380385 --- /dev/null +++ b/src/main/sensors/battery_config_structs.h @@ -0,0 +1,99 @@ +/* + * This file is part of iNav + * + * iNav free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * iNav distributed in the hope that it + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +#include +#include + +#include "platform.h" + +typedef enum { + CURRENT_SENSOR_NONE = 0, + CURRENT_SENSOR_ADC, + CURRENT_SENSOR_VIRTUAL, + CURRENT_SENSOR_ESC, + CURRENT_SENSOR_MAX = CURRENT_SENSOR_VIRTUAL +} currentSensor_e; + +typedef enum { + VOLTAGE_SENSOR_NONE = 0, + VOLTAGE_SENSOR_ADC, + VOLTAGE_SENSOR_ESC +} voltageSensor_e; + +typedef enum { + BAT_CAPACITY_UNIT_MAH, + BAT_CAPACITY_UNIT_MWH, +} batCapacityUnit_e; + +typedef enum { + BAT_VOLTAGE_RAW, + BAT_VOLTAGE_SAG_COMP +} batVoltageSource_e; + +typedef struct batteryMetersConfig_s { + +#ifdef USE_ADC + struct { + uint16_t scale; + voltageSensor_e type; + } voltage; +#endif + + struct { + int16_t scale; // scale the current sensor output voltage to milliamps. Value in 1/10th mV/A + int16_t offset; // offset of the current sensor in millivolt steps + currentSensor_e type; // type of current meter used, either ADC or virtual + } current; + + batVoltageSource_e voltageSource; + + uint32_t cruise_power; // power drawn by the motor(s) at cruise throttle/speed (cW) + uint16_t idle_power; // power drawn by the system when the motor(s) are stopped (cW) + uint8_t rth_energy_margin; // Energy that should be left after RTH (%), used for remaining time/distance before RTH + + float throttle_compensation_weight; + +} batteryMetersConfig_t; + +typedef struct batteryProfile_s { + +#ifdef USE_ADC + uint8_t cells; + + struct { + uint16_t cellDetect; // maximum voltage per cell, used for auto-detecting battery cell count in 0.01V units, default is 430 (4.3V) + uint16_t cellMax; // maximum voltage per cell, used for auto-detecting battery voltage in 0.01V units, default is 421 (4.21V) + uint16_t cellMin; // minimum voltage per cell, this triggers battery critical alarm, in 0.01V units, default is 330 (3.3V) + uint16_t cellWarning; // warning voltage per cell, this triggers battery warning alarm, in 0.01V units, default is 350 (3.5V) + } voltage; +#endif + + struct { + uint32_t value; // mAh or mWh (see capacity.unit) + uint32_t warning; // mAh or mWh (see capacity.unit) + uint32_t critical; // mAh or mWh (see capacity.unit) + batCapacityUnit_e unit; // Describes unit of capacity.value, capacity.warning and capacity.critical + } capacity; + + uint8_t controlRateProfile; + +} batteryProfile_t; From 7dad0bfa681d7940f49ec9932be924b2b6f09aa9 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Tue, 15 Jun 2021 17:13:57 +0200 Subject: [PATCH 053/102] Add battery voltage/weight/power density influenced settings to battery profiles (#7074) --- src/main/fc/fc_msp.c | 33 ++- src/main/fc/rc_adjustments.c | 7 +- src/main/fc/settings.yaml | 237 ++++++++++--------- src/main/flight/failsafe.c | 10 +- src/main/flight/failsafe.h | 1 - src/main/flight/mixer.c | 18 +- src/main/flight/mixer.h | 4 - src/main/flight/pid.c | 77 +++--- src/main/flight/power_limits.c | 52 ++-- src/main/flight/power_limits.h | 14 +- src/main/flight/rth_estimator.c | 6 +- src/main/io/osd.c | 10 +- src/main/io/osd_dji_hd.c | 6 +- src/main/navigation/navigation.c | 9 +- src/main/navigation/navigation.h | 7 - src/main/navigation/navigation_fixedwing.c | 18 +- src/main/navigation/navigation_fw_launch.c | 16 +- src/main/navigation/navigation_multicopter.c | 20 +- src/main/navigation/navigation_rover_boat.c | 10 +- src/main/sensors/battery.c | 45 ++++ src/main/sensors/battery.h | 2 + src/main/sensors/battery_config_structs.h | 53 ++++- src/main/target/FALCORE/config.c | 4 +- 23 files changed, 362 insertions(+), 297 deletions(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index b80c33cfe0..c534531bc9 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -774,7 +774,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU16(dst, motorConfig()->maxthrottle); sbufWriteU16(dst, motorConfig()->mincommand); - sbufWriteU16(dst, failsafeConfig()->failsafe_throttle); + sbufWriteU16(dst, currentBatteryProfile->failsafe_throttle); #ifdef USE_GPS sbufWriteU8(dst, gpsConfig()->provider); // gps_type @@ -815,7 +815,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU16(dst, motorConfig()->maxthrottle); sbufWriteU16(dst, motorConfig()->mincommand); - sbufWriteU16(dst, failsafeConfig()->failsafe_throttle); + sbufWriteU16(dst, currentBatteryProfile->failsafe_throttle); #ifdef USE_GPS sbufWriteU8(dst, gpsConfig()->provider); // gps_type @@ -1041,7 +1041,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF case MSP_FAILSAFE_CONFIG: sbufWriteU8(dst, failsafeConfig()->failsafe_delay); sbufWriteU8(dst, failsafeConfig()->failsafe_off_delay); - sbufWriteU16(dst, failsafeConfig()->failsafe_throttle); + sbufWriteU16(dst, currentBatteryProfile->failsafe_throttle); sbufWriteU8(dst, 0); // was failsafe_kill_switch sbufWriteU16(dst, failsafeConfig()->failsafe_throttle_low_delay); sbufWriteU8(dst, failsafeConfig()->failsafe_procedure); @@ -1322,7 +1322,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU16(dst, navConfig()->general.max_manual_climb_rate); sbufWriteU8(dst, navConfig()->mc.max_bank_angle); sbufWriteU8(dst, navConfig()->general.flags.use_thr_mid_for_althold); - sbufWriteU16(dst, navConfig()->mc.hover_throttle); + sbufWriteU16(dst, currentBatteryProfile->nav.mc.hover_throttle); break; case MSP_RTH_AND_LAND_CONFIG: @@ -1342,13 +1342,13 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF break; case MSP_FW_CONFIG: - sbufWriteU16(dst, navConfig()->fw.cruise_throttle); - sbufWriteU16(dst, navConfig()->fw.min_throttle); - sbufWriteU16(dst, navConfig()->fw.max_throttle); + sbufWriteU16(dst, currentBatteryProfile->nav.fw.cruise_throttle); + sbufWriteU16(dst, currentBatteryProfile->nav.fw.min_throttle); + sbufWriteU16(dst, currentBatteryProfile->nav.fw.max_throttle); sbufWriteU8(dst, navConfig()->fw.max_bank_angle); sbufWriteU8(dst, navConfig()->fw.max_climb_angle); sbufWriteU8(dst, navConfig()->fw.max_dive_angle); - sbufWriteU8(dst, navConfig()->fw.pitch_to_throttle); + sbufWriteU8(dst, currentBatteryProfile->nav.fw.pitch_to_throttle); sbufWriteU16(dst, navConfig()->fw.loiter_radius); break; #endif @@ -1664,7 +1664,6 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) { uint8_t tmp_u8; uint16_t tmp_u16; - batteryProfile_t *currentBatteryProfileMutable = (batteryProfile_t*)currentBatteryProfile; const unsigned int dataSize = sbufBytesRemaining(src); @@ -1867,7 +1866,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) motorConfigMutable()->maxthrottle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); motorConfigMutable()->mincommand = constrain(sbufReadU16(src), 0, PWM_RANGE_MAX); - failsafeConfigMutable()->failsafe_throttle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); + currentBatteryProfileMutable->failsafe_throttle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); #ifdef USE_GPS gpsConfigMutable()->provider = sbufReadU8(src); // gps_type @@ -1915,7 +1914,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) motorConfigMutable()->maxthrottle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); motorConfigMutable()->mincommand = constrain(sbufReadU16(src), 0, PWM_RANGE_MAX); - failsafeConfigMutable()->failsafe_throttle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); + currentBatteryProfileMutable->failsafe_throttle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); #ifdef USE_GPS gpsConfigMutable()->provider = sbufReadU8(src); // gps_type @@ -2293,7 +2292,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) navConfigMutable()->general.max_manual_climb_rate = sbufReadU16(src); navConfigMutable()->mc.max_bank_angle = sbufReadU8(src); navConfigMutable()->general.flags.use_thr_mid_for_althold = sbufReadU8(src); - navConfigMutable()->mc.hover_throttle = sbufReadU16(src); + currentBatteryProfileMutable->nav.mc.hover_throttle = sbufReadU16(src); } else return MSP_RESULT_ERROR; break; @@ -2319,13 +2318,13 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) case MSP_SET_FW_CONFIG: if (dataSize >= 12) { - navConfigMutable()->fw.cruise_throttle = sbufReadU16(src); - navConfigMutable()->fw.min_throttle = sbufReadU16(src); - navConfigMutable()->fw.max_throttle = sbufReadU16(src); + currentBatteryProfileMutable->nav.fw.cruise_throttle = sbufReadU16(src); + currentBatteryProfileMutable->nav.fw.min_throttle = sbufReadU16(src); + currentBatteryProfileMutable->nav.fw.max_throttle = sbufReadU16(src); navConfigMutable()->fw.max_bank_angle = sbufReadU8(src); navConfigMutable()->fw.max_climb_angle = sbufReadU8(src); navConfigMutable()->fw.max_dive_angle = sbufReadU8(src); - navConfigMutable()->fw.pitch_to_throttle = sbufReadU8(src); + currentBatteryProfileMutable->nav.fw.pitch_to_throttle = sbufReadU8(src); navConfigMutable()->fw.loiter_radius = sbufReadU16(src); } else return MSP_RESULT_ERROR; @@ -2695,7 +2694,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) if (dataSize >= 20) { failsafeConfigMutable()->failsafe_delay = sbufReadU8(src); failsafeConfigMutable()->failsafe_off_delay = sbufReadU8(src); - failsafeConfigMutable()->failsafe_throttle = sbufReadU16(src); + currentBatteryProfileMutable->failsafe_throttle = sbufReadU16(src); sbufReadU8(src); // was failsafe_kill_switch failsafeConfigMutable()->failsafe_throttle_low_delay = sbufReadU16(src); failsafeConfigMutable()->failsafe_procedure = sbufReadU8(src); diff --git a/src/main/fc/rc_adjustments.c b/src/main/fc/rc_adjustments.c index 7019869591..610e62f16e 100644 --- a/src/main/fc/rc_adjustments.c +++ b/src/main/fc/rc_adjustments.c @@ -49,6 +49,7 @@ #include "io/beeper.h" #include "io/vtx.h" +#include "sensors/battery.h" #include "sensors/boardalignment.h" #include "rx/rx.h" @@ -500,10 +501,10 @@ static void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t schedulePidGainsUpdate(); break; case ADJUSTMENT_NAV_FW_CRUISE_THR: - applyAdjustmentU16(ADJUSTMENT_NAV_FW_CRUISE_THR, &navConfigMutable()->fw.cruise_throttle, delta, SETTING_NAV_FW_CRUISE_THR_MIN, SETTING_NAV_FW_CRUISE_THR_MAX); + applyAdjustmentU16(ADJUSTMENT_NAV_FW_CRUISE_THR, ¤tBatteryProfileMutable->nav.fw.cruise_throttle, delta, SETTING_NAV_FW_CRUISE_THR_MIN, SETTING_NAV_FW_CRUISE_THR_MAX); break; case ADJUSTMENT_NAV_FW_PITCH2THR: - applyAdjustmentU8(ADJUSTMENT_NAV_FW_PITCH2THR, &navConfigMutable()->fw.pitch_to_throttle, delta, SETTING_NAV_FW_PITCH2THR_MIN, SETTING_NAV_FW_PITCH2THR_MAX); + applyAdjustmentU8(ADJUSTMENT_NAV_FW_PITCH2THR, ¤tBatteryProfileMutable->nav.fw.pitch_to_throttle, delta, SETTING_NAV_FW_PITCH2THR_MIN, SETTING_NAV_FW_PITCH2THR_MAX); break; case ADJUSTMENT_ROLL_BOARD_ALIGNMENT: updateBoardAlignment(delta, 0); @@ -578,7 +579,7 @@ static void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t navigationUsePIDs(); break; case ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE: - applyAdjustmentU16(ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE, &mixerConfigMutable()->fwMinThrottleDownPitchAngle, delta, SETTING_FW_MIN_THROTTLE_DOWN_PITCH_MIN, SETTING_FW_MIN_THROTTLE_DOWN_PITCH_MAX); + applyAdjustmentU16(ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE, ¤tBatteryProfileMutable->fwMinThrottleDownPitchAngle, delta, SETTING_FW_MIN_THROTTLE_DOWN_PITCH_MIN, SETTING_FW_MIN_THROTTLE_DOWN_PITCH_MAX); break; #if defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP) case ADJUSTMENT_VTX_POWER_LEVEL: diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index bb8a3640a0..10c9b9430f 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -865,31 +865,12 @@ groups: default_value: "ONESHOT125" field: motorPwmProtocol table: motor_pwm_protocol - - name: throttle_scale - description: "Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50%" - default_value: 1.0 - field: throttleScale - min: 0 - max: 1 - - name: throttle_idle - description: "The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle." - default_value: 15 - field: throttleIdle - min: 0 - max: 30 - name: motor_poles field: motorPoleCount description: "The number of motor poles. Required to compute motor RPM" min: 4 max: 255 default_value: 14 - - name: turtle_mode_power_factor - field: turtleModePowerFactor - default_value: 55 - description: "Turtle mode power factor" - condition: "USE_DSHOT" - min: 0 - max: 100 - name: PG_FAILSAFE_CONFIG type: failsafeConfig_t @@ -910,11 +891,6 @@ groups: default_value: 200 min: 0 max: 200 - - name: failsafe_throttle - description: "Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." - default_value: 1000 - min: PWM_RANGE_MIN - max: PWM_RANGE_MAX - name: failsafe_throttle_low_delay description: "If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout" default_value: 0 @@ -1142,6 +1118,127 @@ groups: min: 0 max: MAX_CONTROL_RATE_PROFILE_COUNT + - name: throttle_scale + description: "Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50%" + default_value: 1.0 + field: motor.throttleScale + min: 0 + max: 1 + - name: throttle_idle + description: "The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle." + default_value: 15 + field: motor.throttleIdle + min: 0 + max: 30 + - name: turtle_mode_power_factor + field: motor.turtleModePowerFactor + default_value: 55 + description: "Turtle mode power factor" + condition: "USE_DSHOT" + min: 0 + max: 100 + - name: failsafe_throttle + description: "Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." + default_value: 1000 + min: PWM_RANGE_MIN + max: PWM_RANGE_MAX + - name: fw_min_throttle_down_pitch + description: "Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)" + default_value: 0 + field: fwMinThrottleDownPitchAngle + min: 0 + max: 450 + - name: nav_mc_hover_thr + description: "Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering." + default_value: 1500 + field: nav.mc.hover_throttle + min: 1000 + max: 2000 + - name: nav_fw_cruise_thr + description: "Cruise throttle in GPS assisted modes, this includes RTH. Should be set high enough to avoid stalling. This values gives INAV a base for throttle when flying straight, and it will increase or decrease throttle based on pitch of airplane and the parameters below. In addition it will increase throttle if GPS speed gets below 7m/s ( hardcoded )" + default_value: 1400 + field: nav.fw.cruise_throttle + min: 1000 + max: 2000 + - name: nav_fw_min_thr + description: "Minimum throttle for flying wing in GPS assisted modes" + default_value: 1200 + field: nav.fw.min_throttle + min: 1000 + max: 2000 + - name: nav_fw_max_thr + description: "Maximum throttle for flying wing in GPS assisted modes" + default_value: 1700 + field: nav.fw.max_throttle + min: 1000 + max: 2000 + - name: nav_fw_pitch2thr + description: "Amount of throttle applied related to pitch attitude in GPS assisted modes. Throttle = nav_fw_cruise_throttle - (nav_fw_pitch2thr * pitch_angle). (notice that pitch_angle is in degrees and is negative when climbing and positive when diving, and throttle value is constrained between nav_fw_min_thr and nav_fw_max_thr)" + default_value: 10 + field: nav.fw.pitch_to_throttle + min: 0 + max: 100 + - name: nav_fw_launch_thr + description: "Launch throttle - throttle to be set during launch sequence (pwm units)" + default_value: 1700 + field: nav.fw.launch_throttle + min: 1000 + max: 2000 + - name: nav_fw_launch_idle_thr + description: "Launch idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position)" + default_value: 1000 + field: nav.fw.launch_idle_throttle + min: 1000 + max: 2000 + - name: limit_cont_current + description: "Continous current limit (dA), set to 0 to disable" + condition: USE_POWER_LIMITS + default_value: 0 + field: powerLimits.continuousCurrent + max: 4000 + - name: limit_burst_current + description: "Burst current limit (dA): the current which is allowed during `limit_burst_current_time` after which `limit_cont_current` will be enforced, set to 0 to disable" + condition: USE_POWER_LIMITS + default_value: 0 + field: powerLimits.burstCurrent + max: 4000 + - name: limit_burst_current_time + description: "Allowed current burst time (ds) during which `limit_burst_current` is allowed and after which `limit_cont_current` will be enforced" + condition: USE_POWER_LIMITS + default_value: 0 + field: powerLimits.burstCurrentTime + max: 3000 + - name: limit_burst_current_falldown_time + description: "Time slice at the end of the burst time during which the current limit will be ramped down from `limit_burst_current` back down to `limit_cont_current`" + condition: USE_POWER_LIMITS + default_value: 0 + field: powerLimits.burstCurrentFalldownTime + max: 3000 + - name: limit_cont_power + description: "Continous power limit (dW), set to 0 to disable" + condition: USE_POWER_LIMITS && USE_ADC + default_value: 0 + field: powerLimits.continuousPower + max: 40000 + - name: limit_burst_power + description: "Burst power limit (dW): the current which is allowed during `limit_burst_power_time` after which `limit_cont_power` will be enforced, set to 0 to disable" + condition: USE_POWER_LIMITS && USE_ADC + default_value: 0 + field: powerLimits.burstPower + max: 40000 + - name: limit_burst_power_time + description: "Allowed power burst time (ds) during which `limit_burst_power` is allowed and after which `limit_cont_power` will be enforced" + condition: USE_POWER_LIMITS && USE_ADC + default_value: 0 + field: powerLimits.burstPowerTime + max: 3000 + - name: limit_burst_power_falldown_time + description: "Time slice at the end of the burst time during which the power limit will be ramped down from `limit_burst_power` back down to `limit_cont_power`" + condition: USE_POWER_LIMITS && USE_ADC + default_value: 0 + field: powerLimits.burstPowerFalldownTime + max: 3000 + - name: PG_MIXER_CONFIG type: mixerConfig_t members: @@ -1167,12 +1264,6 @@ groups: field: appliedMixerPreset min: -1 max: INT16_MAX - - name: fw_min_throttle_down_pitch - description: "Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)" - default_value: 0 - field: fwMinThrottleDownPitchAngle - min: 0 - max: 450 - name: PG_REVERSIBLE_MOTORS_CONFIG type: reversibleMotorsConfig_t @@ -2496,12 +2587,6 @@ groups: field: mc.max_bank_angle min: 15 max: 45 - - name: nav_mc_hover_thr - description: "Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering." - default_value: 1500 - field: mc.hover_throttle - min: 1000 - max: 2000 - name: nav_mc_auto_disarm_delay description: "Delay before multi-rotor disarms when `nav_disarm_on_landing` is set (m/s)" default_value: 2000 @@ -2583,24 +2668,6 @@ groups: default_value: ON field: mc.slowDownForTurning type: bool - - name: nav_fw_cruise_thr - description: "Cruise throttle in GPS assisted modes, this includes RTH. Should be set high enough to avoid stalling. This values gives INAV a base for throttle when flying straight, and it will increase or decrease throttle based on pitch of airplane and the parameters below. In addition it will increase throttle if GPS speed gets below 7m/s ( hardcoded )" - default_value: 1400 - field: fw.cruise_throttle - min: 1000 - max: 2000 - - name: nav_fw_min_thr - description: "Minimum throttle for flying wing in GPS assisted modes" - default_value: 1200 - field: fw.min_throttle - min: 1000 - max: 2000 - - name: nav_fw_max_thr - description: "Maximum throttle for flying wing in GPS assisted modes" - default_value: 1700 - field: fw.max_throttle - min: 1000 - max: 2000 - name: nav_fw_bank_angle description: "Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll" default_value: 35 @@ -2619,12 +2686,6 @@ groups: field: fw.max_dive_angle min: 5 max: 80 - - name: nav_fw_pitch2thr - description: "Amount of throttle applied related to pitch attitude in GPS assisted modes. Throttle = nav_fw_cruise_throttle - (nav_fw_pitch2thr * pitch_angle). (notice that pitch_angle is in degrees and is negative when climbing and positive when diving, and throttle value is constrained between nav_fw_min_thr and nav_fw_max_thr)" - default_value: 10 - field: fw.pitch_to_throttle - min: 0 - max: 100 - name: nav_fw_pitch2thr_smoothing description: "How smoothly the autopilot makes pitch to throttle correction inside a deadband defined by pitch_to_throttle_thresh." default_value: 6 @@ -2688,18 +2749,6 @@ groups: field: fw.launch_time_thresh min: 10 max: 1000 - - name: nav_fw_launch_thr - description: "Launch throttle - throttle to be set during launch sequence (pwm units)" - default_value: 1700 - field: fw.launch_throttle - min: 1000 - max: 2000 - - name: nav_fw_launch_idle_thr - description: "Launch idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position)" - default_value: 1000 - field: fw.launch_idle_throttle - min: 1000 - max: 2000 - name: nav_fw_launch_idle_motor_delay description: "Delay between raising throttle and motor starting at idle throttle (ms)" default_value: 0 @@ -3705,50 +3754,6 @@ groups: headers: ["flight/power_limits.h"] condition: USE_POWER_LIMITS members: - - name: limit_cont_current - description: "Continous current limit (dA), set to 0 to disable" - default_value: 0 - field: continuousCurrent - max: 4000 - - name: limit_burst_current - description: "Burst current limit (dA): the current which is allowed during `limit_burst_current_time` after which `limit_cont_current` will be enforced, set to 0 to disable" - default_value: 0 - field: burstCurrent - max: 4000 - - name: limit_burst_current_time - description: "Allowed current burst time (ds) during which `limit_burst_current` is allowed and after which `limit_cont_current` will be enforced" - default_value: 0 - field: burstCurrentTime - max: 3000 - - name: limit_burst_current_falldown_time - description: "Time slice at the end of the burst time during which the current limit will be ramped down from `limit_burst_current` back down to `limit_cont_current`" - default_value: 0 - field: burstCurrentFalldownTime - max: 3000 - - name: limit_cont_power - condition: USE_ADC - description: "Continous power limit (dW), set to 0 to disable" - default_value: 0 - field: continuousPower - max: 40000 - - name: limit_burst_power - condition: USE_ADC - description: "Burst power limit (dW): the current which is allowed during `limit_burst_power_time` after which `limit_cont_power` will be enforced, set to 0 to disable" - default_value: 0 - field: burstPower - max: 40000 - - name: limit_burst_power_time - condition: USE_ADC - description: "Allowed power burst time (ds) during which `limit_burst_power` is allowed and after which `limit_cont_power` will be enforced" - default_value: 0 - field: burstPowerTime - max: 3000 - - name: limit_burst_power_falldown_time - condition: USE_ADC - description: "Time slice at the end of the burst time during which the power limit will be ramped down from `limit_burst_power` back down to `limit_cont_power`" - default_value: 0 - field: burstPowerFalldownTime - max: 3000 - name: limit_pi_p description: "Throttle attenuation PI control P term" default_value: 100 diff --git a/src/main/flight/failsafe.c b/src/main/flight/failsafe.c index 90173dc473..fa1d31c34f 100644 --- a/src/main/flight/failsafe.c +++ b/src/main/flight/failsafe.c @@ -51,6 +51,7 @@ #include "rx/rx.h" +#include "sensors/battery.h" #include "sensors/sensors.h" /* @@ -66,13 +67,12 @@ static failsafeState_t failsafeState; -PG_REGISTER_WITH_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig, PG_FAILSAFE_CONFIG, 1); +PG_REGISTER_WITH_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig, PG_FAILSAFE_CONFIG, 2); PG_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig, .failsafe_delay = SETTING_FAILSAFE_DELAY_DEFAULT, // 0.5 sec .failsafe_recovery_delay = SETTING_FAILSAFE_RECOVERY_DELAY_DEFAULT, // 0.5 seconds (plus 200ms explicit delay) .failsafe_off_delay = SETTING_FAILSAFE_OFF_DELAY_DEFAULT, // 20sec - .failsafe_throttle = SETTING_FAILSAFE_THROTTLE_DEFAULT, // default throttle off. .failsafe_throttle_low_delay = SETTING_FAILSAFE_THROTTLE_LOW_DELAY_DEFAULT, // default throttle low delay for "just disarm" on failsafe condition .failsafe_procedure = SETTING_FAILSAFE_PROCEDURE_DEFAULT, // default full failsafe procedure .failsafe_fw_roll_angle = SETTING_FAILSAFE_FW_ROLL_ANGLE_DEFAULT, // 20 deg left @@ -218,7 +218,7 @@ bool failsafeRequiresMotorStop(void) { return failsafeState.active && failsafeState.activeProcedure == FAILSAFE_PROCEDURE_AUTO_LANDING && - failsafeConfig()->failsafe_throttle < getThrottleIdleValue(); + currentBatteryProfile->failsafe_throttle < getThrottleIdleValue(); } void failsafeStartMonitoring(void) @@ -264,13 +264,13 @@ void failsafeApplyControlInput(void) autoRcCommand[ROLL] = pidAngleToRcCommand(failsafeConfig()->failsafe_fw_roll_angle, pidProfile()->max_angle_inclination[FD_ROLL]); autoRcCommand[PITCH] = pidAngleToRcCommand(failsafeConfig()->failsafe_fw_pitch_angle, pidProfile()->max_angle_inclination[FD_PITCH]); autoRcCommand[YAW] = -pidRateToRcCommand(failsafeConfig()->failsafe_fw_yaw_rate, currentControlRateProfile->stabilized.rates[FD_YAW]); - autoRcCommand[THROTTLE] = failsafeConfig()->failsafe_throttle; + autoRcCommand[THROTTLE] = currentBatteryProfile->failsafe_throttle; } else { for (int i = 0; i < 3; i++) { autoRcCommand[i] = 0; } - autoRcCommand[THROTTLE] = failsafeConfig()->failsafe_throttle; + autoRcCommand[THROTTLE] = currentBatteryProfile->failsafe_throttle; } // Apply channel values diff --git a/src/main/flight/failsafe.h b/src/main/flight/failsafe.h index cafc01b007..e2ab280ac1 100644 --- a/src/main/flight/failsafe.h +++ b/src/main/flight/failsafe.h @@ -30,7 +30,6 @@ typedef struct failsafeConfig_s { - uint16_t failsafe_throttle; // Throttle level used for landing - specify value between 1000..2000 (pwm pulse width for slightly below hover). center throttle = 1500. uint16_t failsafe_throttle_low_delay; // Time throttle stick must have been below 'min_check' to "JustDisarm" instead of "full failsafe procedure" (TENTH_SECOND) uint8_t failsafe_delay; // Guard time for failsafe activation after signal lost. 1 step = 0.1sec - 1sec in example (10) uint8_t failsafe_recovery_delay; // Time from RC link recovery to failsafe abort. 1 step = 0.1sec - 1sec in example (10) diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index a42625ccb8..b92c999e3b 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -83,14 +83,13 @@ PG_RESET_TEMPLATE(reversibleMotorsConfig_t, reversibleMotorsConfig, .neutral = SETTING_3D_NEUTRAL_DEFAULT ); -PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_CONFIG, 3); +PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_CONFIG, 4); PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig, .motorDirectionInverted = SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT, .platformType = SETTING_PLATFORM_TYPE_DEFAULT, .hasFlaps = SETTING_HAS_FLAPS_DEFAULT, .appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, //This flag is not available in CLI and used by Configurator only - .fwMinThrottleDownPitchAngle = SETTING_FW_MIN_THROTTLE_DOWN_PITCH_DEFAULT ); #ifdef BRUSHED_MOTORS @@ -103,7 +102,7 @@ PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig, #define DEFAULT_MAX_THROTTLE 1850 -PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 7); +PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 8); PG_RESET_TEMPLATE(motorConfig_t, motorConfig, .motorPwmProtocol = SETTING_MOTOR_PWM_PROTOCOL_DEFAULT, @@ -112,12 +111,7 @@ PG_RESET_TEMPLATE(motorConfig_t, motorConfig, .mincommand = SETTING_MIN_COMMAND_DEFAULT, .motorAccelTimeMs = SETTING_MOTOR_ACCEL_TIME_DEFAULT, .motorDecelTimeMs = SETTING_MOTOR_DECEL_TIME_DEFAULT, - .throttleIdle = SETTING_THROTTLE_IDLE_DEFAULT, - .throttleScale = SETTING_THROTTLE_SCALE_DEFAULT, .motorPoleCount = SETTING_MOTOR_POLES_DEFAULT, // Most brushless motors that we use are 14 poles -#ifdef USE_DSHOT - .turtleModePowerFactor = SETTING_TURTLE_MODE_POWER_FACTOR_DEFAULT, -#endif ); PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer, PG_MOTOR_MIXER, 0); @@ -130,7 +124,7 @@ static EXTENDED_FASTRAM motorRateLimitingApplyFnPtr motorRateLimitingApplyFn; int getThrottleIdleValue(void) { if (!throttleIdleValue) { - throttleIdleValue = motorConfig()->mincommand + (((motorConfig()->maxthrottle - motorConfig()->mincommand) / 100.0f) * motorConfig()->throttleIdle); + throttleIdleValue = motorConfig()->mincommand + (((motorConfig()->maxthrottle - motorConfig()->mincommand) / 100.0f) * currentBatteryProfile->motor.throttleIdle); } return throttleIdleValue; @@ -330,7 +324,7 @@ static uint16_t handleOutputScaling( static void applyTurtleModeToMotors(void) { if (ARMING_FLAG(ARMED)) { - const float flipPowerFactor = ((float)motorConfig()->turtleModePowerFactor)/100.0f; + const float flipPowerFactor = ((float)currentBatteryProfile->motor.turtleModePowerFactor)/100.0f; const float stickDeflectionPitchAbs = ABS(((float) rcCommand[PITCH]) / 500.0f); const float stickDeflectionRollAbs = ABS(((float) rcCommand[ROLL]) / 500.0f); const float stickDeflectionYawAbs = ABS(((float) rcCommand[YAW]) / 500.0f); @@ -602,9 +596,9 @@ void FAST_CODE mixTable(const float dT) // Throttle scaling to limit max throttle when battery is full #ifdef USE_PROGRAMMING_FRAMEWORK - mixerThrottleCommand = ((mixerThrottleCommand - throttleRangeMin) * getThrottleScale(motorConfig()->throttleScale)) + throttleRangeMin; + mixerThrottleCommand = ((mixerThrottleCommand - throttleRangeMin) * getThrottleScale(currentBatteryProfile->motor.throttleScale)) + throttleRangeMin; #else - mixerThrottleCommand = ((mixerThrottleCommand - throttleRangeMin) * motorConfig()->throttleScale) + throttleRangeMin; + mixerThrottleCommand = ((mixerThrottleCommand - throttleRangeMin) * currentBatteryProfile->motor.throttleScale) + throttleRangeMin; #endif // Throttle compensation based on battery voltage if (feature(FEATURE_THR_VBAT_COMP) && isAmperageConfigured() && feature(FEATURE_VBAT)) { diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 195df58c30..e40842cb81 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -62,7 +62,6 @@ typedef struct mixerConfig_s { uint8_t platformType; bool hasFlaps; int16_t appliedMixerPreset; - uint16_t fwMinThrottleDownPitchAngle; } mixerConfig_t; PG_DECLARE(mixerConfig_t, mixerConfig); @@ -84,10 +83,7 @@ typedef struct motorConfig_s { uint16_t motorAccelTimeMs; // Time limit for motor to accelerate from 0 to 100% throttle [ms] uint16_t motorDecelTimeMs; // Time limit for motor to decelerate from 0 to 100% throttle [ms] uint16_t digitalIdleOffsetValue; - float throttleIdle; // Throttle IDLE value based on min_command, max_throttle, in percent - float throttleScale; // Scaling factor for throttle. uint8_t motorPoleCount; // Magnetic poles in the motors for calculating actual RPM from eRPM provided by ESC telemetry - uint8_t turtleModePowerFactor; // Power factor from 0 to 100% of flip over after crash } motorConfig_t; PG_DECLARE(motorConfig_t, motorConfig); diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 7a2f57407e..1368c93fad 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -56,6 +56,7 @@ FILE_COMPILE_FOR_SPEED #include "rx/rx.h" +#include "sensors/battery.h" #include "sensors/sensors.h" #include "sensors/gyro.h" #include "sensors/acceleration.h" @@ -368,24 +369,24 @@ bool pidInitFilters(void) #ifdef USE_SMITH_PREDICTOR smithPredictorInit( - &pidState[FD_ROLL].smithPredictor, - pidProfile()->smithPredictorDelay, - pidProfile()->smithPredictorStrength, - pidProfile()->smithPredictorFilterHz, + &pidState[FD_ROLL].smithPredictor, + pidProfile()->smithPredictorDelay, + pidProfile()->smithPredictorStrength, + pidProfile()->smithPredictorFilterHz, getLooptime() ); smithPredictorInit( - &pidState[FD_PITCH].smithPredictor, - pidProfile()->smithPredictorDelay, - pidProfile()->smithPredictorStrength, - pidProfile()->smithPredictorFilterHz, + &pidState[FD_PITCH].smithPredictor, + pidProfile()->smithPredictorDelay, + pidProfile()->smithPredictorStrength, + pidProfile()->smithPredictorFilterHz, getLooptime() ); smithPredictorInit( - &pidState[FD_YAW].smithPredictor, - pidProfile()->smithPredictorDelay, - pidProfile()->smithPredictorStrength, - pidProfile()->smithPredictorFilterHz, + &pidState[FD_YAW].smithPredictor, + pidProfile()->smithPredictorDelay, + pidProfile()->smithPredictorStrength, + pidProfile()->smithPredictorFilterHz, getLooptime() ); #endif @@ -412,7 +413,7 @@ void pidResetErrorAccumulators(void) } } -void pidReduceErrorAccumulators(int8_t delta, uint8_t axis) +void pidReduceErrorAccumulators(int8_t delta, uint8_t axis) { pidState[axis].errorGyroIf -= delta; pidState[axis].errorGyroIfLimit -= delta; @@ -423,7 +424,7 @@ float getTotalRateTarget(void) return fast_fsqrtf(sq(pidState[FD_ROLL].rateTarget) + sq(pidState[FD_PITCH].rateTarget) + sq(pidState[FD_YAW].rateTarget)); } -float getAxisIterm(uint8_t axis) +float getAxisIterm(uint8_t axis) { return pidState[axis].errorGyroIf; } @@ -528,7 +529,7 @@ void updatePIDCoefficients() #ifdef USE_ANTIGRAVITY if (usedPidControllerType == PID_TYPE_PID) { antigravityThrottleHpf = rcCommand[THROTTLE] - pt1FilterApply(&antigravityThrottleLpf, rcCommand[THROTTLE]); - iTermAntigravityGain = scaleRangef(fabsf(antigravityThrottleHpf) * antigravityAccelerator, 0.0f, 1000.0f, 1.0f, antigravityGain); + iTermAntigravityGain = scaleRangef(fabsf(antigravityThrottleHpf) * antigravityAccelerator, 0.0f, 1000.0f, 1.0f, antigravityGain); } #endif @@ -606,7 +607,7 @@ static void pidLevel(pidState_t *pidState, flight_dynamics_index_t axis, float h // Automatically pitch down if the throttle is manually controlled and reduced bellow cruise throttle if ((axis == FD_PITCH) && STATE(AIRPLANE) && FLIGHT_MODE(ANGLE_MODE) && !navigationIsControllingThrottle()) { - angleTarget += scaleRange(MAX(0, navConfig()->fw.cruise_throttle - rcCommand[THROTTLE]), 0, navConfig()->fw.cruise_throttle - PWM_RANGE_MIN, 0, mixerConfig()->fwMinThrottleDownPitchAngle); + angleTarget += scaleRange(MAX(0, currentBatteryProfile->nav.fw.cruise_throttle - rcCommand[THROTTLE]), 0, currentBatteryProfile->nav.fw.cruise_throttle - PWM_RANGE_MIN, 0, currentBatteryProfile->fwMinThrottleDownPitchAngle); } //PITCH trim applied by a AutoLevel flight mode and manual pitch trimming @@ -615,7 +616,7 @@ static void pidLevel(pidState_t *pidState, flight_dynamics_index_t axis, float h DEBUG_SET(DEBUG_AUTOLEVEL, 1, fixedWingLevelTrim * 10); DEBUG_SET(DEBUG_AUTOLEVEL, 2, getEstimatedActualVelocity(Z)); - /* + /* * fixedWingLevelTrim has opposite sign to rcCommand. * Positive rcCommand means nose should point downwards * Negative rcCommand mean nose should point upwards @@ -624,7 +625,7 @@ static void pidLevel(pidState_t *pidState, flight_dynamics_index_t axis, float h * Positive fixedWingLevelTrim means nose should point upwards * Negative fixedWingLevelTrim means nose should point downwards */ - angleTarget -= DEGREES_TO_DECIDEGREES(fixedWingLevelTrim); + angleTarget -= DEGREES_TO_DECIDEGREES(fixedWingLevelTrim); DEBUG_SET(DEBUG_AUTOLEVEL, 3, angleTarget * 10); } @@ -702,23 +703,23 @@ static float pTermProcess(pidState_t *pidState, float rateError, float dT) { #ifdef USE_D_BOOST static float FAST_CODE applyDBoost(pidState_t *pidState, float dT) { - + float dBoost = 1.0f; - + if (dBoostFactor > 1) { const float dBoostGyroDelta = (pidState->gyroRate - pidState->previousRateGyro) / dT; const float dBoostGyroAcceleration = fabsf(biquadFilterApply(&pidState->dBoostGyroLpf, dBoostGyroDelta)); const float dBoostRateAcceleration = fabsf((pidState->rateTarget - pidState->previousRateTarget) / dT); - + const float acceleration = MAX(dBoostGyroAcceleration, dBoostRateAcceleration); dBoost = scaleRangef(acceleration, 0.0f, dBoostMaxAtAlleceleration, 1.0f, dBoostFactor); dBoost = pt1FilterApply4(&pidState->dBoostLpf, dBoost, D_BOOST_LPF_HZ, dT); dBoost = constrainf(dBoost, 1.0f, dBoostFactor); - } + } return dBoost; } -#else +#else static float applyDBoost(pidState_t *pidState, float dT) { UNUSED(pidState); UNUSED(dT); @@ -747,7 +748,7 @@ static float dTermProcess(pidState_t *pidState, float dT) { static void applyItermLimiting(pidState_t *pidState) { if (pidState->itermLimitActive) { pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidState->errorGyroIfLimit, pidState->errorGyroIfLimit); - } else + } else { pidState->errorGyroIfLimit = fabsf(pidState->errorGyroIf); } @@ -806,7 +807,7 @@ static float FAST_CODE applyItermRelax(const int axis, float currentPidSetpoint, const float setpointLpf = pt1FilterApply(&windupLpf[axis], currentPidSetpoint); const float setpointHpf = fabsf(currentPidSetpoint - setpointLpf); - + const float itermRelaxFactor = MAX(0, 1 - setpointHpf / MC_ITERM_RELAX_SETPOINT_THRESHOLD); return itermErrorRate * itermRelaxFactor; } @@ -1051,12 +1052,12 @@ void checkItermLimitingActive(pidState_t *pidState) bool shouldActivate; if (usedPidControllerType == PID_TYPE_PIFF) { shouldActivate = isFixedWingItermLimitActive(pidState->stickPosition); - } else + } else { shouldActivate = mixerIsOutputSaturated(); } - pidState->itermLimitActive = STATE(ANTI_WINDUP) || shouldActivate; + pidState->itermLimitActive = STATE(ANTI_WINDUP) || shouldActivate; } void checkItermFreezingActive(pidState_t *pidState, flight_dynamics_index_t axis) @@ -1074,7 +1075,7 @@ void checkItermFreezingActive(pidState_t *pidState, flight_dynamics_index_t axis { pidState->itermFreezeActive = false; } - + } void FAST_CODE pidController(float dT) @@ -1102,7 +1103,7 @@ void FAST_CODE pidController(float dT) } else { #ifdef USE_PROGRAMMING_FRAMEWORK rateTarget = pidRcCommandToRate(getRcCommandOverride(rcCommand, axis), currentControlRateProfile->stabilized.rates[axis]); -#else +#else rateTarget = pidRcCommandToRate(rcCommand[axis], currentControlRateProfile->stabilized.rates[axis]); #endif } @@ -1153,7 +1154,7 @@ void FAST_CODE pidController(float dT) for (int axis = 0; axis < 3; axis++) { // Apply setpoint rate of change limits pidApplySetpointRateLimiting(&pidState[axis], axis, dT); - + // Step 4: Run gyro-driven control checkItermLimitingActive(&pidState[axis]); checkItermFreezingActive(&pidState[axis], axis); @@ -1165,7 +1166,7 @@ void FAST_CODE pidController(float dT) pidType_e pidIndexGetType(pidIndex_e pidIndex) { if (pidIndex == PID_ROLL || pidIndex == PID_PITCH || pidIndex == PID_YAW) { - return usedPidControllerType; + return usedPidControllerType; } if (STATE(AIRPLANE) || STATE(ROVER) || STATE(BOAT)) { if (pidIndex == PID_VEL_XY || pidIndex == PID_VEL_Z) { @@ -1201,7 +1202,7 @@ void pidInit(void) antigravityGain = pidProfile()->antigravityGain; antigravityAccelerator = pidProfile()->antigravityAccelerator; #endif - + for (uint8_t axis = FD_ROLL; axis <= FD_YAW; axis++) { if (axis == FD_YAW) { pidState[axis].pidSumLimit = pidProfile()->pidSumLimitYaw; @@ -1218,7 +1219,7 @@ void pidInit(void) if (pidProfile()->pidControllerType == PID_TYPE_AUTO) { if ( - mixerConfig()->platformType == PLATFORM_AIRPLANE || + mixerConfig()->platformType == PLATFORM_AIRPLANE || mixerConfig()->platformType == PLATFORM_BOAT || mixerConfig()->platformType == PLATFORM_ROVER ) { @@ -1276,10 +1277,10 @@ void pidInit(void) } -const pidBank_t * pidBank(void) { - return usedPidControllerType == PID_TYPE_PIFF ? &pidProfile()->bank_fw : &pidProfile()->bank_mc; +const pidBank_t * pidBank(void) { + return usedPidControllerType == PID_TYPE_PIFF ? &pidProfile()->bank_fw : &pidProfile()->bank_mc; } -pidBank_t * pidBankMutable(void) { +pidBank_t * pidBankMutable(void) { return usedPidControllerType == PID_TYPE_PIFF ? &pidProfileMutable()->bank_fw : &pidProfileMutable()->bank_mc; } @@ -1298,14 +1299,14 @@ void updateFixedWingLevelTrim(timeUs_t currentTimeUs) */ if (ARMING_FLAG(ARMED) && !previousArmingState) { navPidReset(&fixedWingLevelTrimController); - } + } /* * On disarm update the default value */ if (!ARMING_FLAG(ARMED) && previousArmingState) { pidProfileMutable()->fixedWingLevelTrim = constrainf(fixedWingLevelTrim, -FIXED_WING_LEVEL_TRIM_MAX_ANGLE, FIXED_WING_LEVEL_TRIM_MAX_ANGLE); - } + } /* * Prepare flags for the PID controller diff --git a/src/main/flight/power_limits.c b/src/main/flight/power_limits.c index ee5c0c3c77..549ead0019 100644 --- a/src/main/flight/power_limits.c +++ b/src/main/flight/power_limits.c @@ -45,22 +45,12 @@ FILE_COMPILE_FOR_SPEED #define LIMITING_THR_FILTER_TCONST 50 -PG_REGISTER_WITH_RESET_TEMPLATE(powerLimitsConfig_t, powerLimitsConfig, PG_POWER_LIMITS_CONFIG, 0); +PG_REGISTER_WITH_RESET_TEMPLATE(powerLimitsConfig_t, powerLimitsConfig, PG_POWER_LIMITS_CONFIG, 1); PG_RESET_TEMPLATE(powerLimitsConfig_t, powerLimitsConfig, - .continuousCurrent = SETTING_LIMIT_CONT_CURRENT_DEFAULT, // dA - .burstCurrent = SETTING_LIMIT_BURST_CURRENT_DEFAULT, // dA - .burstCurrentTime = SETTING_LIMIT_BURST_CURRENT_TIME_DEFAULT, // dS - .burstCurrentFalldownTime = SETTING_LIMIT_BURST_CURRENT_FALLDOWN_TIME_DEFAULT, // dS -#ifdef USE_ADC - .continuousPower = SETTING_LIMIT_CONT_POWER_DEFAULT, // dW - .burstPower = SETTING_LIMIT_BURST_POWER_DEFAULT, // dW - .burstPowerTime = SETTING_LIMIT_BURST_POWER_TIME_DEFAULT, // dS - .burstPowerFalldownTime = SETTING_LIMIT_BURST_POWER_FALLDOWN_TIME_DEFAULT, // dS -#endif .piP = SETTING_LIMIT_PI_P_DEFAULT, .piI = SETTING_LIMIT_PI_I_DEFAULT, - .attnFilterCutoff = SETTING_LIMIT_ATTN_FILTER_CUTOFF_DEFAULT, // Hz + .attnFilterCutoff = SETTING_LIMIT_ATTN_FILTER_CUTOFF_DEFAULT, // Hz ); static float burstCurrentReserve; // cA.µs @@ -84,29 +74,29 @@ static bool wasLimitingPower = false; #endif void powerLimiterInit(void) { - if (powerLimitsConfig()->burstCurrent < powerLimitsConfig()->continuousCurrent) { - powerLimitsConfigMutable()->burstCurrent = powerLimitsConfig()->continuousCurrent; + if (currentBatteryProfile->powerLimits.burstCurrent < currentBatteryProfile->powerLimits.continuousCurrent) { + currentBatteryProfileMutable->powerLimits.burstCurrent = currentBatteryProfile->powerLimits.continuousCurrent; } - activeCurrentLimit = powerLimitsConfig()->burstCurrent; + activeCurrentLimit = currentBatteryProfile->powerLimits.burstCurrent; - uint16_t currentBurstOverContinuous = powerLimitsConfig()->burstCurrent - powerLimitsConfig()->continuousCurrent; - burstCurrentReserve = burstCurrentReserveMax = currentBurstOverContinuous * powerLimitsConfig()->burstCurrentTime * 1e6; - burstCurrentReserveFalldown = currentBurstOverContinuous * powerLimitsConfig()->burstCurrentFalldownTime * 1e6; + uint16_t currentBurstOverContinuous = currentBatteryProfile->powerLimits.burstCurrent - currentBatteryProfile->powerLimits.continuousCurrent; + burstCurrentReserve = burstCurrentReserveMax = currentBurstOverContinuous * currentBatteryProfile->powerLimits.burstCurrentTime * 1e6; + burstCurrentReserveFalldown = currentBurstOverContinuous * currentBatteryProfile->powerLimits.burstCurrentFalldownTime * 1e6; pt1FilterInit(¤tThrAttnFilter, powerLimitsConfig()->attnFilterCutoff, 0); pt1FilterInitRC(¤tThrLimitingBaseFilter, LIMITING_THR_FILTER_TCONST, 0); #ifdef USE_ADC - if (powerLimitsConfig()->burstPower < powerLimitsConfig()->continuousPower) { - powerLimitsConfigMutable()->burstPower = powerLimitsConfig()->continuousPower; + if (currentBatteryProfile->powerLimits.burstPower < currentBatteryProfile->powerLimits.continuousPower) { + currentBatteryProfileMutable->powerLimits.burstPower = currentBatteryProfile->powerLimits.continuousPower; } - activePowerLimit = powerLimitsConfig()->burstPower; + activePowerLimit = currentBatteryProfile->powerLimits.burstPower; - uint16_t powerBurstOverContinuous = powerLimitsConfig()->burstPower - powerLimitsConfig()->continuousPower; - burstPowerReserve = burstPowerReserveMax = powerBurstOverContinuous * powerLimitsConfig()->burstPowerTime * 1e6; - burstPowerReserveFalldown = powerBurstOverContinuous * powerLimitsConfig()->burstPowerFalldownTime * 1e6; + uint16_t powerBurstOverContinuous = currentBatteryProfile->powerLimits.burstPower - currentBatteryProfile->powerLimits.continuousPower; + burstPowerReserve = burstPowerReserveMax = powerBurstOverContinuous * currentBatteryProfile->powerLimits.burstPowerTime * 1e6; + burstPowerReserveFalldown = powerBurstOverContinuous * currentBatteryProfile->powerLimits.burstPowerFalldownTime * 1e6; pt1FilterInit(&powerThrAttnFilter, powerLimitsConfig()->attnFilterCutoff, 0); pt1FilterInitRC(&powerThrLimitingBaseFilter, LIMITING_THR_FILTER_TCONST, 0); @@ -118,7 +108,7 @@ static uint32_t calculateActiveLimit(int32_t value, uint32_t continuousLimit, ui float spentReserveChunk = continuousDiff * timeDelta; *burstReserve = constrainf(*burstReserve - spentReserveChunk, 0, burstReserveMax); - if (powerLimitsConfig()->burstCurrentFalldownTime) { + if (currentBatteryProfile->powerLimits.burstCurrentFalldownTime) { return scaleRangef(MIN(*burstReserve, burstReserveFalldown), 0, burstReserveFalldown, continuousLimit, burstLimit) * 10; } @@ -127,7 +117,7 @@ static uint32_t calculateActiveLimit(int32_t value, uint32_t continuousLimit, ui void currentLimiterUpdate(timeDelta_t timeDelta) { activeCurrentLimit = calculateActiveLimit(getAmperage(), - powerLimitsConfig()->continuousCurrent, powerLimitsConfig()->burstCurrent, + currentBatteryProfile->powerLimits.continuousCurrent, currentBatteryProfile->powerLimits.burstCurrent, &burstCurrentReserve, burstCurrentReserveFalldown, burstCurrentReserveMax, timeDelta); } @@ -135,7 +125,7 @@ void currentLimiterUpdate(timeDelta_t timeDelta) { #ifdef USE_ADC void powerLimiterUpdate(timeDelta_t timeDelta) { activePowerLimit = calculateActiveLimit(getPower(), - powerLimitsConfig()->continuousPower, powerLimitsConfig()->burstPower, + currentBatteryProfile->powerLimits.continuousPower, currentBatteryProfile->powerLimits.burstPower, &burstPowerReserve, burstPowerReserveFalldown, burstPowerReserveMax, timeDelta); } @@ -254,18 +244,18 @@ bool powerLimiterIsLimitingPower(void) { // returns seconds float powerLimiterGetRemainingBurstTime(void) { - uint16_t currentBurstOverContinuous = powerLimitsConfig()->burstCurrent - powerLimitsConfig()->continuousCurrent; + uint16_t currentBurstOverContinuous = currentBatteryProfile->powerLimits.burstCurrent - currentBatteryProfile->powerLimits.continuousCurrent; float remainingCurrentBurstTime = burstCurrentReserve / currentBurstOverContinuous / 1e7; #ifdef USE_ADC - uint16_t powerBurstOverContinuous = powerLimitsConfig()->burstPower - powerLimitsConfig()->continuousPower; + uint16_t powerBurstOverContinuous = currentBatteryProfile->powerLimits.burstPower - currentBatteryProfile->powerLimits.continuousPower; float remainingPowerBurstTime = burstPowerReserve / powerBurstOverContinuous / 1e7; - if (!powerLimitsConfig()->continuousCurrent) { + if (!currentBatteryProfile->powerLimits.continuousCurrent) { return remainingPowerBurstTime; } - if (!powerLimitsConfig()->continuousPower) { + if (!currentBatteryProfile->powerLimits.continuousPower) { return remainingCurrentBurstTime; } diff --git a/src/main/flight/power_limits.h b/src/main/flight/power_limits.h index b82b938c58..2f4385252c 100644 --- a/src/main/flight/power_limits.h +++ b/src/main/flight/power_limits.h @@ -25,23 +25,13 @@ #include +#include "platform.h" + #include "config/parameter_group.h" #if defined(USE_POWER_LIMITS) typedef struct { - uint16_t continuousCurrent; // dA - uint16_t burstCurrent; // dA - uint16_t burstCurrentTime; // ds - uint16_t burstCurrentFalldownTime; // ds - -#ifdef USE_ADC - uint16_t continuousPower; // dW - uint16_t burstPower; // dW - uint16_t burstPowerTime; // ds - uint16_t burstPowerFalldownTime; // ds -#endif - uint16_t piP; uint16_t piI; diff --git a/src/main/flight/rth_estimator.c b/src/main/flight/rth_estimator.c index 7bae4fa731..747f326753 100644 --- a/src/main/flight/rth_estimator.c +++ b/src/main/flight/rth_estimator.c @@ -77,9 +77,9 @@ static int8_t RTHInitialAltitudeChangePitchAngle(float altitudeChange) { // pitch in degrees // output in Watt static float estimatePitchPower(float pitch) { - int16_t altitudeChangeThrottle = (int16_t)pitch * navConfig()->fw.pitch_to_throttle; - altitudeChangeThrottle = constrain(altitudeChangeThrottle, navConfig()->fw.min_throttle, navConfig()->fw.max_throttle); - const float altitudeChangeThrToCruiseThrRatio = (float)(altitudeChangeThrottle - getThrottleIdleValue()) / (navConfig()->fw.cruise_throttle - getThrottleIdleValue()); + int16_t altitudeChangeThrottle = (int16_t)pitch * currentBatteryProfile->nav.fw.pitch_to_throttle; + altitudeChangeThrottle = constrain(altitudeChangeThrottle, currentBatteryProfile->nav.fw.min_throttle, currentBatteryProfile->nav.fw.max_throttle); + const float altitudeChangeThrToCruiseThrRatio = (float)(altitudeChangeThrottle - getThrottleIdleValue()) / (currentBatteryProfile->nav.fw.cruise_throttle - getThrottleIdleValue()); return (float)heatLossesCompensatedPower(batteryMetersConfig()->idle_power + batteryMetersConfig()->cruise_power * altitudeChangeThrToCruiseThrRatio) / 100; } diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 855ff9e840..d161772f4a 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2238,15 +2238,15 @@ static bool osdDrawSingleElement(uint8_t item) return true; case OSD_NAV_FW_CRUISE_THR: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "CRZ", 0, navConfig()->fw.cruise_throttle, 4, 0, ADJUSTMENT_NAV_FW_CRUISE_THR); + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "CRZ", 0, currentBatteryProfile->nav.fw.cruise_throttle, 4, 0, ADJUSTMENT_NAV_FW_CRUISE_THR); return true; case OSD_NAV_FW_PITCH2THR: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "P2T", 0, navConfig()->fw.pitch_to_throttle, 3, 0, ADJUSTMENT_NAV_FW_PITCH2THR); + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "P2T", 0, currentBatteryProfile->nav.fw.pitch_to_throttle, 3, 0, ADJUSTMENT_NAV_FW_PITCH2THR); return true; case OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "0TP", 0, (float)mixerConfig()->fwMinThrottleDownPitchAngle / 10, 3, 1, ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE); + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "0TP", 0, (float)currentBatteryProfile->fwMinThrottleDownPitchAngle / 10, 3, 1, ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE); return true; case OSD_FW_ALT_PID_OUTPUTS: @@ -2774,7 +2774,7 @@ static bool osdDrawSingleElement(uint8_t item) break; case OSD_PLIMIT_ACTIVE_CURRENT_LIMIT: - if (powerLimitsConfig()->continuousCurrent) { + if (currentBatteryProfile->powerLimits.continuousCurrent) { osdFormatCentiNumber(buff, powerLimiterGetActiveCurrentLimit(), 0, 2, 0, 3); buff[3] = SYM_AMP; buff[4] = '\0'; @@ -2788,7 +2788,7 @@ static bool osdDrawSingleElement(uint8_t item) #ifdef USE_ADC case OSD_PLIMIT_ACTIVE_POWER_LIMIT: { - if (powerLimitsConfig()->continuousPower) { + if (currentBatteryProfile->powerLimits.continuousPower) { bool kiloWatt = osdFormatCentiNumber(buff, powerLimiterGetActivePowerLimit(), 1000, 2, 2, 3); buff[3] = kiloWatt ? SYM_KILOWATT : SYM_WATT; buff[4] = '\0'; diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index 7b42b72fc2..f6a0b9e4d0 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -867,10 +867,10 @@ static void osdDJIAdjustmentMessage(char *buff, uint8_t adjustmentFunction) tfp_sprintf(buff, "YFF %3d", pidBankMutable()->pid[PID_YAW].FF); break; case ADJUSTMENT_NAV_FW_CRUISE_THR: - tfp_sprintf(buff, "CR %4d", navConfigMutable()->fw.cruise_throttle); + tfp_sprintf(buff, "CR %4d", currentBatteryProfileMutable->nav.fw.cruise_throttle); break; case ADJUSTMENT_NAV_FW_PITCH2THR: - tfp_sprintf(buff, "P2T %3d", navConfigMutable()->fw.pitch_to_throttle); + tfp_sprintf(buff, "P2T %3d", currentBatteryProfileMutable->nav.fw.pitch_to_throttle); break; case ADJUSTMENT_ROLL_BOARD_ALIGNMENT: tfp_sprintf(buff, "RBA %3d", boardAlignment()->rollDeciDegrees); @@ -927,7 +927,7 @@ static void osdDJIAdjustmentMessage(char *buff, uint8_t adjustmentFunction) tfp_sprintf(buff, "VZD %3d", pidBankMutable()->pid[PID_VEL_Z].D); break; case ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE: - tfp_sprintf(buff, "MTDPA %4d", mixerConfigMutable()->fwMinThrottleDownPitchAngle); + tfp_sprintf(buff, "MTDPA %4d", currentBatteryProfileMutable->fwMinThrottleDownPitchAngle); break; case ADJUSTMENT_TPA: tfp_sprintf(buff, "TPA %3d", currentControlRateProfile->throttle.dynPID); diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 3e82864110..f18c94fa56 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -96,7 +96,7 @@ STATIC_ASSERT(NAV_MAX_WAYPOINTS < 254, NAV_MAX_WAYPOINTS_exceeded_allowable_rang PG_REGISTER_ARRAY(navWaypoint_t, NAV_MAX_WAYPOINTS, nonVolatileWaypointList, PG_WAYPOINT_MISSION_STORAGE, 0); #endif -PG_REGISTER_WITH_RESET_TEMPLATE(navConfig_t, navConfig, PG_NAV_CONFIG, 12); +PG_REGISTER_WITH_RESET_TEMPLATE(navConfig_t, navConfig, PG_NAV_CONFIG, 13); PG_RESET_TEMPLATE(navConfig_t, navConfig, .general = { @@ -142,7 +142,6 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, // MC-specific .mc = { .max_bank_angle = SETTING_NAV_MC_BANK_ANGLE_DEFAULT, // degrees - .hover_throttle = SETTING_NAV_MC_HOVER_THR_DEFAULT, .auto_disarm_delay = SETTING_NAV_MC_AUTO_DISARM_DELAY_DEFAULT, // milliseconds - time before disarming when auto disarm is enabled and landing is confirmed #ifdef USE_MR_BRAKING_MODE @@ -166,12 +165,8 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, .max_bank_angle = SETTING_NAV_FW_BANK_ANGLE_DEFAULT, // degrees .max_climb_angle = SETTING_NAV_FW_CLIMB_ANGLE_DEFAULT, // degrees .max_dive_angle = SETTING_NAV_FW_DIVE_ANGLE_DEFAULT, // degrees - .cruise_throttle = SETTING_NAV_FW_CRUISE_THR_DEFAULT, .cruise_speed = SETTING_NAV_FW_CRUISE_SPEED_DEFAULT, // cm/s .control_smoothness = SETTING_NAV_FW_CONTROL_SMOOTHNESS_DEFAULT, - .max_throttle = SETTING_NAV_FW_MAX_THR_DEFAULT, - .min_throttle = SETTING_NAV_FW_MIN_THR_DEFAULT, - .pitch_to_throttle = SETTING_NAV_FW_PITCH2THR_DEFAULT, // pwm units per degree of pitch (10pwm units ~ 1% throttle) .pitch_to_throttle_smooth = SETTING_NAV_FW_PITCH2THR_SMOOTHING_DEFAULT, .pitch_to_throttle_thresh = SETTING_NAV_FW_PITCH2THR_THRESHOLD_DEFAULT, .loiter_radius = SETTING_NAV_FW_LOITER_RADIUS_DEFAULT, // 75m @@ -183,8 +178,6 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, .launch_velocity_thresh = SETTING_NAV_FW_LAUNCH_VELOCITY_DEFAULT, // 3 m/s .launch_accel_thresh = SETTING_NAV_FW_LAUNCH_ACCEL_DEFAULT, // cm/s/s (1.9*G) .launch_time_thresh = SETTING_NAV_FW_LAUNCH_DETECT_TIME_DEFAULT, // 40ms - .launch_throttle = SETTING_NAV_FW_LAUNCH_THR_DEFAULT, - .launch_idle_throttle = SETTING_NAV_FW_LAUNCH_IDLE_THR_DEFAULT, // Motor idle or MOTOR_STOP .launch_motor_timer = SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_DEFAULT, // ms .launch_idle_motor_timer = SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_DEFAULT, // ms .launch_motor_spinup_time = SETTING_NAV_FW_LAUNCH_SPINUP_TIME_DEFAULT, // ms, time to gredually increase throttle from idle to launch diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index a29a4485ce..4965aafa05 100755 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -225,7 +225,6 @@ typedef struct navConfig_s { struct { uint8_t max_bank_angle; // multicopter max banking angle (deg) - uint16_t hover_throttle; // multicopter hover throttle uint16_t auto_disarm_delay; // multicopter safety delay for landing detector #ifdef USE_MR_BRAKING_MODE @@ -248,12 +247,8 @@ typedef struct navConfig_s { uint8_t max_bank_angle; // Fixed wing max banking angle (deg) uint8_t max_climb_angle; // Fixed wing max banking angle (deg) uint8_t max_dive_angle; // Fixed wing max banking angle (deg) - uint16_t cruise_throttle; // Cruise throttle uint16_t cruise_speed; // Speed at cruise throttle (cm/s), used for time/distance left before RTH uint8_t control_smoothness; // The amount of smoothing to apply to controls for navigation - uint16_t min_throttle; // Minimum allowed throttle in auto mode - uint16_t max_throttle; // Maximum allowed throttle in auto mode - uint8_t pitch_to_throttle; // Pitch angle (in deg) to throttle gain (in 1/1000's of throttle) (*10) uint16_t pitch_to_throttle_smooth; // How smoothly the autopilot makes pitch to throttle correction inside a deadband defined by pitch_to_throttle_thresh. uint8_t pitch_to_throttle_thresh; // Threshold from average pitch where momentary pitch_to_throttle correction kicks in. [decidegrees] uint16_t loiter_radius; // Loiter radius when executing PH on a fixed wing @@ -261,8 +256,6 @@ typedef struct navConfig_s { uint16_t launch_velocity_thresh; // Velocity threshold for swing launch detection uint16_t launch_accel_thresh; // Acceleration threshold for launch detection (cm/s/s) uint16_t launch_time_thresh; // Time threshold for launch detection (ms) - uint16_t launch_idle_throttle; // Throttle to keep at launch idle - uint16_t launch_throttle; // Launch throttle uint16_t launch_motor_timer; // Time to wait before setting launch_throttle (ms) uint16_t launch_idle_motor_timer; // Time to wait before motor starts at_idle throttle (ms) uint16_t launch_motor_spinup_time; // Time to speed-up motors from idle to launch_throttle (ESC desync prevention) diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index a20689fd91..3e2f48e34f 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -51,6 +51,8 @@ #include "rx/rx.h" +#include "sensors/battery.h" + // Base frequencies for smoothing pitch and roll #define NAV_FW_BASE_PITCH_CUTOFF_FREQUENCY_HZ 2.0f #define NAV_FW_BASE_ROLL_CUTOFF_FREQUENCY_HZ 10.0f @@ -483,18 +485,18 @@ int16_t fixedWingPitchToThrottleCorrection(int16_t pitch, timeUs_t currentTimeUs if (ABS(pitch - filteredPitch) > navConfig()->fw.pitch_to_throttle_thresh) { // Unfiltered throttle correction outside of pitch deadband - return DECIDEGREES_TO_DEGREES(pitch) * navConfig()->fw.pitch_to_throttle; + return DECIDEGREES_TO_DEGREES(pitch) * currentBatteryProfile->nav.fw.pitch_to_throttle; } else { // Filtered throttle correction inside of pitch deadband - return DECIDEGREES_TO_DEGREES(filteredPitch) * navConfig()->fw.pitch_to_throttle; + return DECIDEGREES_TO_DEGREES(filteredPitch) * currentBatteryProfile->nav.fw.pitch_to_throttle; } } void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStateFlags, timeUs_t currentTimeUs) { - int16_t minThrottleCorrection = navConfig()->fw.min_throttle - navConfig()->fw.cruise_throttle; - int16_t maxThrottleCorrection = navConfig()->fw.max_throttle - navConfig()->fw.cruise_throttle; + int16_t minThrottleCorrection = currentBatteryProfile->nav.fw.min_throttle - currentBatteryProfile->nav.fw.cruise_throttle; + int16_t maxThrottleCorrection = currentBatteryProfile->nav.fw.max_throttle - currentBatteryProfile->nav.fw.cruise_throttle; if (isRollAdjustmentValid && (navStateFlags & NAV_CTL_POS)) { // ROLL >0 right, <0 left @@ -529,15 +531,15 @@ void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStat throttleCorrection = constrain(throttleCorrection, minThrottleCorrection, maxThrottleCorrection); } - uint16_t correctedThrottleValue = constrain(navConfig()->fw.cruise_throttle + throttleCorrection, navConfig()->fw.min_throttle, navConfig()->fw.max_throttle); + uint16_t correctedThrottleValue = constrain(currentBatteryProfile->nav.fw.cruise_throttle + throttleCorrection, currentBatteryProfile->nav.fw.min_throttle, currentBatteryProfile->nav.fw.max_throttle); // Manual throttle increase if (navConfig()->fw.allow_manual_thr_increase && !FLIGHT_MODE(FAILSAFE_MODE)) { if (rcCommand[THROTTLE] < PWM_RANGE_MIN + (PWM_RANGE_MAX - PWM_RANGE_MIN) * 0.95) - correctedThrottleValue += MAX(0, rcCommand[THROTTLE] - navConfig()->fw.cruise_throttle); + correctedThrottleValue += MAX(0, rcCommand[THROTTLE] - currentBatteryProfile->nav.fw.cruise_throttle); else correctedThrottleValue = motorConfig()->maxthrottle; - isAutoThrottleManuallyIncreased = (rcCommand[THROTTLE] > navConfig()->fw.cruise_throttle); + isAutoThrottleManuallyIncreased = (rcCommand[THROTTLE] > currentBatteryProfile->nav.fw.cruise_throttle); } else { isAutoThrottleManuallyIncreased = false; } @@ -600,7 +602,7 @@ void applyFixedWingEmergencyLandingController(void) rcCommand[ROLL] = pidAngleToRcCommand(failsafeConfig()->failsafe_fw_roll_angle, pidProfile()->max_angle_inclination[FD_ROLL]); rcCommand[PITCH] = pidAngleToRcCommand(failsafeConfig()->failsafe_fw_pitch_angle, pidProfile()->max_angle_inclination[FD_PITCH]); rcCommand[YAW] = -pidRateToRcCommand(failsafeConfig()->failsafe_fw_yaw_rate, currentControlRateProfile->stabilized.rates[FD_YAW]); - rcCommand[THROTTLE] = failsafeConfig()->failsafe_throttle; + rcCommand[THROTTLE] = currentBatteryProfile->failsafe_throttle; } /*----------------------------------------------------------- diff --git a/src/main/navigation/navigation_fw_launch.c b/src/main/navigation/navigation_fw_launch.c index ea71f2a7b9..f4c8fc29d4 100755 --- a/src/main/navigation/navigation_fw_launch.c +++ b/src/main/navigation/navigation_fw_launch.c @@ -50,6 +50,8 @@ #include "io/gps.h" +#include "sensors/battery.h" + #define SWING_LAUNCH_MIN_ROTATION_RATE DEGREES_TO_RADIANS(100) // expect minimum 100dps rotation rate #define LAUNCH_MOTOR_IDLE_SPINUP_TIME 1500 // ms #define UNUSED(x) ((void)(x)) @@ -225,13 +227,13 @@ static void setCurrentState(fixedWingLaunchState_t nextState, timeUs_t currentTi static bool isThrottleIdleEnabled(void) { - return navConfig()->fw.launch_idle_throttle > getThrottleIdleValue(); + return currentBatteryProfile->nav.fw.launch_idle_throttle > getThrottleIdleValue(); } static void applyThrottleIdleLogic(bool forceMixerIdle) { if (isThrottleIdleEnabled() && !forceMixerIdle) { - rcCommand[THROTTLE] = navConfig()->fw.launch_idle_throttle; + rcCommand[THROTTLE] = currentBatteryProfile->nav.fw.launch_idle_throttle; } else { ENABLE_STATE(NAV_MOTOR_STOP_OR_IDLE); // If MOTOR_STOP is enabled mixer will keep motor stopped @@ -331,7 +333,7 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_MOTOR_IDLE(timeUs_t return FW_LAUNCH_EVENT_SUCCESS; } else { - rcCommand[THROTTLE] = scaleRangef(elapsedTimeMs, 0.0f, LAUNCH_MOTOR_IDLE_SPINUP_TIME, getThrottleIdleValue(), navConfig()->fw.launch_idle_throttle); + rcCommand[THROTTLE] = scaleRangef(elapsedTimeMs, 0.0f, LAUNCH_MOTOR_IDLE_SPINUP_TIME, getThrottleIdleValue(), currentBatteryProfile->nav.fw.launch_idle_throttle); fwLaunch.pitchAngle = scaleRangef(elapsedTimeMs, 0.0f, LAUNCH_MOTOR_IDLE_SPINUP_TIME, 0, navConfig()->fw.launch_climb_angle); } @@ -397,14 +399,14 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_MOTOR_SPINUP(timeUs_ const timeMs_t elapsedTimeMs = currentStateElapsedMs(currentTimeUs); const uint16_t motorSpinUpMs = navConfig()->fw.launch_motor_spinup_time; - const uint16_t launchThrottle = navConfig()->fw.launch_throttle; + const uint16_t launchThrottle = currentBatteryProfile->nav.fw.launch_throttle; if (elapsedTimeMs > motorSpinUpMs) { rcCommand[THROTTLE] = launchThrottle; return FW_LAUNCH_EVENT_SUCCESS; } else { - const uint16_t minIdleThrottle = MAX(getThrottleIdleValue(), navConfig()->fw.launch_idle_throttle); + const uint16_t minIdleThrottle = MAX(getThrottleIdleValue(), currentBatteryProfile->nav.fw.launch_idle_throttle); rcCommand[THROTTLE] = scaleRangef(elapsedTimeMs, 0.0f, motorSpinUpMs, minIdleThrottle, launchThrottle); } @@ -413,7 +415,7 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_MOTOR_SPINUP(timeUs_ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IN_PROGRESS(timeUs_t currentTimeUs) { - rcCommand[THROTTLE] = navConfig()->fw.launch_throttle; + rcCommand[THROTTLE] = currentBatteryProfile->nav.fw.launch_throttle; if (isLaunchMaxAltitudeReached()) { return FW_LAUNCH_EVENT_SUCCESS; // cancel the launch and do the FW_LAUNCH_STATE_FINISH state @@ -443,7 +445,7 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_FINISH(timeUs_t curr } else { // make a smooth transition from the launch state to the current state for throttle and the pitch angle - rcCommand[THROTTLE] = scaleRangef(elapsedTimeMs, 0.0f, endTimeMs, navConfig()->fw.launch_throttle, rcCommand[THROTTLE]); + rcCommand[THROTTLE] = scaleRangef(elapsedTimeMs, 0.0f, endTimeMs, currentBatteryProfile->nav.fw.launch_throttle, rcCommand[THROTTLE]); fwLaunch.pitchAngle = scaleRangef(elapsedTimeMs, 0.0f, endTimeMs, navConfig()->fw.launch_climb_angle, rcCommand[PITCH]); } diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c index a141af251f..b35146edfa 100755 --- a/src/main/navigation/navigation_multicopter.c +++ b/src/main/navigation/navigation_multicopter.c @@ -51,6 +51,8 @@ #include "navigation/navigation.h" #include "navigation/navigation_private.h" +#include "sensors/battery.h" + /*----------------------------------------------------------- * Altitude controller for multicopter aircraft *-----------------------------------------------------------*/ @@ -104,8 +106,8 @@ static void updateAltitudeVelocityController_MC(timeDelta_t deltaMicros) static void updateAltitudeThrottleController_MC(timeDelta_t deltaMicros) { // Calculate min and max throttle boundaries (to compensate for integral windup) - const int16_t thrAdjustmentMin = (int16_t)getThrottleIdleValue() - (int16_t)navConfig()->mc.hover_throttle; - const int16_t thrAdjustmentMax = (int16_t)motorConfig()->maxthrottle - (int16_t)navConfig()->mc.hover_throttle; + const int16_t thrAdjustmentMin = (int16_t)getThrottleIdleValue() - (int16_t)currentBatteryProfile->nav.mc.hover_throttle; + const int16_t thrAdjustmentMax = (int16_t)motorConfig()->maxthrottle - (int16_t)currentBatteryProfile->nav.mc.hover_throttle; posControl.rcAdjustment[THROTTLE] = navPidApply2(&posControl.pids.vel[Z], posControl.desiredState.vel.z, navGetCurrentActualPositionAndVelocity()->vel.z, US2S(deltaMicros), thrAdjustmentMin, thrAdjustmentMax, 0); @@ -239,7 +241,7 @@ static void applyMulticopterAltitudeController(timeUs_t currentTimeUs) } // Update throttle controller - rcCommand[THROTTLE] = constrain((int16_t)navConfig()->mc.hover_throttle + posControl.rcAdjustment[THROTTLE], getThrottleIdleValue(), motorConfig()->maxthrottle); + rcCommand[THROTTLE] = constrain((int16_t)currentBatteryProfile->nav.mc.hover_throttle + posControl.rcAdjustment[THROTTLE], getThrottleIdleValue(), motorConfig()->maxthrottle); // Save processed throttle for future use rcCommandAdjustedThrottle = rcCommand[THROTTLE]; @@ -443,11 +445,11 @@ static void updatePositionVelocityController_MC(const float maxSpeed) * We override computed speed with max speed in following cases: * 1 - computed velocity is > maxSpeed * 2 - in WP mission when: slowDownForTurning is OFF, we do not fly towards na last waypoint and computed speed is < maxSpeed - */ + */ if ( - (navGetCurrentStateFlags() & NAV_AUTO_WP && - !isApproachingLastWaypoint() && - newVelTotal < maxSpeed && + (navGetCurrentStateFlags() & NAV_AUTO_WP && + !isApproachingLastWaypoint() && + newVelTotal < maxSpeed && !navConfig()->mc.slowDownForTurning ) || newVelTotal > maxSpeed ) { @@ -753,7 +755,7 @@ static void applyMulticopterEmergencyLandingController(timeUs_t currentTimeUs) rcCommand[THROTTLE] = getThrottleIdleValue(); } else { - rcCommand[THROTTLE] = failsafeConfig()->failsafe_throttle; + rcCommand[THROTTLE] = currentBatteryProfile->failsafe_throttle; } return; @@ -780,7 +782,7 @@ static void applyMulticopterEmergencyLandingController(timeUs_t currentTimeUs) } // Update throttle controller - rcCommand[THROTTLE] = constrain((int16_t)navConfig()->mc.hover_throttle + posControl.rcAdjustment[THROTTLE], getThrottleIdleValue(), motorConfig()->maxthrottle); + rcCommand[THROTTLE] = constrain((int16_t)currentBatteryProfile->nav.mc.hover_throttle + posControl.rcAdjustment[THROTTLE], getThrottleIdleValue(), motorConfig()->maxthrottle); } /*----------------------------------------------------------- diff --git a/src/main/navigation/navigation_rover_boat.c b/src/main/navigation/navigation_rover_boat.c index 40c075107b..62cce388c8 100644 --- a/src/main/navigation/navigation_rover_boat.c +++ b/src/main/navigation/navigation_rover_boat.c @@ -29,13 +29,19 @@ FILE_COMPILE_FOR_SIZE #ifdef USE_NAV #include "build/debug.h" + #include "common/utils.h" + #include "fc/rc_controls.h" #include "fc/config.h" + #include "flight/mixer.h" + #include "navigation/navigation.h" #include "navigation/navigation_private.h" +#include "sensors/battery.h" + static bool isYawAdjustmentValid = false; static int32_t navHeadingError; @@ -125,7 +131,7 @@ void applyRoverBoatPitchRollThrottleController(navigationFSMStateFlags_t navStat rcCommand[YAW] = posControl.rcAdjustment[YAW]; } - rcCommand[THROTTLE] = constrain(navConfig()->fw.cruise_throttle, motorConfig()->mincommand, motorConfig()->maxthrottle); + rcCommand[THROTTLE] = constrain(currentBatteryProfile->nav.fw.cruise_throttle, motorConfig()->mincommand, motorConfig()->maxthrottle); } } } @@ -136,7 +142,7 @@ void applyRoverBoatNavigationController(navigationFSMStateFlags_t navStateFlags, rcCommand[ROLL] = 0; rcCommand[PITCH] = 0; rcCommand[YAW] = 0; - rcCommand[THROTTLE] = failsafeConfig()->failsafe_throttle; + rcCommand[THROTTLE] = currentBatteryProfile->failsafe_throttle; } else if (navStateFlags & NAV_CTL_POS) { applyRoverBoatPositionController(currentTimeUs); applyRoverBoatPitchRollThrottleController(navStateFlags, currentTimeUs); diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index ebac2987d4..8fdea16684 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -119,6 +119,51 @@ void pgResetFn_batteryProfiles(batteryProfile_t *instance) }, .controlRateProfile = 0, + + .motor = { + .throttleIdle = SETTING_THROTTLE_IDLE_DEFAULT, + .throttleScale = SETTING_THROTTLE_SCALE_DEFAULT, +#ifdef USE_DSHOT + .turtleModePowerFactor = SETTING_TURTLE_MODE_POWER_FACTOR_DEFAULT, +#endif + }, + + .failsafe_throttle = SETTING_FAILSAFE_THROTTLE_DEFAULT, // default throttle off. + + .fwMinThrottleDownPitchAngle = SETTING_FW_MIN_THROTTLE_DOWN_PITCH_DEFAULT, + + .nav = { + + .mc = { + .hover_throttle = SETTING_NAV_MC_HOVER_THR_DEFAULT, + }, + + .fw = { + .cruise_throttle = SETTING_NAV_FW_CRUISE_THR_DEFAULT, + .max_throttle = SETTING_NAV_FW_MAX_THR_DEFAULT, + .min_throttle = SETTING_NAV_FW_MIN_THR_DEFAULT, + .pitch_to_throttle = SETTING_NAV_FW_PITCH2THR_DEFAULT, // pwm units per degree of pitch (10pwm units ~ 1% throttle) + .launch_throttle = SETTING_NAV_FW_LAUNCH_THR_DEFAULT, + .launch_idle_throttle = SETTING_NAV_FW_LAUNCH_IDLE_THR_DEFAULT, // Motor idle or MOTOR_STOP + } + + }, + +#if defined(USE_POWER_LIMITS) + .powerLimits = { + .continuousCurrent = SETTING_LIMIT_CONT_CURRENT_DEFAULT, // dA + .burstCurrent = SETTING_LIMIT_BURST_CURRENT_DEFAULT, // dA + .burstCurrentTime = SETTING_LIMIT_BURST_CURRENT_TIME_DEFAULT, // dS + .burstCurrentFalldownTime = SETTING_LIMIT_BURST_CURRENT_FALLDOWN_TIME_DEFAULT, // dS +#ifdef USE_ADC + .continuousPower = SETTING_LIMIT_CONT_POWER_DEFAULT, // dW + .burstPower = SETTING_LIMIT_BURST_POWER_DEFAULT, // dW + .burstPowerTime = SETTING_LIMIT_BURST_POWER_TIME_DEFAULT, // dS + .burstPowerFalldownTime = SETTING_LIMIT_BURST_POWER_FALLDOWN_TIME_DEFAULT, // dS +#endif // USE_ADC + } +#endif // USE_POWER_LIMITS + ); } } diff --git a/src/main/sensors/battery.h b/src/main/sensors/battery.h index 04e25e993b..549515f13b 100644 --- a/src/main/sensors/battery.h +++ b/src/main/sensors/battery.h @@ -51,6 +51,8 @@ PG_DECLARE_ARRAY(batteryProfile_t, MAX_BATTERY_PROFILE_COUNT, batteryProfiles); extern const batteryProfile_t *currentBatteryProfile; +#define currentBatteryProfileMutable ((batteryProfile_t*)currentBatteryProfile) + typedef enum { BATTERY_OK = 0, BATTERY_WARNING, diff --git a/src/main/sensors/battery_config_structs.h b/src/main/sensors/battery_config_structs.h index 5b6d380385..6443b886a4 100644 --- a/src/main/sensors/battery_config_structs.h +++ b/src/main/sensors/battery_config_structs.h @@ -88,12 +88,57 @@ typedef struct batteryProfile_s { #endif struct { - uint32_t value; // mAh or mWh (see capacity.unit) - uint32_t warning; // mAh or mWh (see capacity.unit) - uint32_t critical; // mAh or mWh (see capacity.unit) - batCapacityUnit_e unit; // Describes unit of capacity.value, capacity.warning and capacity.critical + uint32_t value; // mAh or mWh (see capacity.unit) + uint32_t warning; // mAh or mWh (see capacity.unit) + uint32_t critical; // mAh or mWh (see capacity.unit) + batCapacityUnit_e unit; // Describes unit of capacity.value, capacity.warning and capacity.critical } capacity; uint8_t controlRateProfile; + struct { + float throttleIdle; // Throttle IDLE value based on min_command, max_throttle, in percent + float throttleScale; // Scaling factor for throttle. +#ifdef USE_DSHOT + uint8_t turtleModePowerFactor; // Power factor from 0 to 100% of flip over after crash +#endif + } motor; + + uint16_t failsafe_throttle; // Throttle level used for landing - specify value between 1000..2000 (pwm pulse width for slightly below hover). center throttle = 1500. + + uint16_t fwMinThrottleDownPitchAngle; + + struct { + + struct { + uint16_t hover_throttle; // multicopter hover throttle + } mc; + + struct { + uint16_t cruise_throttle; // Cruise throttle + uint16_t min_throttle; // Minimum allowed throttle in auto mode + uint16_t max_throttle; // Maximum allowed throttle in auto mode + uint8_t pitch_to_throttle; // Pitch angle (in deg) to throttle gain (in 1/1000's of throttle) (*10) + uint16_t launch_idle_throttle; // Throttle to keep at launch idle + uint16_t launch_throttle; // Launch throttle + } fw; + + } nav; + +#if defined(USE_POWER_LIMITS) + struct { + uint16_t continuousCurrent; // dA + uint16_t burstCurrent; // dA + uint16_t burstCurrentTime; // ds + uint16_t burstCurrentFalldownTime; // ds + +#ifdef USE_ADC + uint16_t continuousPower; // dW + uint16_t burstPower; // dW + uint16_t burstPowerTime; // ds + uint16_t burstPowerFalldownTime; // ds +#endif // USE_ADC + } powerLimits; +#endif // USE_POWER_LIMITS + } batteryProfile_t; diff --git a/src/main/target/FALCORE/config.c b/src/main/target/FALCORE/config.c index e7090f09b7..f109d0e100 100755 --- a/src/main/target/FALCORE/config.c +++ b/src/main/target/FALCORE/config.c @@ -89,7 +89,7 @@ void targetConfiguration(void) failsafeConfigMutable()->failsafe_delay = 5; failsafeConfigMutable()->failsafe_recovery_delay = 5; failsafeConfigMutable()->failsafe_off_delay = 200; - failsafeConfigMutable()->failsafe_throttle = 1200; + currentBatteryProfile->failsafe_throttle = 1200; failsafeConfigMutable()->failsafe_procedure = FAILSAFE_PROCEDURE_RTH; boardAlignmentMutable()->rollDeciDegrees = 0; @@ -120,7 +120,7 @@ void targetConfiguration(void) navConfigMutable()->general.rth_altitude = 1000; navConfigMutable()->mc.max_bank_angle = 30; - navConfigMutable()->mc.hover_throttle = 1500; + currentBatteryProfile->nav.mc.hover_throttle = 1500; navConfigMutable()->mc.auto_disarm_delay = 2000; /* From 2fe973edd888126e03e29685b2a26b53a2f8d884 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Wed, 16 Jun 2021 09:49:56 +0200 Subject: [PATCH 054/102] fix negative altitude formatting --- src/main/io/osd.c | 24 +++++++++++++++--------- 1 file changed, 15 insertions(+), 9 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 855ff9e840..215ee0da75 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -449,30 +449,36 @@ static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid) */ void osdFormatAltitudeSymbol(char *buff, int32_t alt) { - int digits = alt < 0 ? 4 : 3; + int digits; + if (alt < 0) { + digits = 4; + } else { + digits = 3; + buff[0] = ' '; + } switch ((osd_unit_e)osdConfig()->units) { case OSD_UNIT_UK: FALLTHROUGH; case OSD_UNIT_IMPERIAL: - if (osdFormatCentiNumber(buff , CENTIMETERS_TO_CENTIFEET(alt), 1000, 0, 2, digits)) { + if (osdFormatCentiNumber(buff + 4 - digits, CENTIMETERS_TO_CENTIFEET(alt), 1000, 0, 2, digits)) { // Scaled to kft - buff[digits] = SYM_ALT_KFT; + buff[4] = SYM_ALT_KFT; } else { // Formatted in feet - buff[digits] = SYM_ALT_FT; + buff[4] = SYM_ALT_FT; } - buff[digits + 1] = '\0'; + buff[5] = '\0'; break; case OSD_UNIT_METRIC: // alt is alredy in cm - if (osdFormatCentiNumber(buff, alt, 1000, 0, 2, digits)) { + if (osdFormatCentiNumber(buff + 4 - digits, alt, 1000, 0, 2, digits)) { // Scaled to km - buff[digits] = SYM_ALT_KM; + buff[4] = SYM_ALT_KM; } else { // Formatted in m - buff[digits] = SYM_ALT_M; + buff[4] = SYM_ALT_M; } - buff[digits + 1] = '\0'; + buff[5] = '\0'; break; } } From 7096a9128b2157be12eb48497fb99be658e8d9f1 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 17 Jun 2021 09:58:50 +0200 Subject: [PATCH 055/102] Drop sharpness and configurable window size for Kalman filter --- src/main/fc/settings.yaml | 14 -------------- src/main/flight/kalman.c | 24 +++++++----------------- src/main/flight/kalman.h | 5 ++--- src/main/flight/pid.c | 6 ++---- src/main/flight/pid.h | 2 -- 5 files changed, 11 insertions(+), 40 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 10c9b9430f..1b6cdec7a2 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2181,20 +2181,6 @@ groups: condition: USE_GYRO_KALMAN min: 1 max: 16000 - - name: setpoint_kalman_w - description: "Window size for the setpoint Kalman filter. Wider the window, more samples are used to compute variance. In general, wider window results in smoother filter response" - default_value: 4 - field: kalman_w - condition: USE_GYRO_KALMAN - min: 1 - max: 40 - - name: setpoint_kalman_sharpness - description: "Dynamic factor for the setpoint Kalman filter. In general, the higher the value, the more dynamic Kalman filter gets" - default_value: 100 - field: kalman_sharpness - condition: USE_GYRO_KALMAN - min: 1 - max: 16000 - name: fw_level_pitch_trim description: "Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level" default_value: 0 diff --git a/src/main/flight/kalman.c b/src/main/flight/kalman.c index 7049f66991..ff572666e9 100755 --- a/src/main/flight/kalman.c +++ b/src/main/flight/kalman.c @@ -30,45 +30,35 @@ FILE_COMPILE_FOR_SPEED kalman_t kalmanFilterStateRate[XYZ_AXIS_COUNT]; -static void gyroKalmanInitAxis(kalman_t *filter, uint16_t q, uint16_t w, uint16_t sharpness) +static void gyroKalmanInitAxis(kalman_t *filter, uint16_t q) { memset(filter, 0, sizeof(kalman_t)); filter->q = q * 0.03f; //add multiplier to make tuning easier filter->r = 88.0f; //seeding R at 88.0f filter->p = 30.0f; //seeding P at 30.0f filter->e = 1.0f; - filter->s = sharpness / 10.0f; - filter->w = w * 8; + filter->w = MAX_KALMAN_WINDOW_SIZE; filter->inverseN = 1.0f / (float)(filter->w); } -void gyroKalmanInitialize(uint16_t q, uint16_t w, uint16_t sharpness) +void gyroKalmanInitialize(uint16_t q) { - gyroKalmanInitAxis(&kalmanFilterStateRate[X], q, w, sharpness); - gyroKalmanInitAxis(&kalmanFilterStateRate[Y], q, w, sharpness); - gyroKalmanInitAxis(&kalmanFilterStateRate[Z], q, w, sharpness); + gyroKalmanInitAxis(&kalmanFilterStateRate[X], q); + gyroKalmanInitAxis(&kalmanFilterStateRate[Y], q); + gyroKalmanInitAxis(&kalmanFilterStateRate[Z], q); } float kalman_process(kalman_t *kalmanState, float input, float target) { - float targetAbs = fabsf(target); //project the state ahead using acceleration kalmanState->x += (kalmanState->x - kalmanState->lastX); - //figure out how much to boost or reduce our error in the estimate based on setpoint target. - //this should be close to 0 as we approach the sepoint and really high the futher away we are from the setpoint. //update last state kalmanState->lastX = kalmanState->x; if (kalmanState->lastX != 0.0f) { - // calculate the error and add multiply sharpness boost - float errorMultiplier = fabsf(target - kalmanState->x) * kalmanState->s; - - // give a boost to the setpoint, used to caluclate the kalman q, based on the error and setpoint/gyrodata - errorMultiplier = constrainf(errorMultiplier * fabsf(1.0f - (target / kalmanState->lastX)) + 1.0f, 1.0f, 50.0f); - - kalmanState->e = fabsf(1.0f - (((targetAbs + 1.0f) * errorMultiplier) / fabsf(kalmanState->lastX))); + kalmanState->e = fabsf(1.0f - (target / kalmanState->lastX)); } //prediction update diff --git a/src/main/flight/kalman.h b/src/main/flight/kalman.h index 295caef96f..665371b44b 100755 --- a/src/main/flight/kalman.h +++ b/src/main/flight/kalman.h @@ -23,7 +23,7 @@ #include "sensors/gyro.h" #include "common/filter.h" -#define MAX_KALMAN_WINDOW_SIZE 512 +#define MAX_KALMAN_WINDOW_SIZE 64 #define VARIANCE_SCALE 0.67f @@ -36,7 +36,6 @@ typedef struct kalman float x; //state float lastX; //previous state float e; - float s; float axisVar; uint16_t windex; @@ -49,5 +48,5 @@ typedef struct kalman uint16_t w; } kalman_t; -void gyroKalmanInitialize(uint16_t q, uint16_t w, uint16_t sharpness); +void gyroKalmanInitialize(uint16_t q); float gyroKalmanUpdate(uint8_t axis, float input, float setpoint); diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 1368c93fad..e967461653 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -170,7 +170,7 @@ static EXTENDED_FASTRAM bool levelingEnabled = false; static EXTENDED_FASTRAM float fixedWingLevelTrim; static EXTENDED_FASTRAM pidController_t fixedWingLevelTrimController; -PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 2); +PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 3); PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .bank_mc = { @@ -302,8 +302,6 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, #ifdef USE_GYRO_KALMAN .kalman_q = SETTING_SETPOINT_KALMAN_Q_DEFAULT, - .kalman_w = SETTING_SETPOINT_KALMAN_W_DEFAULT, - .kalman_sharpness = SETTING_SETPOINT_KALMAN_SHARPNESS_DEFAULT, .kalmanEnabled = SETTING_SETPOINT_KALMAN_ENABLED_DEFAULT, #endif @@ -1260,7 +1258,7 @@ void pidInit(void) pidResetTPAFilter(); #ifdef USE_GYRO_KALMAN if (pidProfile()->kalmanEnabled) { - gyroKalmanInitialize(pidProfile()->kalman_q, pidProfile()->kalman_w, pidProfile()->kalman_sharpness); + gyroKalmanInitialize(pidProfile()->kalman_q); } #endif diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 37486a4cac..bd2649053c 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -158,8 +158,6 @@ typedef struct pidProfile_s { #ifdef USE_GYRO_KALMAN uint16_t kalman_q; - uint16_t kalman_w; - uint16_t kalman_sharpness; uint8_t kalmanEnabled; #endif From fda781d05ac3f4844c515c29ac7a158f32e43ddb Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 17 Jun 2021 14:30:56 +0200 Subject: [PATCH 056/102] Move Kalman back to gyro processing --- src/main/fc/settings.yaml | 26 +++++++++++++------------- src/main/flight/kalman.c | 12 ++++++++---- src/main/flight/kalman.h | 5 ++++- src/main/flight/pid.c | 16 ++-------------- src/main/flight/pid.h | 5 ----- src/main/sensors/gyro.c | 19 ++++++++++++++++++- src/main/sensors/gyro.h | 4 ++++ 7 files changed, 49 insertions(+), 38 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 1b6cdec7a2..22e8946f3a 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -328,6 +328,19 @@ groups: condition: USE_ALPHA_BETA_GAMMA_FILTER min: 0 max: 10 + - name: setpoint_kalman_enabled + description: "Enable Kalman filter on the gyro data" + default_value: OFF + condition: USE_GYRO_KALMAN + field: kalmanEnabled + type: bool + - name: setpoint_kalman_q + description: "Quality factor of the setpoint Kalman filter. Higher values means less filtering and lower phase delay. On 3-7 inch multirotors can be usually increased to 200-300 or even higher of clean builds" + default_value: 100 + field: kalman_q + condition: USE_GYRO_KALMAN + min: 1 + max: 16000 - name: PG_ADC_CHANNEL_CONFIG type: adcChannelConfig_t @@ -2168,19 +2181,6 @@ groups: field: controlDerivativeLpfHz min: 0 max: 200 - - name: setpoint_kalman_enabled - description: "Enable Kalman filter on the PID controller setpoint" - default_value: OFF - condition: USE_GYRO_KALMAN - field: kalmanEnabled - type: bool - - name: setpoint_kalman_q - description: "Quality factor of the setpoint Kalman filter. Higher values means less filtering and lower phase delay. On 3-7 inch multirotors can be usually increased to 200-300 or even higher of clean builds" - default_value: 100 - field: kalman_q - condition: USE_GYRO_KALMAN - min: 1 - max: 16000 - name: fw_level_pitch_trim description: "Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level" default_value: 0 diff --git a/src/main/flight/kalman.c b/src/main/flight/kalman.c index ff572666e9..7ac431cb26 100755 --- a/src/main/flight/kalman.c +++ b/src/main/flight/kalman.c @@ -48,7 +48,7 @@ void gyroKalmanInitialize(uint16_t q) gyroKalmanInitAxis(&kalmanFilterStateRate[Z], q); } -float kalman_process(kalman_t *kalmanState, float input, float target) +float kalman_process(kalman_t *kalmanState, float input) { //project the state ahead using acceleration kalmanState->x += (kalmanState->x - kalmanState->lastX); @@ -58,7 +58,7 @@ float kalman_process(kalman_t *kalmanState, float input, float target) if (kalmanState->lastX != 0.0f) { - kalmanState->e = fabsf(1.0f - (target / kalmanState->lastX)); + kalmanState->e = fabsf(1.0f - (kalmanState->setpoint / kalmanState->lastX)); } //prediction update @@ -98,13 +98,17 @@ static void updateAxisVariance(kalman_t *kalmanState, float rate) kalmanState->r = squirt * VARIANCE_SCALE; } -float gyroKalmanUpdate(uint8_t axis, float input, float setpoint) +float NOINLINE gyroKalmanUpdate(uint8_t axis, float input) { updateAxisVariance(&kalmanFilterStateRate[axis], input); DEBUG_SET(DEBUG_KALMAN_GAIN, axis, kalmanFilterStateRate[axis].k * 1000.0f); //Kalman gain - return kalman_process(&kalmanFilterStateRate[axis], input, setpoint); + return kalman_process(&kalmanFilterStateRate[axis], input); +} + +void gyroKalmanUpdateSetpoint(uint8_t axis, float setpoint) { + kalmanFilterStateRate[axis].setpoint = setpoint; } #endif \ No newline at end of file diff --git a/src/main/flight/kalman.h b/src/main/flight/kalman.h index 665371b44b..620473be5e 100755 --- a/src/main/flight/kalman.h +++ b/src/main/flight/kalman.h @@ -37,6 +37,8 @@ typedef struct kalman float lastX; //previous state float e; + float setpoint; + float axisVar; uint16_t windex; float axisWindow[MAX_KALMAN_WINDOW_SIZE + 1]; @@ -49,4 +51,5 @@ typedef struct kalman } kalman_t; void gyroKalmanInitialize(uint16_t q); -float gyroKalmanUpdate(uint8_t axis, float input, float setpoint); +float gyroKalmanUpdate(uint8_t axis, float input); +void gyroKalmanUpdateSetpoint(uint8_t axis, float setpoint); \ No newline at end of file diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index e967461653..d54f5ff443 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -170,7 +170,7 @@ static EXTENDED_FASTRAM bool levelingEnabled = false; static EXTENDED_FASTRAM float fixedWingLevelTrim; static EXTENDED_FASTRAM pidController_t fixedWingLevelTrimController; -PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 3); +PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 4); PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .bank_mc = { @@ -300,11 +300,6 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .navFwPosHdgPidsumLimit = SETTING_NAV_FW_POS_HDG_PIDSUM_LIMIT_DEFAULT, .controlDerivativeLpfHz = SETTING_MC_CD_LPF_HZ_DEFAULT, -#ifdef USE_GYRO_KALMAN - .kalman_q = SETTING_SETPOINT_KALMAN_Q_DEFAULT, - .kalmanEnabled = SETTING_SETPOINT_KALMAN_ENABLED_DEFAULT, -#endif - .fixedWingLevelTrim = SETTING_FW_LEVEL_PITCH_TRIM_DEFAULT, .fixedWingLevelTrimGain = SETTING_FW_LEVEL_PITCH_GAIN_DEFAULT, @@ -1110,9 +1105,7 @@ void FAST_CODE pidController(float dT) pidState[axis].rateTarget = constrainf(rateTarget, -GYRO_SATURATION_LIMIT, +GYRO_SATURATION_LIMIT); #ifdef USE_GYRO_KALMAN - if (pidProfile()->kalmanEnabled) { - pidState[axis].gyroRate = gyroKalmanUpdate(axis, pidState[axis].gyroRate, pidState[axis].rateTarget); - } + gyroKalmanUpdateSetpoint(axis, pidState[axis].rateTarget); #endif #ifdef USE_SMITH_PREDICTOR @@ -1256,11 +1249,6 @@ void pidInit(void) } pidResetTPAFilter(); -#ifdef USE_GYRO_KALMAN - if (pidProfile()->kalmanEnabled) { - gyroKalmanInitialize(pidProfile()->kalman_q); - } -#endif fixedWingLevelTrim = pidProfile()->fixedWingLevelTrim; diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index bd2649053c..7e1ab17a76 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -156,11 +156,6 @@ typedef struct pidProfile_s { uint16_t navFwPosHdgPidsumLimit; uint8_t controlDerivativeLpfHz; -#ifdef USE_GYRO_KALMAN - uint16_t kalman_q; - uint8_t kalmanEnabled; -#endif - float fixedWingLevelTrim; float fixedWingLevelTrimGain; #ifdef USE_SMITH_PREDICTOR diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index f7d1a3ad18..f70bdbcdf0 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -75,6 +75,7 @@ FILE_COMPILE_FOR_SPEED #include "flight/gyroanalyse.h" #include "flight/rpm_filter.h" #include "flight/dynamic_gyro_notch.h" +#include "flight/kalman.h" #ifdef USE_HARDWARE_REVISION_DETECTION #include "hardware_revision.h" @@ -111,7 +112,7 @@ STATIC_FASTRAM alphaBetaGammaFilter_t abgFilter[XYZ_AXIS_COUNT]; #endif -PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 14); +PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 15); PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .gyro_lpf = SETTING_GYRO_HARDWARE_LPF_DEFAULT, @@ -142,6 +143,10 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .alphaBetaGammaBoost = SETTING_GYRO_ABG_BOOST_DEFAULT, .alphaBetaGammaHalfLife = SETTING_GYRO_ABG_HALF_LIFE_DEFAULT, #endif +#ifdef USE_GYRO_KALMAN + .kalman_q = SETTING_SETPOINT_KALMAN_Q_DEFAULT, + .kalmanEnabled = SETTING_SETPOINT_KALMAN_ENABLED_DEFAULT, +#endif ); STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev, gyroSensor_e gyroHardware) @@ -318,6 +323,11 @@ static void gyroInitFilters(void) } } #endif +#ifdef USE_GYRO_KALMAN + if (gyroConfig()->kalmanEnabled) { + gyroKalmanInitialize(gyroConfig()->kalman_q); + } +#endif } bool gyroInit(void) @@ -501,6 +511,12 @@ void FAST_CODE NOINLINE gyroFilter() } #endif +#ifdef USE_GYRO_KALMAN + if (gyroConfig()->kalmanEnabled) { + gyroADCf = gyroKalmanUpdate(axis, gyroADCf); + } +#endif + gyro.gyroADCf[axis] = gyroADCf; } @@ -517,6 +533,7 @@ void FAST_CODE NOINLINE gyroFilter() } } #endif + } void FAST_CODE NOINLINE gyroUpdate() diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index f00d828f32..eed2aceb60 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -87,6 +87,10 @@ typedef struct gyroConfig_s { float alphaBetaGammaBoost; float alphaBetaGammaHalfLife; #endif +#ifdef USE_GYRO_KALMAN + uint16_t kalman_q; + uint8_t kalmanEnabled; +#endif } gyroConfig_t; PG_DECLARE(gyroConfig_t, gyroConfig); From b80c90b80aacf8840574412e9051b0e876a2bd5f Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 17 Jun 2021 14:31:31 +0200 Subject: [PATCH 057/102] Docs update --- docs/Settings.md | 22 +--------------------- 1 file changed, 1 insertion(+), 21 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 577247afa4..d8cf7304aa 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -5114,7 +5114,7 @@ Output frequency (in Hz) servo pins. When using tricopters or gimbal with digita ### setpoint_kalman_enabled -Enable Kalman filter on the PID controller setpoint +Enable Kalman filter on the gyro data | Default | Min | Max | | --- | --- | --- | @@ -5132,26 +5132,6 @@ Quality factor of the setpoint Kalman filter. Higher values means less filtering --- -### setpoint_kalman_sharpness - -Dynamic factor for the setpoint Kalman filter. In general, the higher the value, the more dynamic Kalman filter gets - -| Default | Min | Max | -| --- | --- | --- | -| 100 | 1 | 16000 | - ---- - -### setpoint_kalman_w - -Window size for the setpoint Kalman filter. Wider the window, more samples are used to compute variance. In general, wider window results in smoother filter response - -| Default | Min | Max | -| --- | --- | --- | -| 4 | 1 | 40 | - ---- - ### sim_ground_station_number Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module. From c0a0729fa1bfa0d40e90e7d46e2669b945446876 Mon Sep 17 00:00:00 2001 From: scavanger Date: Fri, 18 Jun 2021 12:39:43 +0200 Subject: [PATCH 058/102] Bugfixes --- src/main/io/osd_dji_hd.c | 16 +++++++--------- 1 file changed, 7 insertions(+), 9 deletions(-) diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index f6a0b9e4d0..bc3c7b720b 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -986,7 +986,7 @@ static bool djiFormatMessages(char *buff) } } else { #ifdef USE_SERIALRX_CRSF - if (rxLinkStatistics.rfMode == 0) { + if (djiOsdConfig()->rssi_source == DJI_CRSF_LQ && rxLinkStatistics.rfMode == 0) { messages[messageCount++] = "CRSF LOW RF"; } #endif @@ -1156,19 +1156,17 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms case DJI_MSP_NAME: { - const char * name = systemConfig()->name; - #if defined(USE_OSD) if (djiOsdConfig()->use_name_for_messages) { djiSerializeCraftNameOverride(dst); - } - else + } else { #endif - { - int len = strlen(name); - sbufWriteData(dst, name, MAX(len, 12)); - break; + sbufWriteData(dst, systemConfig()->name, MAX((int)strlen(systemConfig()->name), OSD_MESSAGE_LENGTH)); +#if defined(USE_OSD) } +#endif + + break; } break; From 9573bfe47bdae57f1a0ce88e39c1886d023834c5 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sat, 19 Jun 2021 17:39:28 +0100 Subject: [PATCH 059/102] Update Building in Windows 10 with Linux Subsystem.md Added instructions for compiling generated documents --- ...uilding in Windows 10 with Linux Subsystem.md | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/docs/development/Building in Windows 10 with Linux Subsystem.md b/docs/development/Building in Windows 10 with Linux Subsystem.md index 2b8439c543..6357584bac 100644 --- a/docs/development/Building in Windows 10 with Linux Subsystem.md +++ b/docs/development/Building in Windows 10 with Linux Subsystem.md @@ -20,13 +20,13 @@ Install Ubuntu: NOTE: from this point all commands are entered into the Ubunto shell command window Update the repo packages: -1. `sudo apt update` +- `sudo apt update` Install Git, Make, gcc and Ruby -1. `sudo apt-get install git` -1. `sudo apt-get install make` -1. `sudo apt-get install cmake` -1. `sudo apt-get install ruby` +- `sudo apt-get install git make cmake ruby` + +Install python and python-yaml to allow updates to settings.md +- `sudo apt-get install python python-yaml` ### CMAKE and Ubuntu 18_04 @@ -78,6 +78,12 @@ cd build make MATEKF722 ``` +## Updating the documents +``` +cd /mnt/c/inav +python src/utils/update_cli_docs.py +``` + ## Flashing: Launch windows configurator GUI and from within the firmware flasher select `Load firmware[Local]` Hex files can be found in the folder `c:\inav\build` From 28b4f2dcff0104bd029b2db70b724bfb28a1cb34 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sat, 19 Jun 2021 17:53:03 +0100 Subject: [PATCH 060/102] Update Building in Windows 10 with Linux Subsystem.md Corrected python version --- .../Building in Windows 10 with Linux Subsystem.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/development/Building in Windows 10 with Linux Subsystem.md b/docs/development/Building in Windows 10 with Linux Subsystem.md index 6357584bac..b03797d8c4 100644 --- a/docs/development/Building in Windows 10 with Linux Subsystem.md +++ b/docs/development/Building in Windows 10 with Linux Subsystem.md @@ -26,7 +26,7 @@ Install Git, Make, gcc and Ruby - `sudo apt-get install git make cmake ruby` Install python and python-yaml to allow updates to settings.md -- `sudo apt-get install python python-yaml` +- `sudo apt-get install python3 python-yaml` ### CMAKE and Ubuntu 18_04 @@ -81,7 +81,7 @@ make MATEKF722 ## Updating the documents ``` cd /mnt/c/inav -python src/utils/update_cli_docs.py +python3 src/utils/update_cli_docs.py ``` ## Flashing: From f2d60802453487cf76d16c4d057286594dc4c615 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sat, 19 Jun 2021 18:04:30 +0100 Subject: [PATCH 061/102] Update IDE - Visual Studio Code with Windows 10.md Updated tasks to include compiling the autogenerated docs, like settings.md, and an example to build multiple targets. --- ...DE - Visual Studio Code with Windows 10.md | 57 +++++++++++-------- 1 file changed, 32 insertions(+), 25 deletions(-) diff --git a/docs/development/IDE - Visual Studio Code with Windows 10.md b/docs/development/IDE - Visual Studio Code with Windows 10.md index 6095fec4e3..66c3928d50 100644 --- a/docs/development/IDE - Visual Studio Code with Windows 10.md +++ b/docs/development/IDE - Visual Studio Code with Windows 10.md @@ -79,30 +79,6 @@ Edit `./.vscode/tasks.json` to enable Building with `Ctrl + Shift + B` keyboard // for the documentation about the tasks.json format "version": "2.0.0", "tasks": [ - { - "label": "Build Matek F722-SE", - "type": "shell", - "command": "make MATEKF722SE", - "group": "build", - "problemMatcher": [], - "options": { - "cwd": "${workspaceFolder}/build" - } - }, - { - "label": "Build Matek F722", - "type": "shell", - "command": "make MATEKF722", - "group": { - "kind": "build", - "isDefault": true - }, - "problemMatcher": [], - "options": { - "cwd": "${workspaceFolder}/build" - } - } - , { "label": "Install/Update CMAKE", "type": "shell", @@ -112,7 +88,38 @@ Edit `./.vscode/tasks.json` to enable Building with `Ctrl + Shift + B` keyboard "options": { "cwd": "${workspaceFolder}" } - } + }, + { + "label": "Compile autogenerated docs", + "type": "shell", + "command": "python3 src/utils/update_cli_docs.py", + "problemMatcher": [], + "options": { + "cwd": "${workspaceFolder}" + } + }, + // Example of building a single target + { + "label": "Build Matek F722-WPX", + "type": "shell", + "command": "make MATEKF722WPX", + "group": "build", + "problemMatcher": [], + "options": { + "cwd": "${workspaceFolder}/build" + } + }, + // Example of building multiple targets + { + "label": "Build Matek F405-STD & WING", + "type": "shell", + "command": "make MATEKF405 MATEKF405SE", + "group": "build", + "problemMatcher": [], + "options": { + "cwd": "${workspaceFolder}/build" + } + }, ] } ``` From def94bf4dce2dfe2d6cf268d4b2750234d5271dd Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sat, 19 Jun 2021 23:25:48 +0100 Subject: [PATCH 062/102] Update IDE - Visual Studio Code with Windows 10.md --- docs/development/IDE - Visual Studio Code with Windows 10.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/development/IDE - Visual Studio Code with Windows 10.md b/docs/development/IDE - Visual Studio Code with Windows 10.md index 66c3928d50..ee83ce74af 100644 --- a/docs/development/IDE - Visual Studio Code with Windows 10.md +++ b/docs/development/IDE - Visual Studio Code with Windows 10.md @@ -119,7 +119,7 @@ Edit `./.vscode/tasks.json` to enable Building with `Ctrl + Shift + B` keyboard "options": { "cwd": "${workspaceFolder}/build" } - }, + } ] } ``` From 5e63c47d66764c2c024d1302a43e8e2bcea2f1a0 Mon Sep 17 00:00:00 2001 From: JuliooCesarMDM Date: Sat, 19 Jun 2021 19:38:29 -0300 Subject: [PATCH 063/102] Uint8_t To Bool --- src/main/io/beeper.c | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index cd7893f5e6..89b55564af 100644 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -157,8 +157,8 @@ static uint8_t beep_multiBeeps[MAX_MULTI_BEEPS + 2]; #define BEEPER_CONFIRMATION_BEEP_GAP_DURATION 20 -// Beeper off = 0 Beeper on = 1 -static uint8_t beeperIsOn = 0; +// Beeper off = false Beeper on = true +static bool beeperIsOn = 0; // Place in current sequence static uint16_t beeperPos = 0; @@ -259,7 +259,7 @@ void beeperSilence(void) warningLedRefresh(); - beeperIsOn = 0; + beeperIsOn = false; beeperNextToggleTime = 0; beeperPos = 0; @@ -352,7 +352,7 @@ void beeperUpdate(timeUs_t currentTimeUs) } #endif - beeperIsOn = 1; + beeperIsOn = true; if (currentBeeperEntry->sequence[beeperPos] != 0) { if (!(getBeeperOffMask() & (1 << (currentBeeperEntry->mode - 1)))) BEEP_ON; @@ -368,7 +368,7 @@ void beeperUpdate(timeUs_t currentTimeUs) } } } else { - beeperIsOn = 0; + beeperIsOn = false; if (currentBeeperEntry->sequence[beeperPos] != 0) { BEEP_OFF; warningLedDisable(); From 58a49f0064923f205275a92a5c839d92830142e4 Mon Sep 17 00:00:00 2001 From: JuliooCesarMDM Date: Sat, 19 Jun 2021 21:03:29 -0300 Subject: [PATCH 064/102] fix initial value --- src/main/io/beeper.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index 89b55564af..57cba56a61 100644 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -158,7 +158,7 @@ static uint8_t beep_multiBeeps[MAX_MULTI_BEEPS + 2]; // Beeper off = false Beeper on = true -static bool beeperIsOn = 0; +static bool beeperIsOn = false; // Place in current sequence static uint16_t beeperPos = 0; From 675f317f1dbd35b53deb808b7785237de36527ab Mon Sep 17 00:00:00 2001 From: JuliooCesarMDM Date: Sat, 19 Jun 2021 23:53:19 -0300 Subject: [PATCH 065/102] [Telemetry/ghst.c]Fix Coding Style --- src/main/telemetry/ghst.c | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/main/telemetry/ghst.c b/src/main/telemetry/ghst.c index c2aca3ac51..85f6f85b96 100644 --- a/src/main/telemetry/ghst.c +++ b/src/main/telemetry/ghst.c @@ -147,10 +147,12 @@ void ghstFrameGpsSecondaryTelemetry(sbuf_t *dst) sbufWriteU16(dst, GPS_directionToHome); uint8_t gpsFlags = 0; - if(STATE(GPS_FIX)) + if (STATE(GPS_FIX)) { gpsFlags |= GPS_FLAGS_FIX; - if(STATE(GPS_FIX_HOME)) + } + if (STATE(GPS_FIX_HOME)) { gpsFlags |= GPS_FLAGS_FIX_HOME; + } sbufWriteU8(dst, gpsFlags); } From efd3f459786bf8f9c06aa5e4e944ac4a92d8d9e3 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 20 Jun 2021 12:14:48 +0200 Subject: [PATCH 066/102] Update readme --- README.md | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/README.md b/README.md index f34db4d136..cf8eecc7e9 100644 --- a/README.md +++ b/README.md @@ -1,11 +1,6 @@ # INAV - navigation capable flight controller -## F3 based flight controllers - -> STM32 F3 flight controllers like Omnibus F3 or SP Racing F3 are deprecated and soon they will reach the end of support in INAV. If you are still using F3 boards, please migrate to F4 or F7. - ![INAV](http://static.rcgroups.net/forums/attachments/6/1/0/3/7/6/a9088858-102-inav.png) -![Travis CI status](https://travis-ci.org/iNavFlight/inav.svg?branch=master) ## Features @@ -16,9 +11,9 @@ * Fully configurable mixer that allows to run any hardware you want: multirotor, fixed wing, rovers, boats and other experimental devices * Multiple sensor support: GPS, Pitot tube, sonar, lidar, temperature, ESC with BlHeli_32 telemetry * SmartAudio and IRC Tramp VTX support -* DSHOT and Multishot ESCs * Blackbox flight recorder logging * On Screen Display (OSD) - both character and pixel style +* DJI OSD integration: all elements, system messages and warnings * Telemetry: SmartPort, FPort, MAVlink, LTM * Multi-color RGB LED Strip support * Advanced gyro filtering: Matrix Filter and RPM filter From 066f36576b6fc9dbee9ba437a625e24c10fc0b8a Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 20 Jun 2021 12:39:03 +0200 Subject: [PATCH 067/102] Always apply MR ControlDerivative --- src/main/flight/pid.c | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index d54f5ff443..10df32db96 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -820,14 +820,8 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid /* * Compute Control Derivative - * CD is enabled only when ANGLE and HORIZON modes are not enabled! */ - float newCDTerm; - if (levelingEnabled) { - newCDTerm = 0.0F; - } else { - newCDTerm = rateTargetDeltaFiltered * (pidState->kCD / dT); - } + const float newCDTerm = rateTargetDeltaFiltered * (pidState->kCD / dT); DEBUG_SET(DEBUG_CD, axis, newCDTerm); // TODO: Get feedback from mixer on available correction range for each axis From 92bc8364cec394fd87905de8d6a7b3c880709038 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 21 Jun 2021 15:11:15 +0200 Subject: [PATCH 068/102] PT2 and PT3 LPFs --- src/main/common/filter.c | 66 ++++++++++++++++++++++++++++++++++++++++ src/main/common/filter.h | 27 ++++++++++++++++ 2 files changed, 93 insertions(+) diff --git a/src/main/common/filter.c b/src/main/common/filter.c index 0656a5dba7..afa986e8df 100644 --- a/src/main/common/filter.c +++ b/src/main/common/filter.c @@ -109,6 +109,72 @@ void pt1FilterReset(pt1Filter_t *filter, float input) filter->state = input; } +/* + * PT2 LowPassFilter + */ +float pt2FilterGain(float f_cut, float dT) +{ + const float order = 2.0f; + const float orderCutoffCorrection = 1 / sqrtf(powf(2, 1.0f / order) - 1); + float RC = 1 / (2 * orderCutoffCorrection * M_PIf * f_cut); + // float RC = 1 / (2 * 1.553773974f * M_PIf * f_cut); + // where 1.553773974 = 1 / sqrt( (2^(1 / order) - 1) ) and order is 2 + return dT / (RC + dT); +} + +void pt2FilterInit(pt2Filter_t *filter, float k) +{ + filter->state = 0.0f; + filter->state1 = 0.0f; + filter->k = k; +} + +void pt2FilterUpdateCutoff(pt2Filter_t *filter, float k) +{ + filter->k = k; +} + +FAST_CODE float pt2FilterApply(pt2Filter_t *filter, float input) +{ + filter->state1 = filter->state1 + filter->k * (input - filter->state1); + filter->state = filter->state + filter->k * (filter->state1 - filter->state); + return filter->state; +} + +/* + * PT3 LowPassFilter + */ +float pt3FilterGain(float f_cut, float dT) +{ + const float order = 3.0f; + const float orderCutoffCorrection = 1 / sqrtf(powf(2, 1.0f / order) - 1); + float RC = 1 / (2 * orderCutoffCorrection * M_PIf * f_cut); + // float RC = 1 / (2 * 1.961459177f * M_PIf * f_cut); + // where 1.961459177 = 1 / sqrt( (2^(1 / order) - 1) ) and order is 3 + return dT / (RC + dT); +} + +void pt3FilterInit(pt3Filter_t *filter, float k) +{ + filter->state = 0.0f; + filter->state1 = 0.0f; + filter->state2 = 0.0f; + filter->k = k; +} + +void pt3FilterUpdateCutoff(pt3Filter_t *filter, float k) +{ + filter->k = k; +} + +FAST_CODE float pt3FilterApply(pt3Filter_t *filter, float input) +{ + filter->state1 = filter->state1 + filter->k * (input - filter->state1); + filter->state2 = filter->state2 + filter->k * (filter->state1 - filter->state2); + filter->state = filter->state + filter->k * (filter->state2 - filter->state); + return filter->state; +} + // rate_limit = maximum rate of change of the output value in units per second void rateLimitFilterInit(rateLimitFilter_t *filter) { diff --git a/src/main/common/filter.h b/src/main/common/filter.h index a6406ee91c..7e6a579efe 100644 --- a/src/main/common/filter.h +++ b/src/main/common/filter.h @@ -27,6 +27,17 @@ typedef struct pt1Filter_s { float dT; float alpha; } pt1Filter_t; +typedef struct pt2Filter_s { + float state; + float state1; + float k; +} pt2Filter_t; +typedef struct pt3Filter_s { + float state; + float state1; + float state2; + float k; +} pt3Filter_t; /* this holds the data required to update samples thru a filter */ typedef struct biquadFilter_s { @@ -87,6 +98,22 @@ float pt1FilterApply3(pt1Filter_t *filter, float input, float dT); float pt1FilterApply4(pt1Filter_t *filter, float input, float f_cut, float dt); void pt1FilterReset(pt1Filter_t *filter, float input); +/* + * PT2 LowPassFilter + */ +float pt2FilterGain(float f_cut, float dT); +void pt2FilterInit(pt2Filter_t *filter, float k); +void pt2FilterUpdateCutoff(pt2Filter_t *filter, float k); +float pt2FilterApply(pt2Filter_t *filter, float input); + +/* + * PT3 LowPassFilter + */ +float pt3FilterGain(float f_cut, float dT); +void pt3FilterInit(pt3Filter_t *filter, float k); +void pt3FilterUpdateCutoff(pt3Filter_t *filter, float k); +float pt3FilterApply(pt3Filter_t *filter, float input); + void rateLimitFilterInit(rateLimitFilter_t *filter); float rateLimitFilterApply4(rateLimitFilter_t *filter, float input, float rate_limit, float dT); From a8ec3b209ffa0c3bff6ddfe4ccc219638598e444 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Mon, 21 Jun 2021 16:30:36 +0200 Subject: [PATCH 069/102] only consider roll/pitch for allow bypass arming --- src/main/fc/fc_core.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index d9b83c9ad0..775e2b33dc 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -223,7 +223,7 @@ static void updateArmingStatus(void) /* CHECK: pitch / roll sticks centered when NAV_LAUNCH_MODE enabled */ if (isNavLaunchEnabled()) { - if (areSticksDeflected()) { + if (isRollPitchStickDeflected()) { ENABLE_ARMING_FLAG(ARMING_DISABLED_ROLLPITCH_NOT_CENTERED); } else { DISABLE_ARMING_FLAG(ARMING_DISABLED_ROLLPITCH_NOT_CENTERED); From 0be545566ec83415aff37de0cff95ae04dd2c9b4 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Wed, 23 Jun 2021 20:14:27 +0200 Subject: [PATCH 070/102] display UK efficiency in metric --- src/main/io/osd.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index ecb0011c8f..357a8acd7b 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2410,8 +2410,6 @@ static bool osdDrawSingleElement(uint8_t item) } bool efficiencyValid = (value > 0) && (gpsSol.groundSpeed > 100); switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; case OSD_UNIT_IMPERIAL: moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10, 1000, 0, 2, 3); if (!moreThanAh) { @@ -2426,6 +2424,8 @@ static bool osdDrawSingleElement(uint8_t item) buff[5] = '\0'; } break; + case OSD_UNIT_UK: + FALLTHROUGH; case OSD_UNIT_METRIC: moreThanAh = osdFormatCentiNumber(buff, value * 100, 1000, 0, 2, 3); if (!moreThanAh) { @@ -2465,12 +2465,12 @@ static bool osdDrawSingleElement(uint8_t item) } bool efficiencyValid = (value > 0) && (gpsSol.groundSpeed > 100); switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; case OSD_UNIT_IMPERIAL: osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10000, 0, 2, 0, 3); buff[3] = SYM_WH_MI; break; + case OSD_UNIT_UK: + FALLTHROUGH; case OSD_UNIT_METRIC: osdFormatCentiNumber(buff, value / 10, 0, 2, 0, 3); buff[3] = SYM_WH_KM; From 7f27c5c9fce5c84928f62b33ccd84f52810891bc Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Wed, 23 Jun 2021 20:58:29 +0200 Subject: [PATCH 071/102] correct comment --- src/main/drivers/osd_symbols.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/osd_symbols.h b/src/main/drivers/osd_symbols.h index 750ac0d8ec..5fa0872d30 100644 --- a/src/main/drivers/osd_symbols.h +++ b/src/main/drivers/osd_symbols.h @@ -34,7 +34,7 @@ #define SYM_AH_KM 0x08 // 008 Ah/km #define SYM_AH_MI 0x09 // 009 Ah/mi #define SYM_MAH_MI_0 0x0A // 010 mAh/mi left -#define SYM_MAH_MI_1 0x0B // 010 mAh/mi left +#define SYM_MAH_MI_1 0x0B // 011 mAh/mi right #define SYM_LQ 0x0C // 012 LQ #define SYM_TEMP_F 0x0D // 013 °F From 26c99813eb020edf9612337332e612285b6ee63c Mon Sep 17 00:00:00 2001 From: Nikita Shestakov <42568603+nekida@users.noreply.github.com> Date: Thu, 24 Jun 2021 14:56:48 +0300 Subject: [PATCH 072/102] Minor update Reduce Scope of Variable throttleForRPM Ternary operator instead of if-else --- src/main/telemetry/frsky_d.c | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/src/main/telemetry/frsky_d.c b/src/main/telemetry/frsky_d.c index b551f6b9d1..0bc65d3457 100644 --- a/src/main/telemetry/frsky_d.c +++ b/src/main/telemetry/frsky_d.c @@ -193,10 +193,10 @@ static void sendGpsAltitude(void) static void sendThrottleOrBatterySizeAsRpm(void) { - uint16_t throttleForRPM = rcCommand[THROTTLE] / BLADE_NUMBER_DIVIDER; sendDataHead(ID_RPM); if (ARMING_FLAG(ARMED)) { const throttleStatus_e throttleStatus = calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC); + uint16_t throttleForRPM = rcCommand[THROTTLE] / BLADE_NUMBER_DIVIDER; if (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP)) throttleForRPM = 0; serialize16(throttleForRPM); @@ -265,11 +265,7 @@ static void GPStoDDDMM_MMMM(int32_t mwiigps, gpsCoordinateDDDMMmmmm_t *result) absgps = (absgps - deg * GPS_DEGREES_DIVIDER) * 60; // absgps = Minutes left * 10^7 min = absgps / GPS_DEGREES_DIVIDER; // minutes left - if (telemetryConfig()->frsky_coordinate_format == FRSKY_FORMAT_DMS) { - result->dddmm = deg * 100 + min; - } else { - result->dddmm = deg * 60 + min; - } + result->dddmm = deg * ((FRSKY_FORMAT_DMS == telemetryConfig()->frsky_coordinate_format) ? (100) : (60)) + min; result->mmmm = (absgps - min * GPS_DEGREES_DIVIDER) / 1000; } From c664212ab530467222f6f3574c55509f5249a205 Mon Sep 17 00:00:00 2001 From: JuliooCesarMDM Date: Fri, 25 Jun 2021 00:39:33 -0300 Subject: [PATCH 073/102] Rename Development Docs --- ...em.md => Building in Windows 10 or 11 with Linux Subsystem.md} | 0 ...0 with MSYS2.md => Building in Windows 10 or 11 with MSYS2.md} | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename docs/development/{Building in Windows 10 with Linux Subsystem.md => Building in Windows 10 or 11 with Linux Subsystem.md} (100%) rename docs/development/{Building in Windows 10 with MSYS2.md => Building in Windows 10 or 11 with MSYS2.md} (100%) diff --git a/docs/development/Building in Windows 10 with Linux Subsystem.md b/docs/development/Building in Windows 10 or 11 with Linux Subsystem.md similarity index 100% rename from docs/development/Building in Windows 10 with Linux Subsystem.md rename to docs/development/Building in Windows 10 or 11 with Linux Subsystem.md diff --git a/docs/development/Building in Windows 10 with MSYS2.md b/docs/development/Building in Windows 10 or 11 with MSYS2.md similarity index 100% rename from docs/development/Building in Windows 10 with MSYS2.md rename to docs/development/Building in Windows 10 or 11 with MSYS2.md From f8dc04aad67512c6b3125fac494fa29a108f7f2d Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Fri, 25 Jun 2021 09:16:15 +0200 Subject: [PATCH 074/102] change target defelction to 80% --- src/main/fc/settings.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 22e8946f3a..f442d2d32e 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2220,7 +2220,7 @@ groups: condition: USE_AUTOTUNE_FIXED_WING members: - name: fw_autotune_min_stick - description: "Minimum stick input [%] to consider overshoot/undershoot detection" + description: "Minimum stick input [%], after applying deadband and expo, to consider overshoot/undershoot detection" default_value: 50 field: fw_min_stick min: 0 @@ -2251,7 +2251,7 @@ groups: type: uint8_t - name: fw_autotune_max_rate_deflection description: "The target percentage of maximum mixer output used for determining the rates in `AUTO` and `LIMIT`." - default_value: 90 + default_value: 80 field: fw_max_rate_deflection min: 50 max: 100 From 4e5a2f3950922731b629a2eb15063d89d9ddcb63 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Fri, 25 Jun 2021 09:23:17 +0200 Subject: [PATCH 075/102] change setting description --- src/main/fc/settings.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index f442d2d32e..a81207a1af 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2220,7 +2220,7 @@ groups: condition: USE_AUTOTUNE_FIXED_WING members: - name: fw_autotune_min_stick - description: "Minimum stick input [%], after applying deadband and expo, to consider overshoot/undershoot detection" + description: "Minimum stick input [%], after applying deadband and expo, to start recording the plane's response to stick input." default_value: 50 field: fw_min_stick min: 0 From ed0de5dfc708a3cac48a2e76066acee441f390f5 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Fri, 25 Jun 2021 09:32:46 +0200 Subject: [PATCH 076/102] docs --- docs/Settings.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index d8cf7304aa..cebd4b72cb 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -1158,13 +1158,13 @@ The target percentage of maximum mixer output used for determining the rates in | Default | Min | Max | | --- | --- | --- | -| 90 | 50 | 100 | +| 80 | 50 | 100 | --- ### fw_autotune_min_stick -Minimum stick input [%] to consider overshoot/undershoot detection +Minimum stick input [%], after applying deadband and expo, to start recording the plane's response to stick input. | Default | Min | Max | | --- | --- | --- | From d0627d94e16770de79d5af1427595c6a0953c816 Mon Sep 17 00:00:00 2001 From: mateksys Date: Sat, 26 Jun 2021 00:59:40 +0800 Subject: [PATCH 077/102] MatekH743: fix some definitions --- src/main/target/MATEKH743/config.c | 30 ++++++ src/main/target/MATEKH743/target.h | 142 ++++++++++++++++------------- 2 files changed, 110 insertions(+), 62 deletions(-) create mode 100644 src/main/target/MATEKH743/config.c diff --git a/src/main/target/MATEKH743/config.c b/src/main/target/MATEKH743/config.c new file mode 100644 index 0000000000..7e47e5bf6b --- /dev/null +++ b/src/main/target/MATEKH743/config.c @@ -0,0 +1,30 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" + +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; +} diff --git a/src/main/target/MATEKH743/target.h b/src/main/target/MATEKH743/target.h index cf49efb232..b26f879b41 100644 --- a/src/main/target/MATEKH743/target.h +++ b/src/main/target/MATEKH743/target.h @@ -21,48 +21,15 @@ #define TARGET_BOARD_IDENTIFIER "H743" #define USBD_PRODUCT_STRING "MATEKH743" +#define USE_TARGET_CONFIG + #define LED0 PE3 #define LED1 PE4 #define BEEPER PA15 #define BEEPER_INVERTED - -// *************** UART ***************************** -#define USE_VCP - -#define USE_UART1 -#define UART1_TX_PIN PA9 -#define UART1_RX_PIN PA10 - -#define USE_UART2 -#define UART2_TX_PIN PD5 -#define UART2_RX_PIN PD6 - -#define USE_UART3 -#define UART3_TX_PIN PD8 -#define UART3_RX_PIN PD9 - -#define USE_UART4 -#define UART4_TX_PIN PD1 -#define UART4_RX_PIN PD0 - -#define USE_UART6 -#define UART6_TX_PIN PC6 -#define UART6_RX_PIN PC7 - -#define USE_UART7 -#define UART7_TX_PIN PE8 -#define UART7_RX_PIN PE7 - -#define USE_UART8 -#define UART8_TX_PIN PE1 -#define UART8_RX_PIN PE0 - -#define SERIAL_PORT_COUNT 8 - -#define DEFAULT_RX_TYPE RX_TYPE_SERIAL -#define SERIALRX_PROVIDER SERIALRX_SBUS -#define SERIALRX_UART SERIAL_PORT_USART6 +#define BEEPER_PWM +#define BEEPER_PWM_FREQUENCY 2500 // *************** IMU generic *********************** #define USE_DUAL_GYRO @@ -79,12 +46,24 @@ #define SPI1_MOSI_PIN PD7 #define USE_IMU_MPU6000 -#define USE_IMU_MPU6500 -#define IMU1_ALIGN CW90_DEG_FLIP +#define IMU1_ALIGN CW0_DEG_FLIP #define IMU1_SPI_BUS BUS_SPI1 #define IMU1_CS_PIN PC15 -#define IMU1_EXTI_PIN NONE +#define IMU1_EXTI_PIN PB2 + +// *************** SPI4 IMU2 ************************* +#define USE_SPI_DEVICE_4 +#define SPI4_SCK_PIN PE12 +#define SPI4_MISO_PIN PE13 +#define SPI4_MOSI_PIN PE14 + +#define USE_IMU_MPU6500 + +#define IMU2_ALIGN CW0_DEG_FLIP +#define IMU2_SPI_BUS BUS_SPI4 +#define IMU2_CS_PIN PE11 +#define IMU2_EXTI_PIN PE15 // *************** SPI2 OSD *********************** #define USE_SPI_DEVICE_2 @@ -96,25 +75,16 @@ #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB12 -// *************** SPI3 SD BLACKBOX******************* -/* -#define USE_SDCARD -#define USE_SDCARD_SDIO -#define SDCARD_SDIO_DMA DMA_TAG(2,3,4) -#define SDCARD_SDIO_4BIT -#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -*/ +// *************** SPI3 SPARE for external RM3100 *********** +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 -// *************** SPI4 IMU2 ************************* -#define USE_SPI_DEVICE_4 -#define SPI4_SCK_PIN PE12 -#define SPI4_MISO_PIN PE13 -#define SPI4_MOSI_PIN PE14 - -#define IMU2_ALIGN CW270_DEG_FLIP -#define IMU2_SPI_BUS BUS_SPI4 -#define IMU2_CS_PIN PE11 -#define IMU2_EXTI_PIN NONE +#define USE_MAG_RM3100 +#define RM3100_CS_PIN PE2 //CS2 pad +// PD4 //CS1 pad +#define RM3100_SPI_BUS BUS_SPI3 // *************** I2C /Baro/Mag ********************* #define USE_I2C @@ -146,7 +116,55 @@ #define PITOT_I2C_BUS BUS_I2C2 #define USE_RANGEFINDER -#define RANGEFINDER_I2C_BUS BUS_I2C2 +#define RANGEFINDER_I2C_BUS BUS_I2C1 + +// *************** UART ***************************** +#define USE_VCP + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PD5 +#define UART2_RX_PIN PD6 + +#define USE_UART3 +#define UART3_TX_PIN PD8 +#define UART3_RX_PIN PD9 + +#define USE_UART4 +#define UART4_TX_PIN PB9 +#define UART4_RX_PIN PB8 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define USE_UART7 +#define UART7_TX_PIN PE8 +#define UART7_RX_PIN PE7 + +#define USE_UART8 +#define UART8_TX_PIN PE1 +#define UART8_RX_PIN PE0 + +#define USE_SOFTSERIAL1 +#define SOFTSERIAL_1_TX_PIN PC6 //TX6 pad +#define SOFTSERIAL_1_RX_PIN PC6 //TX6 pad + +#define SERIAL_PORT_COUNT 9 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART6 + +// *************** SDIO SD BLACKBOX******************* +//#define USE_SDCARD +//#define USE_SDCARD_SDIO +//#define SDCARD_SDIO_DMA DMA_TAG(2,3,4) +//#define SDCARD_SDIO_4BIT +//#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT // *************** ADC ***************************** #define USE_ADC @@ -167,8 +185,8 @@ // *************** PINIO *************************** #define USE_PINIO #define USE_PINIOBOX -#define PINIO1_PIN PE4 // VTX power switcher -#define PINIO2_PIN PE15 // 2xCamera switcher +#define PINIO1_PIN PD10 // VTX power switcher +#define PINIO2_PIN PD11 // 2xCamera switcher // *************** LEDSTRIP ************************ #define USE_LED_STRIP @@ -186,7 +204,7 @@ #define TARGET_IO_PORTE 0xffff #define MAX_PWM_OUTPUT_PORTS 15 -#define USE_DSHOT +#define USE_DSHOTc #define USE_ESC_SENSOR #define USE_SERIALSHOT From 4fb7b46720cb77a5354b48b9ce334666821b05bc Mon Sep 17 00:00:00 2001 From: mateksys Date: Sat, 26 Jun 2021 01:02:30 +0800 Subject: [PATCH 078/102] MatekH743: fix some definitions --- src/main/target/MATEKH743/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/MATEKH743/target.h b/src/main/target/MATEKH743/target.h index b26f879b41..a0864cd140 100644 --- a/src/main/target/MATEKH743/target.h +++ b/src/main/target/MATEKH743/target.h @@ -204,7 +204,7 @@ #define TARGET_IO_PORTE 0xffff #define MAX_PWM_OUTPUT_PORTS 15 -#define USE_DSHOTc +#define USE_DSHOT #define USE_ESC_SENSOR #define USE_SERIALSHOT From 715b0007e7c8a2c497e679b4336c7b9b2926ece6 Mon Sep 17 00:00:00 2001 From: JuliooCesarMDM Date: Fri, 25 Jun 2021 22:09:19 -0300 Subject: [PATCH 079/102] FW Nav Fix Coding Style --- src/main/navigation/navigation_fixedwing.c | 21 +++++++++++++++------ 1 file changed, 15 insertions(+), 6 deletions(-) diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index c8300fbf87..6b970c0d54 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -238,8 +238,14 @@ static int8_t loiterDirection(void) { int8_t dir = 1; //NAV_LOITER_RIGHT if (pidProfile()->loiter_direction == NAV_LOITER_LEFT) dir = -1; if (pidProfile()->loiter_direction == NAV_LOITER_YAW) { - if (rcCommand[YAW] < -250) loiterDirYaw = 1; //RIGHT //yaw is contrariwise - if (rcCommand[YAW] > 250) loiterDirYaw = -1; //LEFT //see annexCode in fc_core.c + if (rcCommand[YAW] < -250) { + loiterDirYaw = 1; //RIGHT //yaw is contrariwise + } + + if (rcCommand[YAW] > 250) { + loiterDirYaw = -1; //LEFT //see annexCode in fc_core.c + } + dir = loiterDirYaw; } if (IS_RC_MODE_ACTIVE(BOXLOITERDIRCHN)) dir *= -1; @@ -535,10 +541,11 @@ void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStat // Manual throttle increase if (navConfig()->fw.allow_manual_thr_increase && !FLIGHT_MODE(FAILSAFE_MODE)) { - if (rcCommand[THROTTLE] < PWM_RANGE_MIN + (PWM_RANGE_MAX - PWM_RANGE_MIN) * 0.95) + if (rcCommand[THROTTLE] < PWM_RANGE_MIN + (PWM_RANGE_MAX - PWM_RANGE_MIN) * 0.95){ correctedThrottleValue += MAX(0, rcCommand[THROTTLE] - currentBatteryProfile->nav.fw.cruise_throttle); - else + } else { correctedThrottleValue = motorConfig()->maxthrottle; + } isAutoThrottleManuallyIncreased = (rcCommand[THROTTLE] > currentBatteryProfile->nav.fw.cruise_throttle); } else { isAutoThrottleManuallyIncreased = false; @@ -651,12 +658,14 @@ void applyFixedWingNavigationController(navigationFSMStateFlags_t navStateFlags, posControl.rcAdjustment[ROLL] = 0; } - if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && posControl.flags.isAdjustingPosition) + if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && posControl.flags.isAdjustingPosition){ rcCommand[ROLL] = applyDeadbandRescaled(rcCommand[ROLL], rcControlsConfig()->pos_hold_deadband, -500, 500); + } //if (navStateFlags & NAV_CTL_YAW) - if ((navStateFlags & NAV_CTL_ALT) || (navStateFlags & NAV_CTL_POS)) + if ((navStateFlags & NAV_CTL_ALT) || (navStateFlags & NAV_CTL_POS)){ applyFixedWingPitchRollThrottleController(navStateFlags, currentTimeUs); + } } } From 5834f896ce526d6af843d75d05767fcb4edc042f Mon Sep 17 00:00:00 2001 From: mateksys Date: Sat, 26 Jun 2021 17:48:53 +0800 Subject: [PATCH 080/102] MatekH743: fix some definitions --- src/main/target/MATEKH743/target.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/target/MATEKH743/target.c b/src/main/target/MATEKH743/target.c index 94b2ff7b75..a56fd96106 100644 --- a/src/main/target/MATEKH743/target.c +++ b/src/main/target/MATEKH743/target.c @@ -40,8 +40,8 @@ const timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH1, PD12, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 7), // S7 DEF_TIM(TIM4, CH2, PD13, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 8), // S8 - DEF_TIM(TIM4, CH3, PD14, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S9 - DEF_TIM(TIM4, CH4, PD15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S10 DMA_NONE + DEF_TIM(TIM4, CH3, PD14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S9 + DEF_TIM(TIM4, CH4, PD15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S10 DMA_NONE DEF_TIM(TIM15, CH1, PE5, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S11 DEF_TIM(TIM15, CH2, PE6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S12 DMA_NONE From 688bff68295906fb4e838e1f5876ef8df578cef0 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sat, 26 Jun 2021 13:12:42 +0100 Subject: [PATCH 081/102] Updated UK units to be correct for the UK The units used as "UK" were incorrect. We use imperial for distance and speed. To correct this, I have added a new units set called Metric + MPH. Metric + MPH is the old UK units set. Anyone who used the old UK setting would use Metric + MPH going forward. As in, if you had UK before, did the update, you would now be on Metric + MPH. The transition is seamless to the pilot. This is due to adding it before UK in the osd_unit_e enum. UK is effectively the new units set. It uses imperial for everything, except the temperature which is in degrees C. --- src/main/fc/settings.yaml | 2 +- src/main/io/osd.c | 132 +++++++++++++++++++++++++------------- src/main/io/osd.h | 3 +- src/main/io/osd_canvas.c | 20 ++++-- src/main/io/osd_dji_hd.c | 10 ++- 5 files changed, 113 insertions(+), 54 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 22e8946f3a..d4db20fd83 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -64,7 +64,7 @@ tables: - name: nav_rth_alt_mode values: ["CURRENT", "EXTRA", "FIXED", "MAX", "AT_LEAST", "AT_LEAST_LINEAR_DESCENT"] - name: osd_unit - values: ["IMPERIAL", "METRIC", "UK"] + values: ["IMPERIAL", "METRIC", "METRIC MPH", "UK"] enum: osd_unit_e - name: osd_stats_energy_unit values: ["MAH", "WH"] diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 357a8acd7b..933a1144e9 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -317,6 +317,8 @@ static void osdLeftAlignString(char *buff) static void osdFormatDistanceSymbol(char *buff, int32_t dist, uint8_t decimals) { switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; case OSD_UNIT_IMPERIAL: if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), FEET_PER_MILE, decimals, 3, 3)) { buff[3] = SYM_DIST_MI; @@ -325,7 +327,7 @@ static void osdFormatDistanceSymbol(char *buff, int32_t dist, uint8_t decimals) } buff[4] = '\0'; break; - case OSD_UNIT_UK: + case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: if (osdFormatCentiNumber(buff, dist, METERS_PER_KILOMETER, decimals, 3, 3)) { @@ -344,32 +346,34 @@ static void osdFormatDistanceSymbol(char *buff, int32_t dist, uint8_t decimals) */ static void osdFormatDistanceStr(char *buff, int32_t dist) { - int32_t centifeet; - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_IMPERIAL: - centifeet = CENTIMETERS_TO_CENTIFEET(dist); - if (abs(centifeet) < FEET_PER_MILE * 100 / 2) { - // Show feet when dist < 0.5mi - tfp_sprintf(buff, "%d%c", (int)(centifeet / 100), SYM_FT); - } else { - // Show miles when dist >= 0.5mi - tfp_sprintf(buff, "%d.%02d%c", (int)(centifeet / (100*FEET_PER_MILE)), - (abs(centifeet) % (100 * FEET_PER_MILE)) / FEET_PER_MILE, SYM_MI); + int32_t centifeet; + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + centifeet = CENTIMETERS_TO_CENTIFEET(dist); + if (abs(centifeet) < FEET_PER_MILE * 100 / 2) { + // Show feet when dist < 0.5mi + tfp_sprintf(buff, "%d%c", (int)(centifeet / 100), SYM_FT); + } else { + // Show miles when dist >= 0.5mi + tfp_sprintf(buff, "%d.%02d%c", (int)(centifeet / (100*FEET_PER_MILE)), + (abs(centifeet) % (100 * FEET_PER_MILE)) / FEET_PER_MILE, SYM_MI); + } + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + if (abs(dist) < METERS_PER_KILOMETER * 100) { + // Show meters when dist < 1km + tfp_sprintf(buff, "%d%c", (int)(dist / 100), SYM_M); + } else { + // Show kilometers when dist >= 1km + tfp_sprintf(buff, "%d.%02d%c", (int)(dist / (100*METERS_PER_KILOMETER)), + (abs(dist) % (100 * METERS_PER_KILOMETER)) / METERS_PER_KILOMETER, SYM_KM); + } + break; } - break; - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_METRIC: - if (abs(dist) < METERS_PER_KILOMETER * 100) { - // Show meters when dist < 1km - tfp_sprintf(buff, "%d%c", (int)(dist / 100), SYM_M); - } else { - // Show kilometers when dist >= 1km - tfp_sprintf(buff, "%d.%02d%c", (int)(dist / (100*METERS_PER_KILOMETER)), - (abs(dist) % (100 * METERS_PER_KILOMETER)) / METERS_PER_KILOMETER, SYM_KM); - } - break; - } } /** @@ -381,6 +385,8 @@ static int32_t osdConvertVelocityToUnit(int32_t vel) switch ((osd_unit_e)osdConfig()->units) { case OSD_UNIT_UK: FALLTHROUGH; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; case OSD_UNIT_IMPERIAL: return (vel * 224) / 10000; // Convert to mph case OSD_UNIT_METRIC: @@ -399,6 +405,8 @@ void osdFormatVelocityStr(char* buff, int32_t vel, bool _3D) switch ((osd_unit_e)osdConfig()->units) { case OSD_UNIT_UK: FALLTHROUGH; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; case OSD_UNIT_IMPERIAL: tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_MPH : SYM_MPH)); break; @@ -422,6 +430,8 @@ static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid) switch (osdConfig()->units) { case OSD_UNIT_UK: FALLTHROUGH; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; case OSD_UNIT_IMPERIAL: centivalue = (ws * 224) / 100; suffix = SYM_MPH; @@ -469,6 +479,8 @@ void osdFormatAltitudeSymbol(char *buff, int32_t alt) } buff[5] = '\0'; break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; case OSD_UNIT_METRIC: // alt is alredy in cm if (osdFormatCentiNumber(buff + 4 - digits, alt, 1000, 0, 2, digits)) { @@ -491,11 +503,13 @@ static void osdFormatAltitudeStr(char *buff, int32_t alt) { int32_t value; switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; case OSD_UNIT_IMPERIAL: value = CENTIMETERS_TO_FEET(alt); tfp_sprintf(buff, "%d%c", (int)value, SYM_FT); break; - case OSD_UNIT_UK: + case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: value = CENTIMETERS_TO_METERS(alt); @@ -1088,12 +1102,14 @@ static void osdDrawMap(int referenceHeading, uint8_t referenceSym, uint8_t cente const int scaleReductionMultiplier = MIN(midX - hMargin, midY - vMargin) / 2; switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; case OSD_UNIT_IMPERIAL: initialScale = 16; // 16m ~= 0.01miles break; - case OSD_UNIT_UK: - FALLTHROUGH; default: + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; case OSD_UNIT_METRIC: initialScale = 10; // 10m as initial scale break; @@ -2124,6 +2140,8 @@ static bool osdDrawSingleElement(uint8_t item) sym = SYM_FTS; break; default: + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; case OSD_UNIT_METRIC: // Already in cm/s sym = SYM_MS; @@ -2410,6 +2428,8 @@ static bool osdDrawSingleElement(uint8_t item) } bool efficiencyValid = (value > 0) && (gpsSol.groundSpeed > 100); switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; case OSD_UNIT_IMPERIAL: moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10, 1000, 0, 2, 3); if (!moreThanAh) { @@ -2424,7 +2444,7 @@ static bool osdDrawSingleElement(uint8_t item) buff[5] = '\0'; } break; - case OSD_UNIT_UK: + case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: moreThanAh = osdFormatCentiNumber(buff, value * 100, 1000, 0, 2, 3); @@ -2465,11 +2485,13 @@ static bool osdDrawSingleElement(uint8_t item) } bool efficiencyValid = (value > 0) && (gpsSol.groundSpeed > 100); switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; case OSD_UNIT_IMPERIAL: osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10000, 0, 2, 0, 3); buff[3] = SYM_WH_MI; break; - case OSD_UNIT_UK: + case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: osdFormatCentiNumber(buff, value / 10, 0, 2, 0, 3); @@ -2654,6 +2676,8 @@ static bool osdDrawSingleElement(uint8_t item) int maxDecimals; switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; case OSD_UNIT_IMPERIAL: scaleToUnit = 100 / 1609.3440f; // scale to 0.01mi for osdFormatCentiNumber() scaleUnitDivisor = 0; @@ -2661,9 +2685,9 @@ static bool osdDrawSingleElement(uint8_t item) symScaled = SYM_MI; maxDecimals = 2; break; - case OSD_UNIT_UK: - FALLTHROUGH; default: + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; case OSD_UNIT_METRIC: scaleToUnit = 100; // scale to cm for osdFormatCentiNumber() scaleUnitDivisor = 1000; // Convert to km when scale gets bigger than 999m @@ -3226,12 +3250,20 @@ static void osdCompleteAsyncInitialization(void) #define STATS_VALUE_X_POS 24 if (statsConfig()->stats_enabled) { displayWrite(osdDisplayPort, STATS_LABEL_X_POS, ++y, "ODOMETER:"); - if (osdConfig()->units == OSD_UNIT_IMPERIAL) { - tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_MILE)); - string_buffer[5] = SYM_MI; - } else { - tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_KILOMETER)); - string_buffer[5] = SYM_KM; + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_MILE)); + string_buffer[5] = SYM_MI; + break; + default: + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_KILOMETER)); + string_buffer[5] = SYM_KM; + break; } string_buffer[6] = '\0'; displayWrite(osdDisplayPort, STATS_VALUE_X_POS-5, y, string_buffer); @@ -3251,12 +3283,20 @@ static void osdCompleteAsyncInitialization(void) displayWrite(osdDisplayPort, STATS_LABEL_X_POS, ++y, "AVG EFFICIENCY:"); if (statsConfig()->stats_total_dist) { uint32_t avg_efficiency = statsConfig()->stats_total_energy / (statsConfig()->stats_total_dist / METERS_PER_KILOMETER); // mWh/km - if (osdConfig()->units == OSD_UNIT_IMPERIAL) { - osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3); - string_buffer[3] = SYM_WH_MI; - } else { - osdFormatCentiNumber(string_buffer, avg_efficiency / 10000 * METERS_PER_MILE, 0, 2, 0, 3); - string_buffer[3] = SYM_WH_KM; + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3); + string_buffer[3] = SYM_WH_MI; + break; + default: + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + osdFormatCentiNumber(string_buffer, avg_efficiency / 10000 * METERS_PER_MILE, 0, 2, 0, 3); + string_buffer[3] = SYM_WH_KM; + break; } } else { string_buffer[0] = string_buffer[1] = string_buffer[2] = '-'; @@ -3482,6 +3522,8 @@ static void osdShowStatsPage2(void) } } break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; case OSD_UNIT_METRIC: if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000000.0f / totalDistance), 1000, 0, 2, 3); diff --git a/src/main/io/osd.h b/src/main/io/osd.h index e1d22e1a7d..e23b8225f6 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -238,7 +238,8 @@ typedef enum { typedef enum { OSD_UNIT_IMPERIAL, OSD_UNIT_METRIC, - OSD_UNIT_UK, // Show speed in mp/h, other values in metric + OSD_UNIT_METRIC_MPH, // Old UK units, all metric except speed in mph + OSD_UNIT_UK, // Show everything in imperial, temperature in C OSD_UNIT_MAX = OSD_UNIT_UK, } osd_unit_e; diff --git a/src/main/io/osd_canvas.c b/src/main/io/osd_canvas.c index 9d7a965bde..d22c1813ac 100644 --- a/src/main/io/osd_canvas.c +++ b/src/main/io/osd_canvas.c @@ -502,9 +502,11 @@ static int32_t osdCanvasSidebarGetValue(osd_sidebar_scroll_e scroll) break; case OSD_SIDEBAR_SCROLL_ALTITUDE: switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; case OSD_UNIT_IMPERIAL: return CENTIMETERS_TO_CENTIFEET(osdGetAltitude()); - case OSD_UNIT_UK: + case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: return osdGetAltitude(); @@ -517,6 +519,8 @@ static int32_t osdCanvasSidebarGetValue(osd_sidebar_scroll_e scroll) switch ((osd_unit_e)osdConfig()->units) { case OSD_UNIT_UK: FALLTHROUGH; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; case OSD_UNIT_IMPERIAL: // cms/s to (mi/h) * 100 return speed * 224 / 100; @@ -530,9 +534,11 @@ static int32_t osdCanvasSidebarGetValue(osd_sidebar_scroll_e scroll) case OSD_SIDEBAR_SCROLL_HOME_DISTANCE: #if defined(USE_GPS) switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; case OSD_UNIT_IMPERIAL: return CENTIMETERS_TO_CENTIFEET(GPS_distanceToHome * 100); - case OSD_UNIT_UK: + case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: return GPS_distanceToHome * 100; @@ -575,13 +581,15 @@ static void osdCanvasSidebarGetUnit(osdUnit_t *unit, uint16_t *countsPerStep, os break; case OSD_SIDEBAR_SCROLL_ALTITUDE: switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; case OSD_UNIT_IMPERIAL: unit->symbol = SYM_ALT_FT; unit->divisor = FEET_PER_KILOFEET; unit->divided_symbol = SYM_ALT_KFT; *countsPerStep = 50; break; - case OSD_UNIT_UK: + case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: unit->symbol = SYM_ALT_M; @@ -595,6 +603,8 @@ static void osdCanvasSidebarGetUnit(osdUnit_t *unit, uint16_t *countsPerStep, os switch ((osd_unit_e)osdConfig()->units) { case OSD_UNIT_UK: FALLTHROUGH; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; case OSD_UNIT_IMPERIAL: unit->symbol = SYM_MPH; unit->divisor = 0; @@ -611,13 +621,15 @@ static void osdCanvasSidebarGetUnit(osdUnit_t *unit, uint16_t *countsPerStep, os break; case OSD_SIDEBAR_SCROLL_HOME_DISTANCE: switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; case OSD_UNIT_IMPERIAL: unit->symbol = SYM_FT; unit->divisor = FEET_PER_MILE; unit->divided_symbol = SYM_MI; *countsPerStep = 300; break; - case OSD_UNIT_UK: + case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: unit->symbol = SYM_M; diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index bc3c7b720b..0c164a9f28 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -652,10 +652,10 @@ static int32_t osdConvertVelocityToUnit(int32_t vel) switch (osdConfig()->units) { case OSD_UNIT_UK: FALLTHROUGH; - + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; case OSD_UNIT_IMPERIAL: return (vel * 224) / 10000; // Convert to mph - case OSD_UNIT_METRIC: return (vel * 36) / 1000; // Convert to kmh } @@ -692,6 +692,8 @@ void osdDJIFormatVelocityStr(char* buff) switch (osdConfig()->units) { case OSD_UNIT_UK: FALLTHROUGH; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; case OSD_UNIT_IMPERIAL: tfp_sprintf(buff, "%s %3d MPH", sourceBuf, (int)osdConvertVelocityToUnit(vel)); break; @@ -719,6 +721,8 @@ static void osdDJIFormatDistanceStr(char *buff, int32_t dist) int32_t centifeet; switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; case OSD_UNIT_IMPERIAL: centifeet = CENTIMETERS_TO_CENTIFEET(dist); if (abs(centifeet) < FEET_PER_MILE * 100 / 2) { @@ -731,7 +735,7 @@ static void osdDJIFormatDistanceStr(char *buff, int32_t dist) (abs(centifeet) % (100 * FEET_PER_MILE)) / FEET_PER_MILE, "Mi"); } break; - case OSD_UNIT_UK: + case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: if (abs(dist) < METERS_PER_KILOMETER * 100) { From e0860d1fa86a30c0f99b7fc8ae7eff0e8b54a107 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sat, 26 Jun 2021 14:30:48 +0200 Subject: [PATCH 082/102] Switch Control Derivative to PT2 filter --- src/main/flight/pid.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index d54f5ff443..146d53f177 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -110,7 +110,7 @@ typedef struct { bool itermLimitActive; bool itermFreezeActive; - biquadFilter_t rateTargetFilter; + pt2Filter_t rateTargetFilter; smithPredictor_t smithPredictor; } pidState_t; @@ -356,7 +356,7 @@ bool pidInitFilters(void) if (pidProfile()->controlDerivativeLpfHz) { for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { - biquadFilterInitLPF(&pidState[axis].rateTargetFilter, pidProfile()->controlDerivativeLpfHz, getLooptime()); + pt2FilterInit(&pidState[axis].rateTargetFilter, pt2FilterGain(pidProfile()->controlDerivativeLpfHz, refreshRate * 1e-6f)); } } @@ -816,7 +816,7 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid const float newDTerm = dTermProcess(pidState, dT); const float rateTargetDelta = pidState->rateTarget - pidState->previousRateTarget; - const float rateTargetDeltaFiltered = biquadFilterApply(&pidState->rateTargetFilter, rateTargetDelta); + const float rateTargetDeltaFiltered = pt2FilterApply(&pidState->rateTargetFilter, rateTargetDelta); /* * Compute Control Derivative From 49577d3f656dc3ace944b67f6dfc135196922c68 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sat, 26 Jun 2021 14:31:29 +0100 Subject: [PATCH 083/102] Added _ --- src/main/fc/settings.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index d4db20fd83..6b8d092e9d 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -64,7 +64,7 @@ tables: - name: nav_rth_alt_mode values: ["CURRENT", "EXTRA", "FIXED", "MAX", "AT_LEAST", "AT_LEAST_LINEAR_DESCENT"] - name: osd_unit - values: ["IMPERIAL", "METRIC", "METRIC MPH", "UK"] + values: ["IMPERIAL", "METRIC", "METRIC_MPH", "UK"] enum: osd_unit_e - name: osd_stats_energy_unit values: ["MAH", "WH"] From 6dce0e076e5969ca37496868e9382dc3b1055891 Mon Sep 17 00:00:00 2001 From: JuliooCesarMDM Date: Sat, 26 Jun 2021 13:06:57 -0300 Subject: [PATCH 084/102] fix --- src/main/navigation/navigation_fixedwing.c | 13 +++++++++++-- 1 file changed, 11 insertions(+), 2 deletions(-) diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 6b970c0d54..52cd765f79 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -236,8 +236,13 @@ void resetFixedWingPositionController(void) static int8_t loiterDirection(void) { int8_t dir = 1; //NAV_LOITER_RIGHT - if (pidProfile()->loiter_direction == NAV_LOITER_LEFT) dir = -1; + + if (pidProfile()->loiter_direction == NAV_LOITER_LEFT) { + dir = -1; + } + if (pidProfile()->loiter_direction == NAV_LOITER_YAW) { + if (rcCommand[YAW] < -250) { loiterDirYaw = 1; //RIGHT //yaw is contrariwise } @@ -248,7 +253,11 @@ static int8_t loiterDirection(void) { dir = loiterDirYaw; } - if (IS_RC_MODE_ACTIVE(BOXLOITERDIRCHN)) dir *= -1; + + if (IS_RC_MODE_ACTIVE(BOXLOITERDIRCHN)) { + dir *= -1; + } + return dir; } From 81a4788246c5d773099d9eb670d56538e19b8db5 Mon Sep 17 00:00:00 2001 From: JuliooCesarMDM Date: Sat, 26 Jun 2021 13:09:20 -0300 Subject: [PATCH 085/102] fix2 --- src/main/navigation/navigation_fixedwing.c | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 52cd765f79..484529944a 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -655,24 +655,26 @@ void applyFixedWingNavigationController(navigationFSMStateFlags_t navStateFlags, // Motor has been stopped by user. Update target altitude and bypass navigation pitch/throttle control resetFixedWingAltitudeController(); setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos, posControl.actualState.yaw, NAV_POS_UPDATE_Z); - } else + } else { applyFixedWingAltitudeAndThrottleController(currentTimeUs); + } } - if (navStateFlags & NAV_CTL_POS) + if (navStateFlags & NAV_CTL_POS) { applyFixedWingPositionController(currentTimeUs); + } } else { posControl.rcAdjustment[PITCH] = 0; posControl.rcAdjustment[ROLL] = 0; } - if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && posControl.flags.isAdjustingPosition){ + if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && posControl.flags.isAdjustingPosition) { rcCommand[ROLL] = applyDeadbandRescaled(rcCommand[ROLL], rcControlsConfig()->pos_hold_deadband, -500, 500); } //if (navStateFlags & NAV_CTL_YAW) - if ((navStateFlags & NAV_CTL_ALT) || (navStateFlags & NAV_CTL_POS)){ + if ((navStateFlags & NAV_CTL_ALT) || (navStateFlags & NAV_CTL_POS)) { applyFixedWingPitchRollThrottleController(navStateFlags, currentTimeUs); } } From c2448ef9e2f9c60b58c36de7f4564fd650d23367 Mon Sep 17 00:00:00 2001 From: JuliooCesarMDM Date: Sat, 26 Jun 2021 14:38:17 -0300 Subject: [PATCH 086/102] [Revert PR] Add esc temperatur on CLI status --- src/main/fc/cli.c | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 5edafca5d9..469b70d39f 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -119,6 +119,9 @@ uint8_t cliMode = 0; #include "sensors/opflow.h" #include "sensors/sensors.h" #include "sensors/temperature.h" +#ifdef USE_ESC_SENSOR +#include "sensors/esc_sensor.h" +#endif #include "telemetry/frsky_d.h" #include "telemetry/telemetry.h" @@ -3193,6 +3196,18 @@ static void cliStatus(char *cmdline) hardwareSensorStatusNames[getHwGPSStatus()] ); +#ifdef USE_ESC_SENSOR + uint8_t motorCount = getMotorCount(); + if (STATE(ESC_SENSOR_ENABLED) && motorCount > 0) { + cliPrintLinef("ESC Temperature(s): Motor Count = %d", motorCount); + for (uint8_t i = 0; i < motorCount; i++) { + const escSensorData_t *escState = getEscTelemetry(i); //Get ESC telemetry + cliPrintf("ESC %d: %d\260C, ", i, escState->temperature); + } + cliPrintLinefeed(); + } +#endif + #ifdef USE_SDCARD cliSdInfo(NULL); #endif From d234c5becfd58f11de16be4e5b1950f7842cc095 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Sun, 27 Jun 2021 14:00:20 +0100 Subject: [PATCH 087/102] add MC servos to IFLIGHTF7_TWING --- src/main/target/IFLIGHTF7_TWING/target.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/target/IFLIGHTF7_TWING/target.c b/src/main/target/IFLIGHTF7_TWING/target.c index 83090b5c94..fb1d9804fd 100644 --- a/src/main/target/IFLIGHTF7_TWING/target.c +++ b/src/main/target/IFLIGHTF7_TWING/target.c @@ -37,11 +37,11 @@ const timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR | TIM_USE_MC_SERVO, 0, 0), + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR | TIM_USE_MC_SERVO, 0, 0), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), }; From 9de1e2aaef2d6d462bbe14b094d44dba5e681ed6 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sun, 27 Jun 2021 19:26:30 +0100 Subject: [PATCH 088/102] Update settings.yaml (#7201) --- src/main/fc/settings.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 22e8946f3a..e973c036a4 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1147,7 +1147,7 @@ groups: field: motor.turtleModePowerFactor default_value: 55 description: "Turtle mode power factor" - condition: "USE_DSHOT" + condition: USE_DSHOT min: 0 max: 100 - name: failsafe_throttle From bbd6356685c8ab8cd0cca77e7819cd032277be30 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Mon, 28 Jun 2021 16:44:38 +0200 Subject: [PATCH 089/102] Fix MAMBAF405US target (#7203) --- src/main/target/MAMBAF405US/target.h | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/src/main/target/MAMBAF405US/target.h b/src/main/target/MAMBAF405US/target.h index 969b725bf4..ae1eb7bb33 100644 --- a/src/main/target/MAMBAF405US/target.h +++ b/src/main/target/MAMBAF405US/target.h @@ -57,7 +57,7 @@ #define I2C2_SDA PB9 #define DEFAULT_I2C_BUS BUS_I2C1 -#else +#else #define USE_I2C_DEVICE_2 #define I2C2_SCL PB10 // SCL pad TX3 @@ -186,8 +186,8 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(2)) -#define MAX_PWM_OUTPUT_PORTS 8 -#define TARGET_MOTOR_COUNT 4 +#define MAX_PWM_OUTPUT_PORTS 4 +#define TARGET_MOTOR_COUNT 4 // ESC-related features #define USE_DSHOT @@ -199,4 +199,3 @@ #define PITOT_I2C_BUS DEFAULT_I2C_BUS #define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS #define BNO055_I2C_BUS DEFAULT_I2C_BUS - From 3c45c7a78a80f0ce4dfc077ae925634cacbadea3 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Sat, 3 Jul 2021 01:42:36 +0200 Subject: [PATCH 090/102] New target SKYSTARSF405HD (#7210) --- src/main/target/SKYSTARSF405HD/CMakeLists.txt | 1 + src/main/target/SKYSTARSF405HD/config.c | 29 +++ src/main/target/SKYSTARSF405HD/target.c | 35 ++++ src/main/target/SKYSTARSF405HD/target.h | 166 ++++++++++++++++++ 4 files changed, 231 insertions(+) create mode 100644 src/main/target/SKYSTARSF405HD/CMakeLists.txt create mode 100644 src/main/target/SKYSTARSF405HD/config.c create mode 100644 src/main/target/SKYSTARSF405HD/target.c create mode 100644 src/main/target/SKYSTARSF405HD/target.h diff --git a/src/main/target/SKYSTARSF405HD/CMakeLists.txt b/src/main/target/SKYSTARSF405HD/CMakeLists.txt new file mode 100644 index 0000000000..cc9515d9e0 --- /dev/null +++ b/src/main/target/SKYSTARSF405HD/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405xg(SKYSTARSF405HD) diff --git a/src/main/target/SKYSTARSF405HD/config.c b/src/main/target/SKYSTARSF405HD/config.c new file mode 100644 index 0000000000..6dd129e144 --- /dev/null +++ b/src/main/target/SKYSTARSF405HD/config.c @@ -0,0 +1,29 @@ +/* + * This file is part of iNav. + * + * iNav is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * iNav is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with iNav. If not, see . + */ + +#include +#include + +#include + +#include "io/serial.h" +#include "rx/rx.h" + +void targetConfiguration(void) +{ + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART6)].functionMask = FUNCTION_DJI_HD_OSD; +} diff --git a/src/main/target/SKYSTARSF405HD/target.c b/src/main/target/SKYSTARSF405HD/target.c new file mode 100644 index 0000000000..ecaeed2621 --- /dev/null +++ b/src/main/target/SKYSTARSF405HD/target.c @@ -0,0 +1,35 @@ +/* + * This file is part of iNav. + * + * iNav is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * iNav is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with iNav. If not, see . + */ + +#include +#include +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + +const timerHardware_t timerHardware[] = { + DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM, 0, 0), + + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), + + DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/SKYSTARSF405HD/target.h b/src/main/target/SKYSTARSF405HD/target.h new file mode 100644 index 0000000000..d6c562aa0b --- /dev/null +++ b/src/main/target/SKYSTARSF405HD/target.h @@ -0,0 +1,166 @@ +/* + * This file is part of iNav. + * + * iNav is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * iNav is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with iNav. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "SS4D" + +#define USBD_PRODUCT_STRING "SkystarsF405HD" + +#define LED0 PC14 // green +#define LED1 PC15 // blue + +#define BEEPER PC13 +#define BEEPER_INVERTED + +// *************** Gyro & ACC ********************** +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_BUS BUS_SPI1 + +#define USE_EXTI +#define GYRO_INT_EXTI PC4 +#define USE_MPU_DATA_READY_SIGNAL + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW180_DEG_FLIP + +// *************** M25P256 flash ******************** +#define USE_FLASHFS +#define USE_FLASH_M25P16 + +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PB5 + +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN PA15 + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +// *************** OSD & baro *********************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +#define USE_BARO +#define USE_BARO_BMP280 +#define BMP280_SPI_BUS BUS_SPI2 +#define BMP280_CS_PIN PC5 + +// *************** UART ***************************** +#define USE_VCP + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 + +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN PA0 + +#define USE_UART5 +#define UART5_RX_PIN PD2 +#define UART5_TX_PIN PC12 + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 + +#define SERIAL_PORT_COUNT 7 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART1 + +// *************** I2C **************************** +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define DEFAULT_I2C_BUS BUS_I2C1 + +#define USE_MAG +#define MAG_I2C_BUS DEFAULT_I2C_BUS +#define USE_MAG_AK8963 +#define USE_MAG_AK8975 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +#define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS + +#define BNO055_I2C_BUS DEFAULT_I2C_BUS + +#define USE_RANGEFINDER +#define USE_RANGEFINDER_MSP +#define USE_RANGEFINDER_HCSR04_I2C +#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS + +#define PITOT_I2C_BUS DEFAULT_I2C_BUS +#define PCA9685_I2C_BUS DEFAULT_I2C_BUS + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC2 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY ) + +#define USE_LED_STRIP +#define WS2811_PIN PC8 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff + +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIALSHOT + +#define MAX_PWM_OUTPUT_PORTS 4 From cb6726e2691d3567578c77822abe8c7d9a4bd8f8 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 4 Jul 2021 16:38:45 +0200 Subject: [PATCH 091/102] Enable H743 for release --- src/main/target/MATEKH743/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/MATEKH743/CMakeLists.txt b/src/main/target/MATEKH743/CMakeLists.txt index 40b0996e17..96a65ca5a4 100644 --- a/src/main/target/MATEKH743/CMakeLists.txt +++ b/src/main/target/MATEKH743/CMakeLists.txt @@ -1 +1 @@ -target_stm32h743xi(MATEKH743 SKIP_RELEASES) +target_stm32h743xi(MATEKH743) From f4472999b93c247b93795eb2740686ffe22ecba8 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 5 Jul 2021 11:47:21 +0200 Subject: [PATCH 092/102] Make PWM beeper configurable option --- src/main/drivers/pwm_output.c | 4 ---- src/main/drivers/sound_beeper.c | 28 +++++++++++++++------------ src/main/fc/config.c | 3 ++- src/main/fc/config.h | 1 + src/main/fc/settings.yaml | 5 +++++ src/main/target/FALCORE/config.c | 2 ++ src/main/target/FRSKYPILOT/config.c | 3 +++ src/main/target/MATEKF405CAN/config.c | 3 ++- src/main/target/MATEKH743/config.c | 2 ++ src/main/target/YUPIF4/config.c | 1 + src/main/target/YUPIF7/config.c | 1 + src/main/target/common_post.h | 4 ++++ 12 files changed, 39 insertions(+), 18 deletions(-) diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 620c25a22a..20429e07cb 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -105,11 +105,9 @@ static timeUs_t digitalMotorUpdateIntervalUs = 0; static timeUs_t digitalMotorLastUpdateUs; #endif -#ifdef BEEPER_PWM static pwmOutputPort_t beeperPwmPort; static pwmOutputPort_t *beeperPwm; static uint16_t beeperFrequency = 0; -#endif static uint8_t allocatedOutputPortCount = 0; @@ -634,7 +632,6 @@ void pwmWriteServo(uint8_t index, uint16_t value) } } -#ifdef BEEPER_PWM void pwmWriteBeeper(bool onoffBeep) { if (beeperPwm == NULL) @@ -666,4 +663,3 @@ void beeperPwmInit(ioTag_t tag, uint16_t frequency) pwmOutConfigTimer(beeperPwm, tch, PWM_TIMER_HZ, 1000000 / beeperFrequency, (1000000 / beeperFrequency) / 2); } } -#endif diff --git a/src/main/drivers/sound_beeper.c b/src/main/drivers/sound_beeper.c index 4dc37cbd16..e7ba58ac35 100644 --- a/src/main/drivers/sound_beeper.c +++ b/src/main/drivers/sound_beeper.c @@ -23,11 +23,10 @@ #include "drivers/time.h" #include "drivers/io.h" -#ifdef BEEPER_PWM #include "drivers/timer.h" #include "drivers/pwm_mapping.h" #include "drivers/pwm_output.h" -#endif +#include "fc/config.h" #include "sound_beeper.h" @@ -44,13 +43,18 @@ void systemBeep(bool onoff) { #if !defined(BEEPER) UNUSED(onoff); -#elif defined(BEEPER_PWM) - pwmWriteBeeper(onoff); - beeperState = onoff; #else - IOWrite(beeperIO, beeperInverted ? onoff : !onoff); - beeperState = onoff; + + if (beeperConfig()->pwmMode) { + pwmWriteBeeper(onoff); + beeperState = onoff; + } else { + IOWrite(beeperIO, beeperInverted ? onoff : !onoff); + beeperState = onoff; + } + #endif + } void systemBeepToggle(void) @@ -70,11 +74,11 @@ void beeperInit(const beeperDevConfig_t *config) if (beeperIO) { IOInit(beeperIO, OWNER_BEEPER, RESOURCE_OUTPUT, 0); -#if defined(BEEPER_PWM) - beeperPwmInit(config->ioTag, BEEPER_PWM_FREQUENCY); -#else - IOConfigGPIO(beeperIO, config->isOD ? IOCFG_OUT_OD : IOCFG_OUT_PP); -#endif + if (beeperConfig()->pwmMode) { + beeperPwmInit(config->ioTag, BEEPER_PWM_FREQUENCY); + } else { + IOConfigGPIO(beeperIO, config->isOD ? IOCFG_OUT_OD : IOCFG_OUT_PP); + } } systemBeep(false); diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 8937097a7b..1fbafc3165 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -123,13 +123,14 @@ PG_RESET_TEMPLATE(systemConfig_t, systemConfig, .name = SETTING_NAME_DEFAULT ); -PG_REGISTER_WITH_RESET_TEMPLATE(beeperConfig_t, beeperConfig, PG_BEEPER_CONFIG, 1); +PG_REGISTER_WITH_RESET_TEMPLATE(beeperConfig_t, beeperConfig, PG_BEEPER_CONFIG, 2); PG_RESET_TEMPLATE(beeperConfig_t, beeperConfig, .beeper_off_flags = 0, .preferred_beeper_off_flags = 0, .dshot_beeper_enabled = SETTING_DSHOT_BEEPER_ENABLED_DEFAULT, .dshot_beeper_tone = SETTING_DSHOT_BEEPER_TONE_DEFAULT, + .pwmMode = SETTING_BEEPER_PWM_MODE_DEFAULT, ); PG_REGISTER_WITH_RESET_TEMPLATE(adcChannelConfig_t, adcChannelConfig, PG_ADC_CHANNEL_CONFIG, 0); diff --git a/src/main/fc/config.h b/src/main/fc/config.h index 4db38b6d6a..90d7b0d298 100644 --- a/src/main/fc/config.h +++ b/src/main/fc/config.h @@ -86,6 +86,7 @@ typedef struct beeperConfig_s { uint32_t preferred_beeper_off_flags; bool dshot_beeper_enabled; uint8_t dshot_beeper_tone; + bool pwmMode; } beeperConfig_t; PG_DECLARE(beeperConfig_t, beeperConfig); diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index e973c036a4..10b5341ae1 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3734,6 +3734,11 @@ groups: default_value: 1 field: dshot_beeper_tone type: uint8_t + - name: beeper_pwm_mode + field: pwmMode + type: bool + default_value: OFF + description: "On some targets allows to disable PWM mode for beeper. Switch from ON to OFF if extarnal beeper sound is weak. Do not switch from OFF to ON without checking if board supports PWM beeper mode" - name: PG_POWER_LIMITS_CONFIG type: powerLimitsConfig_t diff --git a/src/main/target/FALCORE/config.c b/src/main/target/FALCORE/config.c index f109d0e100..d1e6e71818 100755 --- a/src/main/target/FALCORE/config.c +++ b/src/main/target/FALCORE/config.c @@ -192,4 +192,6 @@ void targetConfiguration(void) ((controlRateConfig_t*)currentControlRateProfile)->throttle.rcExpo8 = 0; ((controlRateConfig_t*)currentControlRateProfile)->throttle.dynPID = 10; ((controlRateConfig_t*)currentControlRateProfile)->throttle.pa_breakpoint = 1600; + + beeperConfigMutable()->pwmMode = true; } diff --git a/src/main/target/FRSKYPILOT/config.c b/src/main/target/FRSKYPILOT/config.c index 05ec1b5a85..60f29d3884 100644 --- a/src/main/target/FRSKYPILOT/config.c +++ b/src/main/target/FRSKYPILOT/config.c @@ -22,6 +22,7 @@ #include "io/serial.h" #include "rx/rx.h" +#include "fc/config.h" void targetConfiguration(void) { @@ -29,4 +30,6 @@ void targetConfiguration(void) serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART6)].functionMask = FUNCTION_FRSKY_OSD; rxConfigMutable()->serialrx_inverted = 1; + + beeperConfigMutable()->pwmMode = true; } diff --git a/src/main/target/MATEKF405CAN/config.c b/src/main/target/MATEKF405CAN/config.c index 34166b5512..b400704b00 100644 --- a/src/main/target/MATEKF405CAN/config.c +++ b/src/main/target/MATEKF405CAN/config.c @@ -21,6 +21,7 @@ #include "config/feature.h" #include "io/serial.h" #include "sensors/compass.h" +#include "fc/config.h" void targetConfiguration(void) @@ -28,5 +29,5 @@ void targetConfiguration(void) compassConfigMutable()->mag_align = CW0_DEG_FLIP; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_GPS; // serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].gps_baudrateIndex = BAUD_115200; - + beeperConfigMutable()->pwmMode = true; } diff --git a/src/main/target/MATEKH743/config.c b/src/main/target/MATEKH743/config.c index 7e47e5bf6b..1065971614 100644 --- a/src/main/target/MATEKH743/config.c +++ b/src/main/target/MATEKH743/config.c @@ -20,6 +20,7 @@ #include "platform.h" #include "fc/fc_msp_box.h" +#include "fc/config.h" #include "io/piniobox.h" @@ -27,4 +28,5 @@ void targetConfiguration(void) { pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; + beeperConfigMutable()->pwmMode = true; } diff --git a/src/main/target/YUPIF4/config.c b/src/main/target/YUPIF4/config.c index 5ac92a8358..0e82c20e93 100644 --- a/src/main/target/YUPIF4/config.c +++ b/src/main/target/YUPIF4/config.c @@ -59,4 +59,5 @@ void targetConfiguration(void) pidProfileMutable()->bank_mc.pid[PID_LEVEL].I = 10; pidProfileMutable()->bank_mc.pid[PID_LEVEL].D = 75; + beeperConfigMutable()->pwmMode = true; } diff --git a/src/main/target/YUPIF7/config.c b/src/main/target/YUPIF7/config.c index e61e532d56..9d5077edba 100644 --- a/src/main/target/YUPIF7/config.c +++ b/src/main/target/YUPIF7/config.c @@ -59,4 +59,5 @@ void targetConfiguration(void) pidProfileMutable()->bank_mc.pid[PID_LEVEL].I = 10; pidProfileMutable()->bank_mc.pid[PID_LEVEL].D = 75; + beeperConfigMutable()->pwmMode = true; } diff --git a/src/main/target/common_post.h b/src/main/target/common_post.h index 1c7767dcf8..d7603c9e6f 100644 --- a/src/main/target/common_post.h +++ b/src/main/target/common_post.h @@ -61,6 +61,10 @@ extern uint8_t __config_end; #undef USE_PWM_SERVO_DRIVER #endif +#ifndef BEEPER_PWM_FREQUENCY +#define BEEPER_PWM_FREQUENCY 2500 +#endif + #define USE_ARM_MATH // try to use FPU functions #if defined(SIMULATOR_BUILD) || defined(UNIT_TEST) From 82bf948e692cbc053f7bca2b5fd64b5b26cdfd80 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 5 Jul 2021 11:48:14 +0200 Subject: [PATCH 093/102] docs update --- docs/Settings.md | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/docs/Settings.md b/docs/Settings.md index d8cf7304aa..4dbc9dc715 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -452,6 +452,16 @@ If the remaining battery capacity goes below this threshold the beeper will emit --- +### beeper_pwm_mode + +On some targets allows to disable PWM mode for beeper. Switch from ON to OFF if extarnal beeper sound is weak. Do not switch from OFF to ON without checking if board supports PWM beeper mode + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + ### blackbox_device Selection of where to write blackbox data From 1f62ffea28c965054649edf75200a52f8036397a Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 5 Jul 2021 11:52:57 +0200 Subject: [PATCH 094/102] Remove not needed defines --- src/main/target/FALCORE/target.h | 1 - src/main/target/FRSKYPILOT/target.h | 1 - src/main/target/MATEKF405CAN/target.h | 1 - src/main/target/MATEKH743/target.h | 1 - src/main/target/YUPIF4/target.h | 1 - src/main/target/YUPIF7/target.h | 1 - 6 files changed, 6 deletions(-) diff --git a/src/main/target/FALCORE/target.h b/src/main/target/FALCORE/target.h index cdb8ba4636..5d02d9c744 100755 --- a/src/main/target/FALCORE/target.h +++ b/src/main/target/FALCORE/target.h @@ -25,7 +25,6 @@ #define USE_HARDWARE_PREBOOT_SETUP // FALCORE board requires some hardware to be set up before booting and detecting sensors #define BEEPER PB4 -#define BEEPER_PWM #define BEEPER_PWM_FREQUENCY 2700 #define MPU6500_CS_PIN PC0 diff --git a/src/main/target/FRSKYPILOT/target.h b/src/main/target/FRSKYPILOT/target.h index 2dd56aa73d..539b465461 100644 --- a/src/main/target/FRSKYPILOT/target.h +++ b/src/main/target/FRSKYPILOT/target.h @@ -29,7 +29,6 @@ #define BEEPER PA0 #define BEEPER_INVERTED -#define BEEPER_PWM #define BEEPER_PWM_FREQUENCY 4000 #define USE_SPI diff --git a/src/main/target/MATEKF405CAN/target.h b/src/main/target/MATEKF405CAN/target.h index b9dde1e434..b321826dd4 100644 --- a/src/main/target/MATEKF405CAN/target.h +++ b/src/main/target/MATEKF405CAN/target.h @@ -25,7 +25,6 @@ #define BEEPER PA8 #define BEEPER_INVERTED -#define BEEPER_PWM #define BEEPER_PWM_FREQUENCY 2500 // *************** SPI1 Gyro & ACC ******************* diff --git a/src/main/target/MATEKH743/target.h b/src/main/target/MATEKH743/target.h index a0864cd140..84449f9f33 100644 --- a/src/main/target/MATEKH743/target.h +++ b/src/main/target/MATEKH743/target.h @@ -28,7 +28,6 @@ #define BEEPER PA15 #define BEEPER_INVERTED -#define BEEPER_PWM #define BEEPER_PWM_FREQUENCY 2500 // *************** IMU generic *********************** diff --git a/src/main/target/YUPIF4/target.h b/src/main/target/YUPIF4/target.h index 97e389826c..69c5bc3ab1 100644 --- a/src/main/target/YUPIF4/target.h +++ b/src/main/target/YUPIF4/target.h @@ -40,7 +40,6 @@ #if defined(YUPIF4MINI) // #define BEEPER_INVERTED #else -#define BEEPER_PWM #define BEEPER_INVERTED #define BEEPER_PWM_FREQUENCY 3150 #endif diff --git a/src/main/target/YUPIF7/target.h b/src/main/target/YUPIF7/target.h index 6a146a1c50..6123af03ab 100644 --- a/src/main/target/YUPIF7/target.h +++ b/src/main/target/YUPIF7/target.h @@ -25,7 +25,6 @@ #define CAMERA_CONTROL_PIN PB7 #define BEEPER PB14 -#define BEEPER_PWM #define BEEPER_INVERTED #define BEEPER_PWM_FREQUENCY 3150 From ea52108d3e6a2dea1bf596212c2b0380fa0af9ac Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 5 Jul 2021 12:35:52 +0200 Subject: [PATCH 095/102] Modify library to supress warnings when combining HAL and LL drivers --- .../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_exti.c | 5 ----- 1 file changed, 5 deletions(-) diff --git a/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_exti.c b/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_exti.c index 3d1d792425..d30bc514b9 100644 --- a/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_exti.c +++ b/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_exti.c @@ -20,11 +20,6 @@ /* Includes ------------------------------------------------------------------*/ #include "stm32h7xx_ll_exti.h" -#ifdef USE_FULL_ASSERT -#include "stm32_assert.h" -#else -#define assert_param(expr) ((void)0U) -#endif /** @addtogroup STM32H7xx_LL_Driver * @{ From f2a56aed930247c01b66998c257927c77b4c4299 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 5 Jul 2021 13:28:56 +0200 Subject: [PATCH 096/102] remove assert in one more place --- .../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_i2c.c | 5 ----- 1 file changed, 5 deletions(-) diff --git a/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_i2c.c b/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_i2c.c index a1eac83a9c..ed7104bbeb 100644 --- a/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_i2c.c +++ b/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_i2c.c @@ -21,11 +21,6 @@ /* Includes ------------------------------------------------------------------*/ #include "stm32h7xx_ll_i2c.h" #include "stm32h7xx_ll_bus.h" -#ifdef USE_FULL_ASSERT -#include "stm32_assert.h" -#else -#define assert_param(expr) ((void)0U) -#endif /** @addtogroup STM32H7xx_LL_Driver * @{ From bef405992a8fd8436927197d9b9de59382e61efd Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 6 Jul 2021 21:02:03 +0200 Subject: [PATCH 097/102] I2C Fix --- docs/Board - BetFPVF722.md | 12 ++++++++++++ docs/assets/betafpvf722.png | Bin 0 -> 226118 bytes src/main/target/BETAFPVF722/target.h | 19 ++++++++++--------- 3 files changed, 22 insertions(+), 9 deletions(-) create mode 100644 docs/Board - BetFPVF722.md create mode 100644 docs/assets/betafpvf722.png diff --git a/docs/Board - BetFPVF722.md b/docs/Board - BetFPVF722.md new file mode 100644 index 0000000000..387c9f8de2 --- /dev/null +++ b/docs/Board - BetFPVF722.md @@ -0,0 +1,12 @@ +# BetaFPVF722 + +## I2C bus for magnetometer + +BetFPVF722 does not have I2C pads broken out. I2C is shared with UART3 + +* TX3 - SCL +* RX3 - SDA + +> I2C and UART3 can not be used at the same time! Connect the serial receiver to a different serial port when I2C device like MAG is used. + +![BetaFPVF722 I2C](assets/betafpvf722.png) \ No newline at end of file diff --git a/docs/assets/betafpvf722.png b/docs/assets/betafpvf722.png new file mode 100644 index 0000000000000000000000000000000000000000..626deacaa9f13371703c73a19d8333ce5a37680f GIT binary patch literal 226118 zcmZ5{1yIy))HN+A-6ayz-67rG-Q7ruz_N5V3cG-k(k$I5AR*x{C5?o1OLx8t{@Jtu#TfPjFdq$sP6fPhp5f1#tJ!T(bI)%6Vi1JPSs zK^mcIm~tEb2E{>2O$q^_Hu=S^6)OBahKHh&Hv$57&*KZR-@Vip0pX!YNmfeN&wMW% z)sm=xy7#KtqP>?tCk2;=2E})pmfz8d85{LEQK93nmHqvFTxyz@Z*ORjP?*?9S8x%B z1s%?ZU>ir$q1KVY%g6c-z77}dcYhb&_-ae4sO%PviCsBZWaT(IE2=z>-O1^xyOO*v zJ(XR0e5+Fq{D{n@vyP*#qi@~#KO#(yntL7EGQiZuhQy;|j{^`{^z_+O#1e*FNURb@ zrEi28$$L4&wya{YD&xmd9nII`?9?7n_l4;h+mfQTvM;di|P2pB%5 zcB!%8ALoRiR}j->^kEdFpQY9Got)<>CTC{&E%}<_uL?%sSvEF24s*L9oVlmx7Ns(a zO8V<;JBhunSWIBQv>Fy*BP3A9G>gi);aE+`Q1?qLQqljnG9nO~0efY-VS+_b35dJ0 zB$7X?9vN$6Pdb7$318rbLDP1W7IPs$9bjFJzLfag<%>D{5dGU0!u(0fabx!>k%`Z( zh|AU)o!16!c;f*6W$_@A+!yXhc2Uo4E*D9&NLHI8oSsIz^Vm{((HWBM>u)Q$cs=EV zqhdc8=DYd1-^m)@8GZiccg-RjZxx04BNkOJ3Xz-!#6|J`iYgArI6*wRTFI}S0~{Y; z&o^7gcgT|_R9N&l&MZDYuAJn{vwS@=@A^6#VvC!48vVacpK+O^wgc%Kl#TVQDu}7+ zb9nftM5Vsbqj7fCh&g!ZCs>f2*z_uI9RJ()d&tw&z7#5IciMe2o3_E&#sH(T*k^J{%_?HL1}3>}rSj{f(;^0Mb(#&P>1_0GKOeq4#REEXSfNqp zM=@(W&CK8Biw%|CO|U3K6z$<}thM@VL4RZ+-Ir2jO2IEoXqlP|L#C|))QxP+CxMM^ zkMRPY3RZhMmclKuB8;*<#50F#g>Z~~9?_6iqgh2(JOP3qE0_$p+PlV626061jb@a! zEMu)+{Cb!nVr|<|HF^ro2RkQ^$uR&TPk=;hJ|>RkD&)Fe;LG`7BfhaPJ2>xWWJRY^ zLLxzGLW^F&l5*`}eD}rziZZrEgw&fawu6wZtY*wh`1v~HQlVfu(LfKkdO70Hg2`3Yg;&GEj^wWiz&%=o@&3^zI_RX}S#S zZ#(I+KOC6QBH$Yc5Ls%wvVFF~KxhxJK-v;R;=Izce_2Bszr@px4)Lz$(VN2G_P0wm z!4yr|jnlxYcv=JJx2Gi_8%d=g^Kq*>(vKcbiiyF~@Ope|Ak6^9=-9b}T4^0s&2(0z ziv^=Z`sU(5VI)V4+jR>)OT4$D(s~;OpY2(Mk>zO>X$#;WXYl0f^>HAXz^F|!-ih;4 zHEz0I@xOe*e>%;2+~tuU*|&MVsc^7};1*q)n>DEz1)Sta{tm!ka4b?qH7pDPIgb@$ z@YoN=T%YZ(emnR?ZBQkOj*Z>7aOr15^s&xPuS&sh{dG6%NgKX-rdx;=$|;h{W6Z$^ zAod9(j1;?aFLk$mCL!wPOdU8>^=rWzD0~TUS!>R#fcc!@wB7Q?wAi1-j_tk&RL;{? z@p*akEr4~AeFoC;9u3*fabAih_diZ)QY3G~45tkjSftDOM|M+CNj*;EFzJ>~TMTQt zwx^i1|AAo96BIZw@lcCZPDdWe1@*L=X!=Hd5DUSowM8zwakVGny!=>L#*~_CPXHTB zWohu))fam6ZROa`x;leZ0H4BTkV4`uZMi`;NAz}=To@O_TRXf6trsa?PWGIJ)bGO% zl}8}TAo^v!e-ETjd&C}x*DJ4VjLE1xObu7B<__;FCV4biOYoe@#+{k)G$&JjwZXUm zCZPUCof37&Utc0A83uDCf){^ly6n%lGU->u7}8;T9tlQZ5b7Y=~ADMWGaI zE`G1XYGRB34?A_A018ufi?6?7>QfW>nSEs{bM+Qud+#DD+dHOJWA+@)UT{=q|5heH z@y^0G!Jzvq2jSrw#J;anWjYGOCbib6eaWv_qpUr*W~eB|ftnR>kqq7@^rF+XdA*u7 zWRt}tFpqYXC^~6#etcwm!_xy%Xm!bhV^tMzU_Zy5q2tEEQ}%orlq~rm8f4#B(h=oZ z(aa(u$8B{$MJGKNK|*^3)u4Ep@;3r{tJbE zHplVe#H{xhRl*3=+vn)j3I6nL!>tTUJ~P&svv@Q%<`|8xx1e{4Ke+#UF!R%cS$aLf zm@$I+Og!B9oEisTOCIdHSt%7g_Y*>A@!%INiTxxNfOfn&60e%co2R>t?`3>irf55m zg1y?8C4!zJ>QZCp8`J1Q5hSt%6tp@fLvxrvZ zJ460mGVxEGA(##|IE>LPbka4}ktG%KT&J^KmC&XiQm$<|8wRONq7q9;$Q&yOe(3NL zW!T^Y2DW>yLoM*V0?u|2Nemcev*U>KoZsQ8{A@Dro-qG4!?pXdrsn&>mzliTt=0!$ zjOx=io-;6EvdO=73O}urAZET~kgD`IuMAL6L*;ojiY{uI>pQ(XNkrh)db(E@l{RYC zZ9|D2EWC0QdMquIUf`(J*S4t8yl=L&v%zKsCg<|QopPV2j-I_#?qaRC|JCAfS~GSc z@_?oZJT%4pO_p>5-ex&_S}1tx1pJt%{e)VnNeTfT$~H1=?^gi|Y>sb6h)pM1gQZy! zefDN*2XZAOid8eiG$if_iCFd1YOXbwpu=dSJ%Ag5yP_1TsrP?>Tb^co@bL2Ly!x}v ziz?#tH-c|_oSG>Zd++x*%vxc00i@%tx%QqZ26PxyO{$v44>d?a1wz`rV2k zR%r^>EDsrf?~iPVrFpxWEWs5p<;u#JL?MXX8%LB%HA5lzc4?;8#;^m}xU-8AN=9mEL$Jcwqu^F zu|lS$iyf0Espa6{zz4Q=u!NhNy|?waJhW=fGM*;IvlsDu`vJY}7+ceGfG1(`uH>|B ztUn-K3rB#b(s}xcnK$IfKC-fpsbAO-J)1_A=o+Rze>FZ&l5^CPluzNM=E5@u&4Rnu zi8)Li-C}x=UXXAoj?Q-ke#@Hr9vloj>Lu}-IRuL{p=LvMWvcfVzQO9M%5wU{=tq=I&2YPh@H5Ck#k?vE8B`H1|H``sxt6E9&{ol^2l$A4!S z`^Xz+Q)BB~txnQ1OdW>p;c|f{3Zt@_t+U^}*p@X=_$|v1>j{4P;& z*ytG_*Xe82j!+etGX5Ua9-)?rD%n+}^jrkwX(YX~(i>mY3{EKruf7Z732L(HiSiOD zn&OvdWAMQ_y4d$PuuJ6;m@$6$l8N7zENWkfwFe$p&cDJHawh)oPEj!++BD_OS`N$e zW!4e{yN0JX1rHYF+9XBpIom5P6g_ahkmskQKsDxggaZdsXz*We4t-`!XS7uREPzGC zqMNb`jaSaFYpw#GRYMzyO3Jq3_lrKpceYgSMocv(!UOj=swR{`>|3|9HvHertrlO7)5?rB|06%IA5+gx!G3_2<9FBwcULj+>TQHC{_si> z*)n2UD@spKSz8{|6~?C`>^HtEr`zNDmU@y|vh#92 zxKmR1^kFVpmg_DnGmk(_Owod};7guk04ma#VpSt5`G4|E9)-1ocoX6-U=oL??|V%? zkzIR^I9fQMd1(Kt{0w*Pnk{y*FRyXhNGr$wRf3-hF(T{NSW*2?hM>SR@ys}GtI*tXd`q&h1hhCARX$!1)=+b>;VSia+vRlw z&+>#DhvhK`xyty*=xK?ETY~UsIAFLV5CK-3NYaTzGguGv)#r#doT+dr7TK#m$#u~IwTa8Zxi*d5+ zLy&e^HDdMD#pLZB|NBjzoRRrwDrEq!snfY+s%5$PSvr%}^LP?e*fMLdMJiUKBYZyf zA-^}2^7MY1XL5!cI{3=H9L4kl5n$EFcmUKSC6+-s(<|X5E6oe(MVp{T2V>p;6W5J| zU9kwg@Q6ktqtXnx7MW#=uWn7uQ00w1lISi+G8pDHInMjpU`Vx}Gt=(ExsQ=SH?h#_ ztpKor=s_61`7}oA7p*~o9{@rv#(nJlO40nwK4qn&ACXCHX29cKS<5J3dUhYkzmpw# zJlQxXHS_AjGj{R&4%Ls}Eesc0O@6ud0cLUI$4RL=?LOjzj8mEVw!!qOoj2}8dAP>CxHNcQ6s|2>;E{|tn~3X>x5S-^=; z-b!B4r5g-&wr9$%7P$BFC>PaBuU+x$^rHlYQ=7*fFJ)7d!^VFlOG6&L%}Jjpj{*7a zLDG@kF4xzJsFiC?=Kbd2qGom5~DV8OeSVjZd#Up#DO{XXo{1=HqNwRoW@6RbAUkA5iA; z`V|ecIa%5#QtU{-u2#6#^bWr)oSwA)H=%Pl+1mvX&MHKrF=1Q#A;=(+4=u*@jZY8k zAsR&1(&$%ovUGz?jgiug$GO7jtw6Mv!#VsW@7I49DiPQYeInYOs!WA3F>6$i@es|7 zF-1M+f*=&F7#sD~+VmGrH=4HtNW}mRKHro#c$_$!4TCXO9#FKtqs-il^+5M6r(>X; z{O`Df<^q5H7ONmKt{nXr&mgA9C@LI~_@PK18Z%1HUU4*ES<3ImPAUg=V#xxHD!1@V z6=GVd@gW;Bzn{K7pL4gly*wHV`1)>J+ZLLpBv3_LgU?5l_glL7lRAjqgcxoEG)i;8 ztfNujVQfE~6${_30V|VP@Xc6kG!ss07a3X$xjo;OwfJ;=H}N70G|@PTW^Q<3-%9xI zt+x7q!40=@rdZ2l*Hj0`l^rYJ_%nC+a^-_gRx7b;C&*)E(5&gzlVfAMX6qg7Gz=pq zltC;;%RX@S?)Aypum}NU{~|L>e#E&a3dy*HqmSsR(0$bMVfU><@bic zUSLrLZtE*e?oKq5aDi;_=58?;Y-h^bWr=S#3;V|ZO-s~Hdr;xAy3TN+k3TM;}EOY>F!jM^H@{!qCwEAWh zN4s+bX^5#Jv<;kJXcPM-`W@U=-~mm7*-dO65#A7y^4P{?jhI#bk&qF;Y&Bk5L9#c%*9InO{685}5YlAYr$cpEd|&)xS8i-%ClXrUTNZTIRAogPsWn+#`mp@Docq)iw9z*Ni&$c8h*<4(hwe#Q9hZSRRo9; zd@@xTQ4sw~W5=lqGFn>NkCX@FsYS!64J;n(gjAjtq+jWyw*0XO2r#O{o8*);)FKRE z*ZNMJ_y$Fjiioznjq21wj()(xOF+75N zZW{7KW7sRVwWVi4!NJ9FoUQ7B?J13PmY{=9C_>q#;M8YO>;p;2XC zh;?t=7TiPJnXcxfaPc`1d-N>DMw+M@~eONmy;}yIVnu$VMDqc&0UEy zdCe=3x15GciPw|h)IJ23Q2v;FX+hh<5T^4*Fs-)O%F61vQCKdci2hmC9#@`jnKqL} zN1Lis(Ta&t&Md17nq2)o22ZZ;gD%H%T9fyty8j>{FImFNH~Pg_P`D8QKU4Y=3AftC zgE((V-r>+J#|*hs58e@0IB7D7!g{x8?`LjQP%QUU2{NaH+alK^v7^$CYWU+KE@C^X zW-ez92P(2oFVkVo^84#Fu>2xZ(w>29`+xruQ7`8kAI;34Q1`M(-lHc zvm?@6@$gzwz9X;|FQd}uxQM*zotanrEbw!AU_ddGEHrUs<_)Qxcv1=DRFJiXF<2=o zvz$pPfxta>(p&Z}owA;)pg9-J1$p^IAgfE@G1gwlqbPrrP}$r2Cp~BCu6t*AAx=J3 z-#Flh^5D4ht-E4nCUst7ic*Xkp?Ap`%wvT?H(1JEd^iA_Y9o-@dM){k_ z#y=+{Ea#u&+M5$cai8SFva)ujcFMOBb1qF{89yPCI z)FAxYft=U}c7(ot{Xihl7RcD8+xzZV?}0HF7zXDL1D?D!v*BNZA<@GC|s{U?b%wfpGhau&TF!1ZA3^F%gHd{lK9m1o6O@)4x>CZwSP;0H2Q zhQgFBDY_75KZt2758NW>EGa`XX3=kSn`;_7QC@&c`>#o4I};5hGyy4Be6}W4BI?eg zc~U&`>E@eTTaGRZ8I|6f!;ki%_`{yJ%k4pGOryJo(#Wt_CV9LSHBcz?-HHgyX?CK& z!@;sI_weO>Kx2xA0YvCYJ}Z3|^@W^UJPIc1akP^^JtePV`d|d5vK5bQd9YUuHf%M0bdn6=b`zyQfF0cG zdKfn>_E_$&6Biovy1FXl$$e=AF4fP`0T?spCdrj`=y0=cB)R7G9wPj8dP4s8N8~Re zw2DfR*5R)F1=p$zamM3Q$~9JgA-x7nsv)IF2F#JNP%1*HSWN}E?csq`q1^$zT7!5G zJ8)_n)!X+{xVKp)`s!JeJ%66t^bvWmA8$F;sfu(X&z8dgR4EDU3PTn0-oUIfZ;#_J z`)b$@OC;x)hL<#K`$C;3%asgY3bSs?kN>GL2F}_LEJK z|GCRF>HBqZ9O}6G<2NzDOMU85EnO!+O_*7l(JC^8oGxJ*v9Y)kJPH*uC~o_LE~?!` z{d!0gtowW*jj-m3|7xi#+>R9hpwcN;jlI9SSv_8d;X7`}>Q?uWJqx%Kxj3BtNo6S> z=Lg&{xNLNu{FtNdlhw37HX*`?^i>!P$}tRU-_gu>nXan)YywWFY?-U}m+2E-P2S90 zMm%judgD(}^lT8EquR9D3Ti3b8scP3S;>OGdF3E2!szjA!@J3BjT z41*loiYw11vzl}Qbv-Q{RZn_>4P-pFDGOs>&%oBJ;LmHuH zLr?zW+4Uo7fAJAjiVfE}in9B8KD-Y^zP_no|8xl77(-}m+_{JZn~B$!icS%aZT1DR zjyW@4$Gy_fXF-J$_3X7el=_aq8|AHnjGHtuS8fBd)8{sf3s&u#3d0#tGDk=(^KzQk>P843&Rk~b>=Ul6S)=9#d8*wxa zZ^7G@D^+aMRg{`VLhmc;ZcL=qg132tovj((!vo|}j(VG8IZvK*d(I=Lkbb=!PHn@T zM3G|iqk%kUD%(-SEgKVudTAbjfc`3pCxS(q;-uzy@_msq=;M!K21e=ZFwI6$9oyQ1 zFwfP#uGv|#&0&mgeA*wyiXWr}Otot+Dr{e5KD?G@{r1kT7=d13?Dtn62#VHwzD^sU zVXG*E-YXQdB;Ion4H02Uy*XUY(7(dfuf&$QHG5BEnWf?XR&_ITMYw~t6O_0+Gw>D~ zYr-@aAYd=M09rV!BO`NJ0KRuq`-gJys%<3+Eo+EjNK_At1|-3WXw=yE`aRqg2~z7B zcaD1!OK71wH+0^vEH;JaiZ>E4I6NTw)8H&6@mJqbmpQrH?Ig{g1tVh)t^5qJZ2A!gzW_`PdyIB}c^oUxwj%T($7HHz+Qzt)H5k~_9gL_$r#LWi@;sfuE_)q`N{drzwYF_C;T%u)~#J=?hUUDKEhx!?n+w>=S`1pWg zuRw9c>@4*-qAs)2#YWHhw(o2m!$rh>LX!^3pSj$B#)jsik zsPVbGR>RPTL$v%I0E^xd@9^VE2MYq7V=cEfoZs6GYsd9O=o4||<)u`QoUHw%i_UHQ z7_PeiBH3wYqKwCl=)&S9YczAW;K{`O(X+WDihf1Ug*B+&r#HS;r>41L0s3H=&vv5P z3T871RUV_rAmT`rz?c==h&msHRiE*ESKJ$2@tXg<|No1vFS6*|*2ZN0%8qt9Q*_oD z+?CC!+XEb?m4)4*vL5{A@)YtRU$|d{0PHkstObiQc^%}Btm(BHcS;5_xOuT(@gSs$ z*@`KPup+&LZ7_;e0#U0)E9aw-3?3a0s7ScXD_;AX+)D-mes6hl^B?$u)v-azwsf&g=5$ zsbFKS@yJ6u>bMA(!!ru4jVXqI$9(0TQgJLQ(US)&AAG(f;ne@Q>&Xr<#&YCOQOZ0L zF$rX8iAzY34Mjq&3A&R%-CrPK?AiXq3&z02`~i1ds1V)+d@=X{tKDR38Z8-|%b&q5 zcNob5*E(>Tbgtbq>sTXKe4tZ+rs*fRu?wwbg>v^GP=K&riBq!bS15Y1HQBK; zb9GRpw^T@~!BRdV8Lx^SRU96LFjt{h$^~fP=K2=G=Qr%-LniNG0G8v;H469#w17vT z9Ven$%V(&O0WKzeXIwSFL3iPDe?hKp!WunWp2cMom0D=2bl^yG5LRU$2m|q|hS>u<=j1 z9xIu+2V8e&+J!7*&$~zA)=&aWGGB&ZH3=muSGoFA`9EhXS(Zw94dhwYtGG<)r>{j2 z+aVa~%l9}?%J3AQ`c$Gvd}Qh4@`SImkE*+bReGRDRT9%Gk~`5AIO(zYe&SOHBG6ys zfEDiXyo$&#q;+JDDL{9&Ulm2lJmzCjTm@u}Os}oOD^e?VYsVWrZbjgAo>Tog8Kl0^ zIy_Qd?9p#ZvtfthxEGn$vwNzcW-UCqEG2VD#pTF$Y5o~l5P0RAHk$02irZ`*svbli zv_4i)0d8cUW6_T++WAPuK3y=vCzS^|^62&mi7k0s@S}4!127x|?}Pg1Y>HLE1&SB} zp8ej+=OywE0sHe1h7;d{u0k%18r5*wH7gsoC|psFYi2H;;uU_fR49iDa~Pvog{p;I zo?VgwfOgg|J`vQyR+KlSpEb;bo_uTT%+xng7oc1J(d6NeViy-;z2DJF-4U6^l|}}a z)LTxYPQn!+>RJU!-*VkFt9tXZS-3fx%9g%+DC7oH2fR&1bDggbVNKi=HlB%Co!0#N zhfOu9E&NZf&@1DQ!J_}F@yh0K36m3x&ix}@wv*d3lB*|UYU2e?Uf14V9z?ObwAwY* z7YClgCxG)GX!5^){o*;-_17AbFViRvq|M?nBN~@I;`P~?80#4@ErfyDdqR<)RV;LW zvQh_Gfsfl*m{W=}n;#nF9PJ#Q?P-QuH#cC0YcA@TbQTWY^Z?@G;y$(qarct+>lq@9 z8~MQSUq<^R z!VF9wSCGhN`6VQZHjfHlKe&$=C}@?K5b%1S&(o+CNQ-ip3bz@VP5K~dx=l4sQ3@U1 z4z~I-7S&>_>|le93a9XO{G@>+`lRt9g4(vVrG zR5NWJ%r$EOf-q`NQ+^{c^x9}r8T7T)U2uX&T#+K)$9aroSO9X!dLTQRWOgP3E?EJN zd-M{$@Ant`?P`U35E-(+CRztNSpJ?h{4848{a>wE@@f7RD4);^98el2jA}?MhUTJe ztg~j3F{5g8Q_rku8}Q_3nGxD!>_=B?$XZ-`2@Oq?xfDHxrP%^Poqsnl!>M^>b;q^x zaDdiIZRsi*zcV4c5y)PQD$Gw(5&`>_I9q?F4ygL!N@*6U*oaML5{DPFWpY~_ zzp2=kBi%tc6cV9-^fN<03Yn|8aefpv!|R+wJ@)9ezp+yFxklnY0xI)(_s+)X+Jq8B z7JTFA&mT>(d?!rI_=Ys^*_0%2d`ny9tRhJ6(wgNWyE6Y% ziDd6s|7+MqdPH{to=`@qlcdY!JHDX~^fYollJO*qwADIyKrLl@t#YLci;PkzE5T;) z=`V%jNr@gbAP`8kg#jgQLwDorFy3VK#I81N)du(6LV$O}`e&v&fw#QhnTtX$@Ww7~jij=t~ZtEwEfl1h^pGIV}fD8T}{bfqSn@yZ+i`HXs? z&rGzCBZqI<+#i}Xy$(%P#YtFK)BS@8tmUkZf5dw6wRGSE4nK`vb8hL0xL=b410OfP zl}Re(g_wJoN$u?*e;RokdJpZ&>oy*m)N72m?=F7G^lK^ZKLB+XY&2xAnEAX;Neh+I zvHN>^Dm8yz>h(GC*dX-sP}!r1#kCs1yA2%9WO-h(+L+F=vwTY~YPpRk?mf)Unvs2*89$O>sHL%-_F znX*z~^kChENB?f@bYZ*yZHL&-MI5Zm#Y7C~MJ~b2U(sa4G1unCuNGK-_V@3rB5;6d zt?8MW_MB!eA&mb3LcUS**K5PmBy-a<1NM2kwz;a^rcUs$mG)-X&1cgEtqrfqj$acU zEVFYO0d)&tmY(;4{BIZ0?B3kB@VNiEH7SEO-toncw^%gwSDo2D5_MDC`?|WutJhuW zkG->5F_5}(L}~2wC5@z8ttEtD#vhDbpe2}+Omwnrlxn8u;eeG5-jPi=n!>G=C6Hk` zY2}>C-ZXj6s@j-@<1n)6D7^o+0(x>;^J;yQ{me!+Gx!#o#vFdOI}NjnJF3Qfd3bS= z-flG;R%9e9e!^Y;^~0GnkBLVkd#Zpi12#R{a8Ds`Ee|Sqc>EfmXeP09-SAS-qB-sB zThK(y-*?dSn{-p7jqMGumX0f{B$(&?BEUH#*FHek)5t{8VD~eO`ylskjepik3(IuQ zo?CpKUcy*-Dn% z(#JC=yL?9sPhl`aqZAvaIv@x(oJd9t2)B+#NV^VI8lDhIII+z@5KDuXGr-vxTzZ7T z?*=s{IgK|0^=n%P(L49hCw>(u9QEKxC|cS*L&9X%gw078<0os~EseEc37e4yZ&XU0 zWw9~*1{b(mU+NKVi@)^#(Sv@skYE-BkQf2SFCmTterZn+!L#3X0K5I1(qQGR{{VLr z;sVx&mF_0yI)73g>GM?IJo|}DEuNAI(_c9@jq3aBZ30YLKObE8rn-pk*$L=6X#1V? zsVa&YJmh6~F7eZpfj67WqQPh$dsiA%Dc+iMHPiaQ7T&WFSW8p_xwCHN+h-lR{nlIO zzn9j^Hn+NRKEXYc>TkARAX37I4GCQ0vRi!CSaBsZ*)-|k)n7if+;QagX=g2RMU)(- z*`u6Q3|;%$#-MwrJulIy>a_yQdEsNalhN|>1h7NOq{q9{7m7R@D zW*R`{B%dyw8vTrgdq``{a^**^E>jJ(-gcS}3i;r;QuWXA_lV`>w2+*u?#jhYV}x4H z)L8MDw|T8Yd8UllAJ#8wwF=}PyUmo-m}q$4*OZ6|B&>af7*vDZ1(|$SzrWkYXVERC z?s?aOX*1nQRdSS?9jWQ;Z;xa}WzPY#3kwUgWy1RN&<(uxZsqvR`#njx zaDI(mD=L2KMIlNYg{_6sF;!_IfsjuKeUdU{l!~y_gW&S z(RzB|ov9qn*;$4H6uWhQQKohJMT2hrge}a%*}~UBsTthTn+CO_(G;P;*S7dVv z1|KRUQ8K$bo_-laF4HzIdqp0wTlQ+5XRKC1+9zUMhQ4TL9OfA+A7TZ!a zp^ikyo~h4P6(nF)XXJwXjZ1RXxOyAn{)$cZ8SJpsG;Xr#uZEW_Hxe(W*2uNcHo(j8 zP>Q=OVed7c{v>g9Mihy@c;ACXvmgcGfW2-+iJnR=OTQHmZ1##hacp8FIEt@_4vZz4!YhACKy_txY z?@9>+P=xmd?e00stb&4tRjF5fKVUIqXhe`m6H`cdiC=66KiuSI6^F$3|J-9ZeeLz# zuWkO>zJ$b^cU#m}rg!o)aW@J!=~MF>fK$U)4bqX%l`_55FU9Su=C0ClH`q%)eY+Uooy76xi4GpP0y99CG5^%_o(^9X8NjX zASp31Lo@8_#@Y7T+Uo?p%bAR*Jk$K|e4=Y}KB3UWWXv}r24e?s> zmTI@(4IgmS=FvvtS#ocBZC1tSl-(>?{U4bP4eiol?~BC8CbJ&2VyY{hB#NNt$i~dw zQSSU;l^u5uD9IOk0aIlVF`=4|vE!c*Le)t;uPmIKTXCXDv{z@$>%%T6*EixUKf zu@_A-R^UluJU0bXD{SeV_@_D$<0hRTo_#y$NF8rAL&9%wbctf9Z78D{D)mDC56Lq_8S9rIyTSm=*QL_<@Ql{wy#GMfSt9N{O{$tKm+2+0yj_}Bzde}HLu-;)rVT!$0 zId{bFC^sdH5YV*MZk>T`fk)6iai*Y2r+S#5Q2o|F8{Shli);Y6OWRBxzx&flO<_v*(#9smwYItiVh;4a)X9cH@Q= z7``}@G%jzV2RV#KLh<Nb_o8jGb+~L26p$d~PcVq25`~mfP?@5xp9~=j} zhWO&sKJ_&t0P_m!Bi+%2D?-dcm1iFRvYYLQ^%J$@Qqtv@69H+BMZzPC{Ka~%n;&+N z&B^Q3pNQna$W9nv2w}d^nx3&4vp%S(%t>VFy6F6xf$(yt9D}J~g zHZr(hKi6jF&lWTTI8E>c@Mvt-%-$>6Q|m1`=hzEOG1TTZXOwX_Yc^cG-gbgFV#q%% zd}p0X7dBQqpD0vssub&>Dl&J4HDmwOGt%kH1=DoDTou?ZTD{O{|5)s&vzeG5=8qI8fKdPBuwthw%_TOMP??pgIP)) z*aq&e9Z~R*Xxoz>%Mjd2JH8<&mrB)?VqfRo_jB>{KU4ARC4DqbuPM!oTseXp(`FkG z-zo*oBHvH2ljSrkd=&Yh5e#-!H0le;D-_3nepH4%q5Ww2hNP!=C$ zU{pb6AXUgFtNgHQ+ZI>~jf`yo5+Fn`OQ0H~oAD*KDHtojAM40ZmjaWcCxt(*|Hn3v zxi~5bbYfIBCGl99dVv>Qo_17{idA=cBI{>H?EOscn*GO8>XBEL#7Lcv zAqP{(^u~WGjAL}j&RWU(Z~SIe?#}CtD@DofJCyl$3P!4wAAH=L>N78o7(LLBFlwhx5IWVVv@rtag!nK;K4>mC&VfC{Xl2%cJGZP-$Wb5D^|pC=Hr&N zKhyWbDH$ZJ`Vj+eETt>RY+{xPHbu=E{9kFgP7*QG3$~o-Fuly;s0{BrO6!=gA$PQr z-Z#$&FMs~UTiUvMElH4tUPU;)?&1ZA+@>!i`OvC^LvZC$tl^jq9QnD@2R zB=;+9Kg=`{PEo3ky5h|bmN2(+H|}gIxP2s`2DZ9y*Rt2R4b;wqBv@x4SbR943Gpbl zmJrU}1ceMX+d5~jK{tbNP4&>xljWq?x^kzf&bkpGnWmwb)u7F1>K+1zcPE~Zeip%he+6-=47lw(sF)xoCr>6FQ4au zzS6OLqH=$a&neiiRAi8ocg zdw*5-aYb)mzm?V@tyagk+nh3=ZBStg=PB`+3e+kr2I?V+hoZ*{tbz%t0TzTRmSkeb z4bc!&bBxYzx}9#t3D8?{Pz>(xnT{?7;Dt}8vBD2H(KtEVyL ztJL%OubBmERwx*Vx;xh=y_&53`QA5m19+zqlatpE5hJW$mSxz2`)zDU7U5r_NgMau za~AKl5~u#fdtVc{Btv?U+h0BW24?SwZk0PN*vrENF!A53aL{AmRRccUT_{19M3YWJ z2h0;7|BD^pr|flBxM)C}FVbIFvoHG6$Y;fX%Ias_Ds1(F9xyP8SCbLMuoFVz<_v4w z9k8<2?Ns!zEJM(sX+?EkVMi{eI%SYKXp33P+^R!eN1`d=r7jlXMDm|iSgF(M2x)<9 z=vh^k#)E)ZJi?r%MnYSxb-RPL@t~Q%xw*Us#7ITXA(JI9AY;rkTLLrj}Fv3_~@`9HOrc zF=!6Gz1`S#?@jFJLq2f{(oqTdg)`%#^z7nG?{3N;`le6C1|O|ATtQzzKcH>6*3##_Dy7}~Z|1giG zCGqVZh3bnu{)splNi`*T@aQ+#@Q=!;iULv$GkCeS~%}2ix zRGgk{u2-c|x_neBuM;7lZbPPwneVrnD7fZMaPi@&q~gUCg#^a$Q*}m0Jz_CmSEhbX zRJDZcHQ{BMH_Mq+Z}GDJ z+(_ox1mdw>^~GD}^4KXG;Q-q;S{QU6#@)%=n@`)0{aSL{7=#jce-S8;FpjWagwL%X zFeJy$t?`Moc?MwGSuGs5odijh`Rv8w*w0%OtF7{P!b1@$Ii72HH&xq5`N-HI2C3Jn z!otKu59amlr<=+DvejzHtga~w5o5>n^y&eObb6a4!qOVv(hZgt1R_*Au8bK|27KQ>WpBNNf})0Vie ztA6SEbSbp)oNX@63YOo>24*~P{6**VbtfD)K<}W+K|elG_#djyf~^gx%htG4+}+)R7xxw@lp?`hiv=j|?pEBT zXmNL!0>Pc)uEkv^d~=_fxj!K}IXh>sz1F*9Y&t;`TeMq7uNmmH#n;QG>%`pQ=vosq6j z7aluz;Z^rb8$sDTHzEc1kola{{T2fWeCb(PYYZeW&tf~y09A4`cbDi8t=Kk@s&@4( zg&2z@{yh4T9FL4jil6b750f2K33W-2D&}Cz-CaXr zN&}-(26q^N4%lnciyK^U9b3Y#@NiAqvDO@2O$-KRij2c3yTIWOVfj0Qpwg+WL8`$A zCyo^FSM`U*d<*^CZhBg=hn)MnzKMTv)D1$H&npDG9*QBV7aVcS7Fs(GMo`Q*>Hbjz z)*FE~?s2?wb}Dz!=T{&6x|Een?@$xBy-G@62lj_jSokk@k$M+$)cc-^>KxdQcuv=` z77PP++ryj`E(R4je=P)e%VW@p@V~waZfu^0XZp98wnVL>p^TtY*!#lmjz)U9qf!CC ziaw+8z{@RM@c<}Xa^ zXE`4yEjgR(A3}Un3G2Ur6mYmz5z5-Pl1ZmD7y8*h8MRMM?h)|BQO>r8)~ZREoiorv z9oM%+Vo5<4W6<_F;>cAHV`@BxG-N0oUsWjf&77ElkgeE1-?Q#jdu%UCq8@*Lq|gT33jBgjJmqMK^AYS6fyWcs6Fw` zYv`9|Y}0`1uz|6_o(n6V%_?;#Eb^tNcw4Nd1NMRY%iRLAh|7`ZpW|U0dD7(NhO{ch z<6+Y(_MD=QPaOyUx={Yp$QN`o394>+r*X=-p|>F6o_68(QAeK|+YgXbA-HoZP&=4J z3X{id%S9y@9Tmyd*!cSl4sql9W|s5Mgg$>2sXmiLL(R2_S^L7!qjtW%2 z@L+xWY&Hu&^K&&JTccCcBzyj%*dBZW4H=4opc^~*ZoifHNVy~XxVD__(KL~zJTaEU zEJ2;ptw`kf=v};2kzKqL3|R8meb6{r@%y{3Au-(h5XTSHZ%-J9PP+p79rN3sJ9I65 zQa^EOKg`Bq7j2;vo_}b>KU%1up$O}=pGE_|byAP;GY71xCt)jkr%yzBEPkCKTpo^t z9>krVktZC>5~>PPeLE417Xtc}EzE&u2n0ES1d^TWP=9 z{-<@W?NC`F9$3ir+Vy1U8M=~JrmRE9g@i!4WAze^;D7^w6VYU*YPZ1niY{c_-;^2a zjJyx-VGd4cs+@loRQ4#8Pr2=5m~GKjt2rfFNBV{k5Pn-L4kpz2M~oboh%>fOY==^m zaiyTwgx&Z?s?6^fs5YsXp9>SwcUv|@BDcGj)ecCKdVy3Y^!7})Ys!pFm`y+f&T$|G zT`5;imuW(;)po4M(X?RMUw@2_l5Ygst*Kr=*5iuJ{YEoLQ5+&kgcWs<+~`=@-P9@; z5k2L_DwS93d(v+?A6`H|pNXyb`rGpJ^L&etu|0zac&s)i62n<(6b#bz$Ly0ts`7eK zHl*vu=g^oYrWUtn>8OHR%$JcLX$A(ch%`VRvlzG>8rqV!DdSyQjpyr0A9F?+omN$@ zA7^G-SsziDF;eL^lcr+A!51F*7|eiHt)xrSZ|e%lV@5uIxhpJaJe^;7z8rVGb1FD0 zW--tZ4>%=22WS{ldAbagQ**WFoe4VH4ur9jq(zAgcB|oF#g0a$e$hAaw04@`} zRnXfj0Ois)9S!Kbhq$>uozB-{f(G$dYDWD6+{?X@Skfh@5d%84Zw;st6Ut6o=Ivk?7bZ#8El=Dk!VgtY;DxP$!m`%tB zeLAIalK4HVVFSt4l^&t>h)yD5Vpsnbb{v5PpOP*G(|AT1^*TmWd?&gavHBg#mRvet zj9X8SSXoXOqleShdxEa2JTP(s&8G=;y5W)b@lO5#I`<3vajH>4X<3i!S>* zAu79zKQ?JIYB{<@8t{+mrN(s-BMjv*e5m?WfRv9gC6-MNjF6N2iCxU=!h!DjED+6& zA1LTHZyU*hI3aaN@sz8*JucvUN`E>SY0b)~WFt4*R6<}Ti^65}J3XO-+XUJ~4N%g*sS zhRX#hUw&(o4`?WE3t`pvGFf_%waJnjt0#;rXsv4t2!D0c=VnnJkmO-56G&)?gr?z>W-&PkP?b zB@#8lsE!khnCcOLhdXN6Ij+Tt~DalWKw0WXHI0&im?- zHEXQ+Tq+2Ieu3L)ygqwM2fIkQeZnBsUqjrqmfIdYM89v@WI(#SksL%*0-Ym?KX(7T zum8i7_~;Dq2qFE6p;)t$Tw>gdCq!dt>$G@&=@6Auzw><{bz=6*%6>_SD#QpOQUMtw zU1`@!Yay4hf3O=OOC?y#?mWMMNTgA$h_bA#BK6NZmolg+A-@8Jv>PogZeY3;0Wlxl zRTo$w{cio`Rmi=m@KYk;-jD3aC6$F;SCPXfcu4qq;WNbe^6IpO{$-#Yuq?jR6Up^& zG3U~mUnH30s7O|sCBeGPr*;WG_vj)xPV$V=35&U^M9Vz4!Q;z7acF2L8o`DzB+XE3 zlQw>-=GG12anRv95ii8ACPrxgEW|n&FboiZVKE6Ln)&#AfWC9sK$tTj0#n4ukooz# z!C&gQnHkKi6sO}M`t2$2c7VD_9AJoTIa!4IO#orzio9>?`)4G2J1zgLvQSDdEl=r? zANVRXp)Bq z{e?4{`d#pcvld>^};u}SQM ztiq1<-UAHp@!Gdcw_h~1TtDO2Qs^wsa;4wg37r8Ny^Be1jfu*Mqs)c~*%p**(h#$2 zwkob$Ez4&M3yUTxpLU){&r&Um;tv?GRZDbSHvH~ zb{tSg61p{7q_Ws$1I3<&)Kjf5)gWC^XI z$8F4pGgEV+&D|attAP`)aH;!sx$$4znkrxY$Pv}XEI-5LE;HO&`O@a@DNAnB+B_+Y zao`TmhbN?~8?3M3A9}{_+J3%vk^6Ia>pnU<`UdUzHrqKAm2yH6f7G{BmiaxZ-1)Xy zD~&}{0i=dUTJHcuO-$!6K22}<%4mbwkW5R}JB;mR-*n{wJNo?NKiAw;ziO*L9AJ`6 zn8^D!{ARAc1z4!tAN7!M>>*xKE^B}1;F3GkwqDxfr<<%X1a(ClC9JPZ@Z}?n0io#= z2>K`TKd&@J^Wlf<{q1aEe89U0cSX!yP-1###r$`uj5jMUaU`pF$_*V-C#xb2{@QdawEcvx&Bk-?bor}h=TAaGT0_q;R z9m4RbD1>Ikh%K;JU}Z?fPJ&W!+vN!;1F%m_*yz7rCJ-SK@`KsU#}*cT4SUcktB1?k zt|uZ@dRg~c|5z){xb#mvA36I`E&%7U{~JO-^mv!XeU;j$un5C!;ea0c?!Qnw&~VAS zZD5gQNizi}WAB90b+ynISKemP)t0v9dkWlB$$`DFf5xDCln~VV*p!MLS^;$2LA45B zTuQntxmuzwk7Q-#C{>e3Q@K5}N%w_KItt`^78kl?rmjn{wH46P*$vmj&|g&*8A<@1 z4X@?VB|@IRbYrRwZ{~(qw~p_HrlSTw71@G(wkqGOmjq!V(`Ywtd`|TG*TdzG8!Il< z>ZGA1OU6bz!b+dlq(SY*5L=xOHSl&i%N{5UHtcIAbbE!xiLGjCP-m z&K*Ca^Aj+@A?zkmYPMPmUcXgP94(YYi?Qn_lZ*3dlhmHMCLW8C87)L1(r=glU2Q9< zosZR?K5zaFd_+IuPu?IVjDyh0kc$PM9eXB(F#VUD6bx@JOrxxGA%B^_Vbs$tG{l?}vaif?>cnSEDD-pQEX|MoLh1zejoPv4xu{wVoI2@s!)ErT(@?^SQ8V3bJC?i`V zyJeaJ_Eg`Bm7?vsoC(fZ47Jq4YFMc#dyHjYIQdjPiYC^iYkX8WFHXoZakopxr1orX53X)t0<*XNE`;!|5@n;R$a1VD;J<_9j1AE(hpH|ZPcCDsvon}8UPp-!g~ z+HT*hTrCfX5LRw-n)DHfF$7pD;ch7q__GC>EditE%a%V4mLcqpa%`(56({AO5#;_! z>N|o6)n;&-=6GMXPwn(!%Tr@A$676= zp4$2BtPibQH!6A$)Y|}YqBvog&?_JXtK+?3F_?L7x8V^$8sJ5kDA`k5)lKYUaY1SIjQPZ#+ zUDm^c?ygfXm+S7tXRGeW*!3P2NcX+n)fC+(5dEOr#`9PFT99xQ!Q8Gogw6(gfAHkG zU+|ONga z+g@go3ifewkdsSasC@^#uPZ^&*=m$(sO#2*s@yTegI=$OY29oMi)L2G^LQ z(xHPHA9O(3rpOmKAbiy`k0i9$#^#YNR2e5fbeYzw$mY=wv#3bi(aT+Y-wZm#oy}ki zjgEuq)wiHC-QdV67=0Y)!U0ocy(}f{AA=jW!3FLSR8qzycb(&o+{4g*meM@XYF8@R#o`V%~ z4>8y-Y%4qjKnI%Gpbi>Q-Z$Ey z$n92#ZG7g$D%Li)FKE!8P%5*vyy5CmG@Y*k%B(f4LR{z0t6K%zy1}dHR;oTw9Q#p= zb?k5{eXiRFg9BlIYe=WsdO^m^D9}}ZWZ)zI2t3eX3eiraVc(rU__0hd9baqPln2dQ zZS|UpKz=Zneb$K(wpk?v>-698Mix3)N5A8XJGycu9M^$&Z%%J~q+@0_FhH3)Oc<&1 z)-H|}xMl;d>2o#4UrVClp+3jMn`54wUMyT{qniY=G(yZDDPV}N4x!0z6(T;SSE#i( zAoo*lxUAS(H&uMTTR(T52FqvQJ4m@~e-xqDFh?~M2=+Q=kKm>#uBb60*>vuz{#&<@ zcQHB#pihqLQPa{5G1DB_EC_ww`Dqr;ra41II7!T4`P8_0XP?pFZ!kA8Wi$KfS-@OC z5-#&Qq<3R4b4y>922q{9x?={O;dhgom zE3K~t+~cnF*mvizozm*}7O1_;_FlBz6Nq`>1uAy@Q~@jeZ$%@16J7TR&PP1b%Y04sK1q6M*!I zc6gVGQrIe0dxZB^czw1)@cdqfw^!-S*zVA=x=rl%^M}i}VKv}@=R{BM!7)NT%64Gk zzsE*M%Lpi0TNpKFjcr3{KF>9gxF^Yp132T;3|HNdrb{5lR1|sGFM{gV7ZCo z9b%Qhp!}Xco%br2znw2s3uGT`=CfbZO_p(R-%fh-{&BjZWsWT1a*~>P$H|0|3j>VM zF?56SBuQs9Y&eN~NcCdY4=4`OptsK_;6^T?O=2U&%-90H*WMV zW)08}5a7nv4WB@sj(q(xgMXg`B==hKWUZZhh4#r&8@Ld;!m4YePzrYLqd4}YGMC|h zZc!4q{^Z(^`O6{DoKd|N z=DBVk!h*QOW2E=Ydwj0rsIgy%)^cuK1I=TY@GLo>=86z}t$DL4$E{aZrrzX@aX0_x z#{%9Iw4mwS8jzQ#G$Vw{<83pTgw56<-pA3*%39gI)B>2t|49_x6#{{;srZ6M2ZIxY zK&IB!Pz#vQB~;jIc+G<+nyeenT=_0+Quo>F_s67lGqu?RJ`M{zyheuB)BicZqzi4c zRMb!{1FxqZHQ>pha}nXDYvQ_$yH!N+=<#3fcL4|p5rFhXhDoa9c0b5{+KrCqs*-s` zFgdu;{M9r6;?}|_QiY;hK@J$t)#`VL;OJzDp)2HKNeqYAsvsuMKnQ!HOzy^L%WJTC zJX3H6AY&sh4l81Rq6MCr!BJ6B;oDv8`r<^i)rd9rz4;DTJUYD9zt_9i*ikVv%BnC_ z%|njPU5k}StI7PMPd<%7B#z&)(t1<~cayeJYBumDuDb!JW`C-mE#!c@S zj>1&Uumwo*4y*H}2tS!!GsL5TB;TQLa43#lx zD5kN*DXh895~>QT1oJKEz9AS&*Rdao&Xg00I1N1X4^>P(vGVU&C1?E$1v>fr{eXCUhJx#RS3O2o_rK&TiWS|p zk*m;*(wMU=Q6fCj$(&d3*-;V}O3Wx2mjR>yb1%ynGDs*L{0}n^cGK9A8ZFm@QysQ` zwi{u8C*m`_ZKj6?DhSfZMu|ht@jY}SSh=NRCE|J8Uv1P!JIgrn-7(*FZeLSWnHt8GPgtZPFnn(izqQ~5=g9OuzVpSwJ5bp3PVENhe zD}V)&_0PCOh#ICo1`16(Um7WW9~M&8$<&bMM7JQUN;%!qr!iG)!lEO|h`@5#G zA|V)(39sH?eK(+Z$N_Lx&o7(lb2!l1b|8f}zE0*8*c1%bIKAdL1{zh-m%G1nm9jjB5=CJzcZUNrp(V~iH@yToK1?$TErRaa z`jGM7ne}W*uw-zAVQ6$e7$8V+rso0 zJr2;7qkKJArza;Uu1)3Gy2#a|l!hEUepkp9F=<&FTL-ix#x16b!4+kJ7oPV@5DIPw zKklYbvSzosyIyo0w1+KQfkln9UE|b^B&6uY9GnUxvBGydB44B?2(8r5~FqD;)l(4m# zJnZOnB8*OP#yoyC;(k^xi$57TK=Rv!juOcl(p-a{;o^I2ZMcGGk#$-PJ^S`eD_Q+U zj)t-XqDF@I_$%Q02ldNwT1nS>9?dP($d!BTXPn|eQNn{$ppY)AeM3&Pp&iXrq% z-VXWodOmgUJZO3%OdN4Rqtm<2U7={Pdz?-_UiunpKeFF@_JqHE*>f1S27m$5q~yKa zsbd~w6KQ=b?uqk}QfXSd`*hKTaqd*6B;a~W?Q{RiKtz)+C?yN`h&W7MnhCJLo2jK% zK9xMb8uK58!H&dd3jc24#pL9;BQDS=as8mcawV(owJL`I4jw7hs|sw5{l<}??`OuDe+eQ=ysbeO ziEfl_3|Qa1h@Tjh0|$P_lsaX&`HYz-?It=BcbNc8ArLC>eXwu^X$n`xmac;RJDzu* z=6&YR!nB;hWT5gbNGV{R^}=8Z8kO^ADCcsH&Y+Iv^SNoI0%~)k&C)j)+}x2(Yh}qY zm_-XY9wbff2w5L$oBvL}r9=Y!S{ zQ$5%vBw778tUk@{CSH3x|c9FW7+Kox%jam+I8Go?CZ` zVr%m91RIXyrk(7f;Grw-g1*+jL+Pi-tav=d>*|h21I0j{MR_$7~Ui^#G@l{O+{C@Xsi7>r=hRq~r zzy?H*UiF3Spcn~7Eli!Ui03d6^}62-h53}VxkYU_i=YcZjK$jQjeYJlAEJU{x7G-wA`S1+Iv*T#p)?WeGmJ6*8o6HH_bz71Ekn zLNfMC@$Xmp+Yy50ne3+$6NPg;0{?HY1jb%!0qr&V(c8B3)X?nZo+yqG{;9KQbS~_;feFm zflW1EK)BA!&*lTg$V#!h)1G8!dvF|82hB**3nA}sUz(0gIG{n!$@F%*kiDoW#t_wr z6`Q!GuK1SQj#Lap4lqk+na7aG&Lh@~rO!R6##^MPKX1(taEJ+-P%E9LMaJPI5vkSy z;awp&eMloUMTAY8F_Rper7-dy^3si338m4I1nG(&{|Y!x69NBREES=`);0N1^(TCl z1-_je6On2o$%<5QA+uuEU18j9>}t8+Ix+6!XRn@!>nw)NxyNLwMBCf?^o4gCro7Vo zJL+?qeE?5qOi{rfHLuIT;nYcZ7)BK5oRH5?6Y>YDO9)6*Q8ExBp~prybWli$F@!e` zNU?_G-{a}OKxl?+szqoJkd;4#6}Ne^ROgr#>R*=r#}P-yl9yQ5L2SnkOjetUiIqYw z+_EHV#_o=v-$~~X7Hx>Puvz32j63Rf?0QvXXkgo7mlz57PrBr#<>TRb0w=zfCyh**t57r0(EFol@pQJ@<@&8iU2xCReKAHJDfmuAD6E&n!j zbDF64n9OJ^chQS;SUn9=el;B5ds6w4 zTUkrKS~3z-EOs{&Jr{QT!pE_`<{`I3GU{0XM!Cp_&5aW(a;akA0D{g~IfGX4ev*zVXo%_(n$E6jF3{YZ|80)>zH<1EP|%o_enKn6Zbl<_V05fR*o|mf z%_aobN+h1XArS66U%4aRa;^mgBvg-WOjnLVGy73cK;Ck!H@kDXu;=%#!nxWQ`*{O9C_zH z{QPea@~vHn`SzHqI|6c*6FZC<0&9Q$uaq71H(BQYV!SPCm#;=X$SFAc2- zadOFBN=$O}MPdvB*3GtJYr`4URi3VYf$(D-RA{-DY-tr6KS__;<@V@h10%{}e1m~XL*z~I)rYRq zw_K{l2?$)s{kz|w(r8KKW}y_hp6(sa@>EQt>j!ePbPWo<7Qa675omL!?qtS6GT28u z2OkATn6dN-S-TXxa*BMce^3u7i%p@ZZ8gIYKZaGFumRl;p%8Fzq|yHiRI|Dm3{8vM z`p5cdQx)G#=!@haN_0H63FWl;MTmkq&=fB&V{Ubfy}3vsLqf7C$^sASn08~XZ;b5l zTVasu;E%;>5L5u_@vCn>o0O6f$#1bw|U=E#ci z+2J~`#dPd-o02A?>-uEEW+)Tob>7^$OUj|E%J~{Lx&M1l*TyF253*>ru^;bIxKFUZ zIvR4y$`SEv7x{fVXYQGUF?KcCE>Owwd1OLBC#Kz0a|hD=`UL^r!F%1z0WX~aPR{fU zvi|AR5){n6lq4^Tu`S{G-VBg88C(#Hv2)+d@0b&;k?opAZjv+w9+H>uj$H#ESNLe0 zAu0ZI`E4J0H(vb4&(3)Wl*m1ohvsIov_!G!v&s0}a zs-{y;;BjO}gq`H-qrq7;Gw%;geS_SzduB4Ghm^5A1`Me7XA zBr~ha7YRdfn&+YPSOhhR))=}tcNf{bMM+iq#aSKUy&`fZmuVTb7Z@hm37tQI)~|uH zx3*)l;ZO0iCIOi4C;6x@<(SvhEzU&AEKWe<2AU?TXff~y{5 z{P!8ww`g+2p*>>Ghp*|AzgPycATn(A*T#gQ*@h;t{N2#}q!Uzi;?E+t_e*{C^4vu+ zc=oI-Qklg!W@d_Dszu8FaMiR3>eg$nK>=fDj67&U9>4zv$LQYsiSa~l1v)g@r9XbR zE8?=%=q>*P5=3-Npn}C}@FD)L#t5y=L`4s|amaJt{NAou(HPF2VHE3hJi0D%&CHU_Lo|rDEx64_sHNbLAZ>0p zg4Q^UF))}tVNzcC_+s_g!R8Nhd8Qco)YHQDeazP&dkmQ!I~~xMBWG_lkVuznaL__s zC{W%l`ft~iAMgURcs%FhRr~lHQQ_3g2;siW6c8dH408?gf~%n)PN+prj6Z{&&Gi@N z|L2Go^p9jex9>!|j#1pHm~VVTL+8J22fVS^x7Rk&to;~3x!dlK*6luy9ZLtF8Zdce zMMXi~O`W&NG8)tbWWM@ohOmB(Sz4*a!zbK6iMg%S%#Qo``VOZNgIAqcui3LolBsSt zHDh13QD*ln1f_~vhM-rQ1bA>a=2k*!e!#Ij9l~2|35WvW;>Rw#+Ha;9NvUi%W#1PW zh(+n*1x#22leC~6-95Y41#xPH+C$YI>us%r~(!X&aT%yFTdi?b z(jkS!JZ$VUb=Ocg!5%aK8%pX0rS9Mt>#y|oxoAWXC%gD&uZ)>x_p-eY<+dJ6G8;`# zq&z=!>63A{Zcu2ywIlZIuy7tlS z>9gl{^jiYihxV5}q5FqF6z5M%j31i!9?5RRW@^LXfD&uJGh#vukZ7+yRcp4CnUWQb~%?=a%#4)gA0^C7|sDIAj4u+>3 z0$5l0urvTniEa%#F|Ty|)&On)G}yF>pKV4YlOnw66%CX28ViYDc2zR1$B9#LFD6Kn zy8joG)nWMUnQ4`@S)L27|QN3~lM1CZf=wDXCbCKy=-;{5iZD@tL58{qqb9a_4 z5W2%U_O3G^1~?}Dc~W|aE81x)`RhtA++`EYUyC15=Nbp4%3;l+`MHNz2OCrvs&0m9 z__qR*a)~ekJ`fRN`k6-`nK+;8mTPiit!mE?T#$j`ONgmpcpwu-zqq8{7tGwtKg5R;|? zm>NDcNM_AV>J26W{lj2fm;ezhSjXk34!cNJ@2p4AtOq(tu4VYvyxT&*8W3T=blJsN za8Muxvf`=~u752y;Ys2k!v*kx4l-YuyKhtpoOL6{+7)gOr2aGOd^12%>~tY25k( ztf&pH#{UoRjTj@)xZRTpFUEJbH%rvC${QLoK4g}{d!k|y!lrN{$rOIl*y@BTUq zr+MFlC*t_bm`x{=(ItFdL0?{|juJ6?bA-&Pj6ZW^A|LuEDJL?xJtC2>Eou2@JJ>>J8kOz zqFcKeL6n=IbaR7Wgoo6_8TkbC8aPUep}5a6IEIG~-fvkLQ z*M0x2rL0FgY#sjI*eFaT^Zt{583E+;pTpOFD26Odxha73IfZnPt&Wl8k{;T{TocxB z52@Hb1C~g1iXRmQd;#XlsUyVQr#g`Y9PEDtS2OVyjIti)ZTYyHv7ZlaAnSf7wJXnH zMlt(GQdRcSqB~3=DVN&SpS8XWo^%r9 z{D6?|t53*(JNBoAHxRR-6)}JQ$G{=42R1*zUVqA!_tg#B;aV5uUWa}1>3@B`G; z7DKvAg37S+N*|Extpq-zZ@~>CN)yWZFYPXP(C=5AHDu<<(QHAijT{{hb>xa5;6%Bo zhGD}^GX&_mY33|@G;0;lZc9(Jcdh_#B;>Y)8$>4z`tXHh^E?DEOt2b$b6GvCn;E%= zl)hdR6(qutd$Y1ecfb7=iJcU4<`zfaH4^nE`MU8E+TLzdZwG(jK$DAFO0$1=xEbV` zt#R|eM`tD{{iPGeOyMDz;1nV??I&@5RxXj0<387Kb5z&Hc5vCE)?n&35kxkIUfXD) zEXKM=DxERjQpw-98U1K|eQkyg-0*c7spn`YEM`&vEuu=j2+E00U9i13+GSEBZ-x^j zag}+=`^8D`hTvkC8r2cmN+aAX6f5Ygx9a%At+279|l@qJf-zb2a3vOu1LNl z8_BAbx63Xa`UPna9otg;-z#S(r$`FYd6vUq@GMAojL%*O2JAuB0XStt9XjBF>jvr@ z=6Iq37#RhWvCY3JQ?sZ!(fsrwSfyk#07ab-KjpliMoozJlv3Jlp@v)QyFCz>#CU*i z1+w--(inPO$!YTqtTs#3hW1N?b>Iknrp9&HKCB?c*@_^D<1~y0Rfh&p539uXhF9E+ zV7xxUG<1B7Vt~Ql+}2867l<=$HWZ*j!;q^nHVAUQl?wTBdN5_iNgXS*`37k}it*Ps zH2NK-D@em|6g)TPH{DZLjy;zqSz>b#9o<^H+5QRL*O(J!uJa>8z*PeVhO*QTwtUu;q|$4_&;3V`|Q+6iKCD$q7Yd^5YKB(4@UcPlYHN4 z_{#5VA+%lk5j01syJ;U$=u@!tpWwkZu!>2}LOqrR)KV~`l*3PeKf63!#@QCw1l#}g zLJ(>D!T(4J_#SkH<qN(KZ17V@Z} zQE8^4>cpyQf~GD~uP}uUCqq`5k)3`cbdmW6p&y&w+}LAA(BM|FuvR{MIGJFK_eGI^ z!Q4s2hPI12cXkcY*_&lFn8m0Y{Lz;vk@c0Q7!gpYz_hUlEfo^o{WvD1vbFtvNT(c| zn8zx5;P}ok)GZ(t-yJ>YgAQEEcQGneL#BH;{9xtAOl)oM_UP;easu6lhpAAj^F9o= z$*y%nv;#4?tiSaV2czMO?S|BYKkS(QEf&!Uw9*m&X=2AaZyi0@OCrM%mIA5ETAD2( zDwB8TvdMjIU2uz9YnI!y-Q}msR`!&X&DMbZI(K9H^nc2mvc@?NF|HmSCRmnX<_#+1 z#vq7D?k$n4dZ8cS%DM#i(@nPmV7GPKPtqKu!KK(t1M%cJqslyf>4Vr9YaMW4F}Aj_ zu_HfsHk)2AvIzeiZ8Ii}mD#=7d6T{3l5`E0?V|Kv(k_{|AYK{qj($_ff#zl2AB;AE z*aLiW{T5=vP)@@Vdj5fEn|WhGUHV^Ty0)hCg6~UTi$CRDig@Wapb#&-eGu#j#7q?7 zhj|I4J^7L@jF?AN_LZ_&>?8jhJ}`#8w-VkKWaz_^srmOqv82#uKeY$QbL;3dEp_@A zk)y>}n7Dy5bO!nP1vb=i+=r!1GWa2stDzA7b%k(qu?ERe3ST2|_BPV87bb6~eQdj${{EUZHdG(% zKJ&8ni#6fdpn2t2ySl!-8YAt%XS8R9Ek2+U!VO>-nDuOjLN9qR5#wv zpG?)nJ>@3(^=sQ~w5%n#Ys7ZgEV>eD5uMe3RhCE|e?M_nhRaLROG(%pX8>WmyT2~n zUAw}}2|@sQHZF+ii=rHSi?Z6ih*-t_1J2s*d=vKg=w;2@H-TfZwH%WbKS;-dLckss z#k4M2r)_q=a3L6`y(}eeO#+=lW*V!BnBv@P5W1h|92fx_jzbtgNs&I7ZXgsh2Gj~Z zcCU-HoqT9;zoJlSwUHqrKX<_5cy_iy&R@Xj9mZQVZS*_f?4y?YNMo)}L257!yKpx# zaP1@3%cdZIk9gm`I)?>+MGz-qI``U$+)Ly8=l&4&Ysn9ysB})eB_~|jF?zC^quDR@ z*-hw$ZHl1=6_xkh#e^%*s8kskp0n81M@g!F)qcPn@je08FWu!S6zwA3W)nL4r)$%= z?Ep`xKDg?J*u!3vd38nf4+L0Tr=G12}om3F=JQJ-E%H=(DlFwS)CGwT(+n@y-{na4&DlwrVmsrssehcm@pwaYo4MCov`oF)p;O@DgXx(D z3ID0w!g|O?+g{g3huUGy)rP}0i6A1=+7HQ)k!Tf@Q4|61OYU0S2YJb|Dp$FLcCt(y@&#OEeAQdC_|X^6 z{KhtT^B?inPLUyUSmbK4$Bl>oB*(Q=v1itNP#AwhBI?fX3gH{k7h=5zhSN z3&tiF+Z$YrFRD5`6r#8|DM~%_yfoE9_x!p-^@JUej+gunjWG>OKm?b``<4&)`mvgD zA%>&xfd)Levs^oLzexgdk>bl-CJ&Y-q)g`7QlJq5;8n1Ew;t!(EZ24{3O-#FK@^K0 z&cRNDOp1LbS@J|Fk`loh9FdKfy!W#-v8*A}rYEO~;A$SQXLnO$1;y~Xx{fV_y z_wdQy`bAc3^C;SrQMHkI&6@+=s}8Yeu8LB!*S@dHM_G-KFe;yHkWz-;01lrKUHMEG zP&vn4CRXdd8`p=TTgNp&m(ZP#RC(Qst&7*5E`@O5yvx9iI_Yt966%0MpQl+v?e^r$ zbS_g^yVxX(OG5CaCpkEw`oE}p%Z8{LzU!Or4(Sq+2I=lnK)Sm-29RzTx}`+AySuwn zx*0$~y1VXuoY(W_nHTc~X3zfDTI*+Xge8A8_o17sIzr-@U<4F+QAs7;aa?5%W01NU zG8dM{+>*7?ts@R78a;V;zC1bdgHbw%-5dBc+xqkk&`QQHIK-~djW1P)6vb)3h!zM|e z4mx2pioL(o+#hN-VGo!Tmb0jQMlVVqWs()8qiTJQnfjH3k?k976p!})!(g6EYiyC1 z3wyq#k#pGLXbO`72$hvuHT@NQa!*o36li;$84j_!f5sTs>1`sLPO|~7&SDIXLX+UZ z!Zk2Em0FPfm11%7Feb{oXnSDHkC%KEbvt(h8-I}uo3Wi*uz*0Jnk0t0oHk!HC+cQ? z{{kKB%VAjG;F$6ASwFAe4&GwLR_vw(?M}Ug{vWeGucT8hicNH{ohX+4O9KSWztgIs zq40RjdLIn3pd)4&qW{w`*mqVn)mDL*axy%(vxR7#;rIHJtm`ipG!3Kb>PMBre`jmp zTo8wL+NPKs*R5y?xsww6>A;YYXbwkwj{^O?tkO-Taz0RjuI_c)zA;XL)4K;#S!~&m zZq$E}`50$17CKon?7d9;dL}3ox$Iv>H}>yWNZwl z{2VN2GI5m~DN)>YrE}jnF*bkjNCySE^IDy$nV=;Q?kwH|_y;F)~w?|9h92Uio}q{3$)cloFt z&y8C9$FGw1#DUb~{HR)|fxC=tyC5rCNqdqA({zhGJ!26MOBX31tT}f9h&dRryYswxG z*19%JnSFT^3cXJFfc>y+*3MeLku%F4Cb86PgRGUkA8sl=P8b6GE!2Rr$N6`C6z!}z z2%O%INzC&KjrxH}EW%{)QUto1OSlxgcWsd~UEK{ic;aHqHMERAd!t5Zt_~{J#hr=vedjhb!$OC({I51z3z7Zrp9}LRUsjYR1;^k(4-8%^ zm3d3bQlpk$fN4X9aYe2a?+D=#fUZYK`X_>_s<`FdCs=7CWVlg;x;EBiN7M&`5L zp-iV}d{}564rQvRukWMO^aH=aW<@#3rYL#}#>!>120EzBreRPKzSF_v>XFc^}PuCh^#7miiCZw%84Xw=q`^;|W!d9gnTCIgW!D)cs*Y zyr+lbahuIG0&G8ER>~*Rgd!J5TW5L+V}v{_H11nBdg-)2P;ad)1jTjqB}P1(kxJui z@Q_-m$nU9_uF>)OT~qsI@DiamhZxz97@cTeF=8;=#NeXpQkfXrS|>#5QrTGRlA@l4 z|NFjMV|8T2Yc3xWaI$%Ed&^~z+x|#J=Wb0J*AY(K`1>QJi~$-6C!uE@pNY!(=N2~) zmOIve;LiHB-J2m}-dYEyE*3H<|I`NQ-;B`Bn;7RNlPAzE*w~@z35>OjW~9Q5_@AzO z>ulAFip$guit9%Lveeq2J~z539!4nFMsKI5UwS zSYlLY7{4k_?m%ME@?JXNqjJ`V)#FuqY`7^z07+@j!Xy#?c&b!Xc6$Eza*CNw2}aV@ zI%4CwFw^4>Wi9qPA!)agU|3_-PYqe?b^oBN%Z+nqfsxnHKS|lN zZL`6^@_+wed3q4nga`82vchJTWz;*$y?($q+P9{n1`}EYuxc!>PShP+4wp(a?o+{h z=D&pVuW_AyiKB2;>}q}NEWPUC!?#l9ETE?*bcUNWm}d6ETH`g7jAc%oFoFijho6Q3 zt-J5I)ZD(1ENu%1@xxoB2nJJ6fCKaP(Jvytx@UkPjs@Knh=Vj&;L=aKaJ1{zQ8L{p zb?Fz0M>un*JCLmx5DuuV@K@o7KQ#B}4xVCnm5F>@MDk#!9|MhpefaA8*SJstAr-i2 zD@m+)-!RWAhqi;1J$Kb|q1Jki`^D)E2RQ#q8BO&q*Yc2xG@pn3uJq1xe%_{AvnG8x zaujgxT}>ZA!qyO5p}zsM5>(^O9pm?6j~-d7AW4Szi#319Pw?BxL zDA7A~;T14XHior`E58EN4A*-MU_ft44S46O3_zeO(JYvd?MxxWjP;G}{q2b6O<%;) z*#c>R&-4Yr?s8fwVV0_Pv9=d%w0m;hRbUM54<^<+EGkV9t&#_?E)DlCaL}|!JLuW~ z7?@MEL^q3jS=1Kd!}?!D0smD?)ujrVLO(Yy@(2>+ynXoZn00j<|(p^9hZ z>d@vC$kVd}n{PFdL9@1r0lEj*F_B?sbxt&~H}P$ecy^ZByPGd_B`u(+1-|29G+kkh zGiZgX;r=B1uS@j`yRZq4{bNbVg~RUK4-fnaYdJoziAF#Cui_g2oU-mO2o(eaJhX-SL5lkxOzBCwu$4Z8Dxa zxZaL)ZwC@s-Bm*WpA9k#q#2D}6d1mmlX#%=%o z7bprnf}-W}bP$%V%ALfjk3Wc#9FpqorfpC*Po!KsOG~F)%RXx{@hSJ#-|;Ow`rh1N zX}e!K4}c+>w8sJx{LYDModzRl()Ctsz^O90xOZLSx2<+#qYS8Z)O)&Wi0XPZZeo+e zSIIxSbh7KGT(-`l)cg@xqI6y&mZZ>Qt%pZj20>-tWJc55^6Xd*7?W-_lmBU7*0L>J z_~%;Kyl~Niqldm*gDq~vBq7jgxZK;w>te?UN5)&VS&VqD&Iu zuLjfpn>*t2#^RTmf;E>zOk?xcNpH0WwehhU+HwA)xh6a2O3VL3cXSjfU3ClT!}nsq zLuR7&Z!jn~+ToXo)!V-avpo>#=KQ%WP)y9_%dugfuSR|J#>^0)kt=tkX@ouJ^4}|_ zPvGgUR5f3C?UBb8?ZKEF=8~dDls-arIpIs~ybT=`Q;uXouu;0G0jG2oiQtJSZwsUQ zqi-OEcZ}bhc3=Y`1mtCAI7?bqxV;ft-PKf9P2}5S-!LAPj+hQ%ZR}bnm^{t5(B11b z$loACtgaF=1q64ji&cXjJD&e!MJ4#17tdAN4|RC$hPUzCPzDAD7nA#8_giwbyGrjZ z4?M!}6~w|m=Mui&sa$1{^-~TxA6^7aRG(P|WAVX+vZy#yXVq}5^!S51ch|=bcKLuzd^~0? z;z~ao%&=&n^}G`+`Vm{A^2p(HH>f#6M=4aU$qk@Wpt)@3B^z10B+oZ}*?gbmk!!70 z3zPT%K^V3h&Hlh>5qyZ&#+5c!N_8V#EX4O}tO%weBQbRx;T!;TD9{T~8g6Pv0gT3+ zUP}zfRoLx-wsSq)lQH=6+w>p8hHp^i0UGvLBu!%_a zlrQghsq?zqk(_P)^^SlW4>7O(#BS)xSt&`gD5s~F@n@ky$-{$JA=?7$=P&B6^o-%@ z-QhUeGzEGnbrnit65AUO06xKa%`a=yrJVt|wAoJ9TXA_DE>gwhj#vISz~j}Co5iYK8q>9*%(P|Mq1AhieFeEGnY*fn>+6cGkuC4IX(^8C6S@B zkT6^cu^s5+4%b;1ZDF1QyCx8!{(3r^Urf*vs^$^Y=jiG0hdn#1VwaxZ0Jd}Z zOo6xQ?k3ZL{mb3Yl>01t!B@BKIf_QP=nND@tv^*6Mh%W&@0y!3vB>lkhH(LTEEP!FalYPh#?xmK4+S=^W}}ek z4l($`gC_f9L*+6p_(RWI&}|A8ti4X7#M2L=?UNIR`{zlXt%1MDxNMG7J`c}N{R^Y& z+y>7V!Abvt?z~iM?=;O`9;7^>62fDsg81P}rX@rb~YHdF+0<=A0O_u8x$e4#F^_y!5 zzFs~?_*JX}qC-S6zk%Gho&_Kc-CBrJTQlM|Kj7z5RC#$hSQ&M;a-gLDirm1dP5uo(P=f=3s?VL71Mma@nJ zfD8XCWNp55s>ZOh*9^kv;n+>ZS>6dkcFe;MCA>h=%&(dEAe^|UOxjNngFZ5+e%bh$ zRr|3YNvE^8F+;Jve<8J6?RHqPRfOSNJc>h#hN&UCtM^J@WS~08*mGJO5lHm~F#G|* z_c1Mj@#I7o=zAuNZ<{-TQWKu`ENTvu5(XlMRIdIr3rIedXwc;#Buqj&iQyN);PpX> zcbmI%w+%)bO@NTmV8y@C5=d;{D)r}z{OEk4t_IjU=0h-UdZ_7T(iCVagIK%X3mIxM z7LY(w(|t*u$kizUee-!aT>8cD2tT!sU_l-$bt^W0shs9@QMHcs80C*pjHazzrG`KM zQj`__-CU5-@L&$9*qCu~doc#?WWz;kN|OlYA&s#l0Nx~u>c=BLa!VLSM$hnGSsx&J z^k{wFNoPIIG3qj5FZ^Jt|0?*Z^d(MfdO<&+9TiAgN#Ky7-29pVv%&8!k)7om&nIC~ zAeX7oS6Qv-1|VG#g@uJL?yr*!mb&x>cAxnhYb_21?aT`rw6CNIu?>3;Qgil;Gt)94(ad0$jnHn%QzW0M39RCMMS6_u9sEevs`i zU8&RfR}d&`H2+uD*48S7@(+?d_4Ch($+d>Mg_i~Q_HggxT5NtjwA-HCy0Yc3EU(Zl zGv8-pe58t2gh>F%a1e zd&=&arV%2YE9(7~unRiX5q!EK4t3v@kJ*+OHXXd;0?8#}^TAzc&_jY@Hi;6Z*HEQk zVH5Tz@vN>qvDbM83E0ZLs7$QAGf=FbLp7oWVQDVita){#C79|#EEjMrFl^zK(Ksur+`-~|QDr{M_*MAR6b=_5Zd z(F>J=7wgO!Mwedq#?=#Qyx!JnX+fGkA(YuG(oZ!hgMseo|~rhp4s%+s9^Dqdjc z4Kac%Q!9%FfS$Yc3=7KntIZ=BET~t1N1{5QTfcaXfYAP};1a16;oa`XKv9Sk_?-Ki zjsHg9lTA$pNP0kK&PK*Yfeg1xN;Dyl1)PolHNHycyD$tqFa)+ir)#kEG!^33TEAh* zliYA1xR%7c+FDTS^&LBtu3<-C=;!tgJY<>o1z|UO*PgV94));asqZr5SN|TU2(Yn5 zs9{%6kx!*5qF+wFth#}m8AjF9-tU}EjwAGJexJCO<#^+fKNd?9%EA-M-12|#yvb0> zcsp(0%KMi1xx}Ee4Q}!JU^?G!rOsK~OQzlR_;V_a*?)O!&e|z!tuB^-M-veN4}%1d zdHSgWM-31VfEm=wa&#JPzID`R_+RcwwW2Li2>b8?;Uv~+<%PF)1%PVk7}>0=b(Mn# zgSKZxIA=oe-5l@Fb`>1*8ISLXw7kP}f~r!36fI}AAbD?kk;(Y)z-6v(*jSV(jI+>- z!Az{iJVd`OA@r>UI*in43d*o-9vE2Ic$Qb0k)M3%FrBaQlN-99k1VaAgpzMWvv~0W zw^rRGLwQt;-fCDLT(&+++F@bo)iXG^@#c9{Wqf^iLwUI{H`ZI_A+ub(#a=rKcd>1Q zfIuXY4rGxMB(%9E*!~{;7QLF;J~3~dVfjER!uHWwh)=7t+;ma3p&u_?5@2rlu3WYz z-{QN1a1Ng=(N(7&&z6`ERx2tokzg1qz>!QNgOsz{QZZaHvFLY%V)qY2@-gSWS}|)h z;MJL5Cpxv-1q>>{AyvKHfbJ8HS$kq$OTGh5qc-`4y zREMLb22BPN_BY(Ovj&kJVyAF4RQ-OTY-Vk;n+5DfuQ02Z;r-@vjQm3#mbXff4UvGZ zqUd-gm&IcRjKkUn=8!J&=Wl9fQw z0~GSn5QtHlXHeEmNeP|L)hO++FUBxqsjRH2rK-gk#N2jt+dr$Xh;(ZH1D}YY<6(wo zbh(}Cr2SOzG(_$mGd+et0)VU&9q5HD07nTWBO_zC(YC-Y1$0e-DK2FZ_v?nn+bEir z`lj4&(F=RH_s{js^=?JInB*avfAm$$euP)t$KWc}VJeSFGdsOMsO<#J!&Pa_@HJPi zzTVbw%ZcO9kbB>2<$7mf-eSd=bw2osJrqf9M@3|#ljbczY{zZ^5}hXZ#r6cUGkliN z(%xjO?896H;P9sHf^m&uFH)hFKNu#9EBhT9|dhS z$My80<0_X*2B2X-yv!*A?OS)P*QAA7l@2<+s=26}+lTo4FDl*yVcvU14?Ylaj|ICh zH9sjVtsEvnpZp1Wc5^qJi=!xcA~JYFyy1pY03v=bx7=yljV5L!QEIp1 z13Ax@=yC9Tczo<1Ui%`lMOt^f`0|LNYig)jz4~bvz?jW+j81<|Wf#g|=g*P9oE=FP zg7U1h9LBsQfhZKAywKO!tZHV(uEsof&=boko%S z*W>&+>R^)ZjvyCjJ8)*s4yN>KK5C$(_tBYTY4|;P(WFz4skOwWVkw1E5+m3^ZmD3` zFO+6a`RDkl&PT=|+T+H8Lp+`^bBs8zIuSF${VdWD_i|U<(FQP_n{;W|yPcX@NIEy;!=(hbbpfpF&kQW3n z#Eq`~=vK=JEC3I8Aai1^sh9w%{tYU|v~5UuA(=UM0w%*EAR!pxZPvo#;wx@Svk|L_95wul!ZNfFx6Xfk!Jt%EM9-VDO_c>DIm zQD94*Bec%Kn^q_h-WW-Mnj@;mYZD>MNoGhC;(^gYT`t{+zbue>bimJRwNV5s9hVvY z-g(LGyw4C|FA$ew(Qg?4(HCl6_>DaK{x`ZIbR~W8SRbn*TMM6=)Snk~rP3FIi;)!l zP=X()v#=bNQ^}C0ZwsuTCpEOyCTmug$vWs{AWRjxoE+F@u=LdHt)SqT=W3j^w+!uWW+i2}=#v4)jM{t|)2DgsI%AE(Nc=(J2gt_#W(s-}zxxq`;W;}ucX2jB zQ4CSghZviD?a4AN0mn}k7%%YsYm0+#=7~-=&(4y_R)C!AFodRoI2U&OXMpWQ)|YZ2 z@)lwPO^z1gZCDrs%*wvQ;Bs@~syUga2-~$kMcQpMmZXttrQ@%lEDDAL_PUq4 zo|Dt;?)%vIRkYQ!y#l)rtC*nRCXd%1E(b%LPI&L}KyVCUci|#I{J-;aRuWZg@yyIj zb03CW=gkh!E3r_UxgvCiNW@HF^7}f?D3)lj8Xk`HSTn4p9*R+uu#_d_U67i5S(C}{ z`jc`TK?~sWCg+UV0|BtDlM_4JfNfNneZXiqmaI-5=;7)A>)}}o=b4%Lp50|(s@(r$ z5^4F=CAbF>3i&?^w@vEBu6Lt})=p7hj|0U0C^Y?NW!@fZ@0pL34VwU^tsiom&`bX>#g9j3DBDU4OkpW9o8K3=eKkY zjLOHYGn@F7Q_I9{zZp!GKSWLEkDZolbR0|lZ`GX?VRAE?&AU4PDqs&(x%k2QN)_C_j_lIp-xk>dZ*DD405H9em0HihZSB1 z_p^?=<7N4@x}M=R%q`y~NiRL*>b-GIJfnE^pl|4TG-J9lK&0N>%ceUlIPz=i-)WRDf?Nd;@N&P;32n*((e= zmHUo&{%o*yY`8D;J4Q!a)3l6fX`(hb|33PtG1$uBtpl;)@-n%vmYV2A=XEgy7E+J8 z^L(!n?{CEZhcsQ5g0kio*gB3;ig_RCz0A(|HbZ15^f(OKsQDH;_`>gzS?_OwcO)3520oYs90937!KoT`%@ZI zm9_cO$Y_d=D1^qN(IL&#Raaadz8urxE|2FJwTo$shK~Eo8*v9i_Z6 z>>e+ZgaF8(J$7e>kV1%ClAD>aZN{1~g0ahUuZXReM;mY7#wa>p-9dcy`AWC{eCw9e z*=+W5gG+HsE<*ocG2xic66|%}0D9+^xY=7Cyzm7xa`w78WalWDoo0NyzRa+PDlze9 zk=uG64SPGGM8CcX&GBpYXITD*(*P0Hmq6~y)t=#T8Kz^(ITb#@qWmRrB8}|t-Jv?O zS`8tL%ike_Y=0UFcs*dlc9q{?LPUEw_&t-q5-P}t*XJMIR2E-YUP$EFt7X?}l>bWv zN3lXaC@=_Tpx%5ulqiwbbUT{<7l$7lKWAmw8T0Qv?a69L(h;@UxAYGVED8?|vg*(a zmIe>6V#W-j^Wc zK_3rDh0b-2sd3Iv$=@2n1)z(z1b@U)KAv{|)+ATvireKBrwdF}$x=PKJ6&7E(KPqDk`y$3Orc?ObzEq8^%L9$(}dQVQ4v&<-p?$Uth z^Ue^5ZntD16Z;h}C{4$8iHoaSLQX3tFEi!vTgg#(l*w9TwsaQd%1+|2f z#~kIed}dIjbk`5vzoUA~af`im=?~EyxZ~(H#%ys;8 zd!~6Xn>Y}A_GNVO<;Ez5ULB><&mrVc)iOu4E2wUX*^76sfDJ08Up`{+3oNY+4|FLD zdlzs{Z3b&{i+ev;y8mf*^p{T)M9=g){n(GrUN{Y|?tak;rDoE_LGw2hITSP3JAQ_F zk-;DXUrIdfhOKhV0E)=eBJ?jMrX-xNMF{ML-$JHEDjCS3U?9H+p&zgQ_G&Ja0SlKe zOxlEKGSK58S08|^vcn61dX*fIlAE1=E8(zPMeph(F1DcY7oDY7yvk$$AbToRxE7Y= zn1<*I7{&hG-}B@MRShoec1Fw}?<)pd6A|I8J6RxOB9}c@kNM%rK+IEd<4L&rznWVn zlL6l6f{!>j81x*Jzr!XkN+^@(cqa}yxhnQmQNAv4HZm19StDq0Dasvt0)d$+i*ls{ zy6L{&&X=JQaj|1RC>^X@{Lf=M*cM4Ru|vAv;a`iQrM`~9*=fy_34Hh=I4rE%tAaNtD@d%xsO4Im-dr(C0=Z=t(t`+!1cgj4mr zu&K_M_%j>v-!Pfb-Z@tJ(S6M$`dZ5l94P) zbuWtK*$4CgTPfm7Vfhsm$C#9uwHWk>O7)`EGQoSHAADY5xlEs*SdwZ78r_Lzmx|o& zQK8?& z4cUq-?GK0%uJ~@5hs$sUmeLkc&-AWxXfUxI+r@-}c(Kyl_q9@Vf?V)5)!ZlX@pad* z<0ad=ny|lZ2SdqeK;=fye*mRY&`bLEqWxL1E<`pqeNy9{)9}#v8jvHW{-@CCOk$TP z6MA-Mmu-n#Lv}a&P1Y4;$7c2kv9UpDTmy};ltX0&1LywV zhiE;sH?wym^OGc1U`F+n3q8B>%7**>`&s+SYunet=R5oEg}H73EnB*%|HplW{bZvP zONIksXTENVx3z$I%Hl_V{ce4&gN>ym?}0=~I~mLd*|rT}>Erg?-nNU#lR`22(}!<$ zDJ7#;qKCNU_s$qgDiT(As9yWtLv^y;1iuJ>{c*mZ2>LDs3Dh7C?rug?!J@DVk$c|X zISbToY4Aj zidJ1NNZqo0p~`n$l}oquzzfIl*EyV80-kbT-fJLV;j0R_0%_D2Cpr;p-EI-!>#g&O z>Npl>rN+P5U3@ugoi6fb(X9g^X9@XzZh~egfzx!GHMtg%Fmw_PTK;7c9vdlB+wuwS zF=T`dXE#x5@bxh)br!5h)9f5FR-#(Yk|p99OT1u%G9n!sVmcq5@bI+4F<+*RI(6q( z!xWGB-A1$b#`txn)(Q5;eho#Y$#F0}+fSv3m=SBT7a8M3fX=usau6Svf~DWy*CYiu zaaciYi`-X<*AV*e<3H+#_dLF)Dua+R8r53&4QD&8FDP=KUHc3CVnCn`$#vd3a!vN7 z?IUR14ja&G)XRsjB5;)xE4j&!)q&+2hJ29TdPW)0d7p8TLag-Y{HIF;XHvhS_YYdH zO0ySZ|DeH(`6AHfpWn``UlnRU=HBwSq9RqjPh>uL8$I23@%&79lOKiBq$WC4OndNp z(tUI+?(SYB>3G_+?C`lx=agF{>m-aILp14m`L^8UPJUNS4&Ie(-=6=ez}s0tJymrS zD}lPU+nYPO+*QMqCsYYJH$$ZGMje2A>RFs6B@=KP$~D!tD(K-dJ@(7!bi*uPJny+k zFjek!=EHj%Knq@7>?_Q4squAVotM7?r%U+3A+}P_jH7&`a^r3GML0XlW|3&$+~UB~ zS#F?K`XZhLhvJv=r%<+D#8r9G@JxBXDw zBkJGlVGD|=u%yXnQmM61|lgpsN+1BI4IAO7sS#zi7 zA+lPenFCq6qGs2zfo~p{lg%i?y9v61PBn&5K6;tPSqHd2I;BjX(N5zQq7HV~M@_9} zYpC-2sLj5>WU(TCCY*5(C~3KYwDGm|j}GBGVP7I)MvD$MpjfS($Z^`vYkmA8PtFBH z5O+3Mr9M|{|A&r=bd8+4eX;jX3|8&NPjm5O;O1k>d7$VY9|83SE9j>GASLR?~STb$HPbJ6>KOtb4~< z=E)Y;G^nJjoNyF*&p$j5JluNT{3`v#K?AE7V^$zyKKt)+>1s>C-=4XQoBj2)k*@Lt zVGcAR|LF&LoF8DnNrp+KCIJF#_KkVF%Lp(g9$->6?t#OKy%S45ZQbIJ;V4u&Hg6Bj zhgEGlP-9S3BTdFBX~Dfu{b=88*ZrkeAg3dQB$m0CKVl-O}NTmzAv@n2>q&v8R#F?QA&; zx47DLG!G3NGSEA;2v6RX3%WuRS3bAWDq56!>hY|pzM`4P=!f9`ri`?+5l1l*@832# zXNo+4K=;?!J{t^3(;(?dhf420B&g=;siaLNQ#S{V0>`;V-QQQpAr=-C$dv3Z7lAv2 za+JbdgepJfP%3bAkZTeWYGEqX^h=vU;X+GEKZ=g_62_7Ve@+RU=u8`VbgF93>}e~b zIN=G@ycXZDdwmmncDn78;?>s8|Jo&JrB=+X!K@o;qt5WHxMEZ2DZDZ8K=orGIB3sI zIU0GlL2+4^f3y+TAf4w?y!Toq0$sPji0aeefYJGWBX5HzA2%~`SS3Iyx(mM}T+J26 zs7w!xYEONIHgF`{d|**cp2Vnp$7?~U`JHpSIJ)8C^@?_+LC?r$_3G1sjfF)?Ek^VC zb7Y?H>6oi(t8XRB#hOPy1(@ma;XXS~W|4@td}7kim%n{7gFJ8!tiY9YepkrHg*f& z{TBz`_B;^&xpD2OO*0LsM@p{vHTj738q2>FY>$ zbz#k_$^*{=kcpJEhr=sw_|Y}CE^ik+rDv^X8|GN@_5hP_d$k^;#DYFIFf>t`p^jDz z&h%DXij@&J+t*m@4YYc=jJ+#7C{1o>j$%`~J~cS^YJnexit8;WhB{WR&3}}AgpZ=b z!XO|lz|T>AR)8rZwQxNuC|#~`!_7F=rvZORUfrQDgi~uABPK|H36uAr8TkBxG4^i( z4vu+1W^)RYK_KApFnUTN!fB;s5JY+Py6+z`&i~@H{t4QmkH&OM1)f|GghXm@S7>5n zkQ1NrZh0$$YiK(+ojz8gbMj@eLD{8+&pZ701Rb*5BF2buimJE|IvKB?PrI7e?hcMp ztF!v$=}>5h@o?w@Z>K*AhMis{*?4iT?wrlh{ny^w7#EQBmTWER3^$;`wScbxYpBi# zp3K;ck-WukA+G4sHoZ`733SSx+9GD@3kO;*P3LQO{-#T!Ena3PG>FEB!8j2mv>d4e zmweLWwXZ|}=h0sQK8##m8(j-IS-y1`?WXNC7s-;k4pYvMR@%tO#bE)(}94#^Y-6>AiTwpLM-ohEwiF;R9(cAAbdoP^i zE^GDSK8hSbV6Ke}87;yv>V>lQUD7Po`Un;RYfPlP`ANMPxHHFp9^_ zZ=xNv+Qs-yZqMfoJBq=p;qi12&u|g6DU^dVnsBP<)ogzvkT9c?xAj$j%8j%4F(zwG zr7|UaPC$6NCHpjPB}AFyj0Gb;bwSlXC@m`0|r{;M4f|vHdd!aJHJX?uQ_0MmY7o=_7v@)m8G6v)RR*uyS+D8t^ZxieDlm z9K#qA?b9|UvjGaf*1MU9?rnnlZD|=n`uSJ<&{{;~8heZ~OWUhXT-8_4J!SRCT0Gt3 z{%}k7Hkp|oKi+s9GI+tn)->B@+G^6Mrh8N$1*O@~HO;g>@i!f#VagcdMX|&(TC&RW zSvXB$RCUveA7?}9rOls@)z3V>4jja9I!j~HariMmk@^L!9dXDEJ#|)hCq$bS+$Ta; z0gsKp@zd`3)jeO=?0H$UiEQd+_$ep!9zRByHkAw>t1dGBSQ6M*n4=-qPko$Wnb2Q6D8Rf~0Gi+B8tOa0>GDCCD(`!i|fY?mfT{-ab^r65eD% z!ng^kujJ|=v%|(Gq#QFY#lf%f+%+gjt&EAAKrvnXnfa^z9K(5VUg|cX9HQG!=G^ws z`#Tu^A(VauP4hxWucy(d>*FtWClvC{?l=P>FQk%L5}kHw`^)sYd_1wAIU`w*dTs}c z`iHrSBMqF**bjw`0cm$oefZSCa}TXcLZGFyJf76wj_{DKrY+8B+JOU-OJ$%fW2DB! z5-qKp4ejYgD#>v+f@O#X?^7ejeWhh2&!&{ac6v(EKGI_)RT za4#^DQNkOaUJ38n&C&!=ZSHvQ`FVCy_$I*uK=WZB8;|BjV>2V0l13PXK#^2*VRrC~ zW1o_;L2C4AwA02BWI41HrW!5TbuTn@(jQ|;mvBcAg#^N*hUyDx3@OWBAY)ggu?&f zQ9lVn}~mr-4kuZK`BnMhTDM7HLQ}!3qRVLKR(ZbB}1i`05#F* zR|*A$7UI#b?;+p1nQl=pnwN@rD^E6OZ3gTf8q=e5V&{xV5>NzW+?6r;W`8DrS8l<3 zCA2NN?>U8a0Xa{CMhTh~dUiR=|5Uo-|JBH0vzmd*=mZfp5_1M*mNN==2yUNlBm2Y0 zsE@1v%vH=hi83+iF7g1GVN6w?(Ayl3dKzx`UB$L^6>+dwHVof>&vbI~mC@U%f_U8H z4S-vFHaCeAP)vCB7-VYmL^ydV)etyF(x^pN-Tnp7X?71KJd4g93Ml1G!|-a_N4*5n zhbw-U_~8L}Qjr0t*SY?J*N}{rP5+v+P_EJ6$f#N9E+QbMT>F<2s^LGt1>3HQ(;Zt+5EH1;?wzPh-_A&z;19+SFJs^9WZ zHWzM5p?+}u^u#UFc85kN53=4`HYrI4BRll(c#l49kZ{5c|bZWV=s{SMgRbg5?su05NKsE;Sj*(D54!d z*1df0iT%7sDU}&IsXKWdq{JAn&uQMb5^w0!vUq@a+rGvP4v^_MCD1FuFY(+ZDc5G56NQeK3+&APZfa@G7nrjD7fY)> zej&BXP}5kS^7(ou2T6J37ji9}{FCyWtzT#;tmVh5SF0qlb{q$EfnIiYd=_YBqzg=m zwUI*by09ga!=i~L2YiET&*tNhWsyk!)aM#jYm!Sfzy-FziDK)S>zt{ux zD4^nrkFOy{ArP`Ro_U@bBxkMf+%yOr_ ze{Q3e>^u;SMZa}nfS0VYqx{KTA&FHR2fFNKP-ZZED>WI9VV=u&UZV8p9{dqs1uHWt zoARIVD3p+5Rbx9Hc8rI&qC8P`sBhjoL`I(ex5Y|&X&wkGfwxOre(IKY>7vKnQq>KJ zH)~lmGf$aga5@HK-R~3s4O;H(Jqy6xRV|02?e9(V$n#3(D<-Q?FbhYcJ`; zh3BMS+%v%ea|ex$qymwpNtoQY5z}BWBzBW>HZm#>)nc>#GW%1)*gT8EcByLkjtsHJ z?^L0|b`Dh{On$ITeXZ7YjhwS$35$Cl9=~R_cYF|8SOF!e;ws;B@GFrZ{P{vbmQ;Nihk!YPwP7rBsU4~=VsOo>>I{wq5jEgs6 zD4G*9Gp1MR?0Tt=W90qgG!W?N$Kp%Dl3vm)OxZuR#6QBBO($Sq!c@R%Dr;@QYR2Z6 zTN^XVGTOt#X?W=(S0f{j)?s=nBj;r=nh7pBUi^DgCCZJ8bWDy^H_J+aUqvFUi#q5X zL98}>4aKnMr#cw+{OfhtetU~1siu{Y!D^f`Zbf4RA2c&ezhLf_&?+)ioXKy^{`os$ zHDuJ4^DR`x08pfr63rgyS{&bgs`V^sitROZvI7V?5G*EQzP zauVL=215!$9R(RE45o_=E7%)U?)f5T+uX2i^4fNAJL9=9dP2 z)o6z;ykQN+Vf|Hj47-8k{x#6;h}$T5(N@MCm`3+}Nm3v?31qxo-jxiFx}aCPBD%`G zL~13bbwlVT#=gFf1KnfZ3XRE4SUSW7uxV}N42#%e3E`Tey6o&I2@V>|T|R_o-vn@~O&n zSSc_h)k+@T@YDmeSZ8M_e&YQJN)>n=o&Co4d(oljIz}hUX(L+oWWx$(#;ehuEq=PeR6W9Oq!`nxE2rdUZJP55=Cd} zzHd@!7i2xnGyuPv1L}&C!WVQp5md-%33A@EVSI22Opl^CS@%(%7r?$evt~kGC+@%0XbVbobiw%aw?$Z1IEt!KS{qIj=gx*?|#^ z+BGi{luU!kFmoT1!1r2?5BPHEl^I70+WcXml9s`0#Ui4N9J%8*Y+rswjJ$pmzHHd+e#Hvoh?A9Ja!~Y! z>RtGI;QC=N`OC<0!O?FKML*Kz?1BUdw3inDhe{a6?VRQ>Q^cZa+nwGn5_cg7A%m+GMWwOua$(FI1!(34wCM_YjLk zs`V}pQtNMjU@Fz;#wj^@C82}`1yva2D|oS%S0bVhj!sU>ri4UI&WGR;@_xl}+%ac| z6QuG$h8fF2_Ygcm5kA!WyYGE_nR5Zz4&{B*2>0E^%~xyh5}ay~F%wud?1lHs6`=8cPx!x0v(;$B{4c3WObNqvfV4O66x3ebZeGW3Mt2zcUt=IUxH`~!b^?n82Ik|-$_ zB1Qe3>$ztoDA1|~eZnNj$Bj75EiW@_C4#3Iu1YB=Qvrqk+b^VgLHBhgqP(W=IwaAN z)VWorzfID9p0FJ!E4xXCs+*VhSthR}Iq_!G(u&SYc%?&e>tBr+b&b^~4k@1p+FJ8T z64dKS#zNJ1@6i(vsb4g79Bzyfir7y`ad6*iVZqXts@jQf@ugWR$~3=J_Vzfv-5OjH zPjV=^`2`J588s>}C+ud6cYxLNQgUu3p-oieaZ1dZ)6LBPW9cdzqKeiv3?SXzB{f4M z-Hmh&-Q6kOAt4AN4Bbc#-Jog4NO((tBl>5zKA2z6LQAmUSJ2^2eBqGQ~ ze0Qtd-_bGa_B18c?&qy4inFn^!2ei&FPfE$dlNDvezn5z_Q}8E$07Z{em^aow}tOZ zk3Ik3vj`efbLxpAZgZaE1ghk^LtwlIwbK6v_JZN-ndhB~tGOfUKW`b-+j~jY0*$py z)m7x7po)O4(`F4lv33@r`Go$Chz56$l}{9+KQXz$jx+@?ZYjrt2!5+OIJlrUM}aj0!azR!u75`z6RhL-fdUi}Mrc0=6Z3Cd4Z>MjUk@CBMXh}o zqoZxiui{@(nn0ln)KFhlJeLZcVVcUUCCY}VCK=7LwD^LJ#*a#??N=B%0oansH9sv5 zmW}@jI+2MTaS{lM;%#QHV}PT_qXTl93mg3-`@e{%I52M|9@2q_U`v>68~4Gs#tYOM zMy+}%Z9=}uV>3ug;V!f1{$kcLpdr~vK?7y29N><-pqgC?)7}QTS=)kanSAVL7`ruh z$8%4rj5oJ8X}c%C86nO`rdtiyX~Z6SKL4r&8&h>TA7Ob=Hu9^p*ktQ74!T1&=xOw% zjJR$N=5#BO8bzE|8W9exL8vjB9e@3=zv3B{o5A{LqE?ZG?dx`kYqD1Gh^}@)aE^|K zq=TuHa{}LW>lR5C30NbYNkK_%_JrOwnGtKFOl4>v`Qwik;pDkX&|7El+-}BbDK>s# zGTok}Oc~GcWNHHSgMT$2$t80Q( zg`xAdLx{vm8sTPV?_+_28}P(mHBe9ms&$sUVrFrd+;+pbCxDX*m`bEoHh*^8Oy>z zg12_Iy?vQM`Jr$zWNLh4d|}0KjUSxk#y8ZwThvc=zODI=iZTaOFlUl&9Pg?+F|;E+ zdw$eb?AsoKc6ydY)0|xKRI+oEoO~D@2nvPLJDz_`%6iY2`R3!cJKtsd!U~nS(6+8> zv{A^O=Ot<04_`!x`SYf<=mf*T-}wHAhszglm_oSUqPHSU%4Ih;Z!d0s8!b}W>cSFL z*re-hy@g@P%gDO(*hBV6Y4UqMgOD7{Ix8#753Hy0#0$5UcVUzYugB=`uhS#bC-Bef zlt?^?8X+YvuKd)fAFUntzrb|z1Pq*KOn&O6Qucu%*4XuY33yF6GIFjIhD!+iK3@kR z;}LGoM>yGrv)CKC#tBVV$h3>2WVzL<+onID3SP-*D^Tzer`vA7Toj1GKbew%`sevCz3XZVUm50n_iROco5*v*kGl_kO0ye0EkiBEf0M5>hH45A0< zgv_j*GF~1Fw`%}DZ5C8}$`!Aa0#iZ6N-84>Q2yANAreZy&}^yV+}s8SiA%Lfh&iFz zhlrSOB=EZ7htZV)5vsfK@>k`1Mj0MDIAP1LBtlY^aFIe-Dick$|MZ&JeLwj z9ENe3ifSO*6!j6maJDK0qrrf2>)`=SE5R+DCsWi~(`LKahSG@e8Fz^F~IsE!!trO5>eIt73C_3LknN~!M z4?8hIdFX1V;ey7K%p}_&^yNxu=X5=`HBS&18%wzt6Z}!Q%MvEfkMd_1V4s^rqYFta zg1)_Um9(gBtaQ9|hA=|Q3mc(A?+coSdIDN&#I%H&8eur6++)c9zkuZj{5Km%EgV}5 zk@K$ZPyIj&Q&AFPUF_Zm2*UZ*5`=mG4t21ZCHiP(Xy?yNu0Y)na&{-mg!ov~%?dJj zflh0nD&8N^cSpsBt$e!IY`@fhtay=h|B}>5qOAX-i+16fxKVAGh5=a zzm9QF{}2oXaAH4<-4{>hiKNBA$44vHFe8)retP2yetfmnU>hIv_{}@r^3*9BnxXP& zKs%0ADZ~SnK$&DHPXR2x_XXitwX%zzhnghjD>gxJM*XT_4My+ubK0=xjG@09*{3ok zC9F%pp$9Ab95Ok7y)H6MUa!%Z5^@5O3$FHAab#iU##)AUe4V%f!sN*@L@l^Y*WJ&*kv9m}<~_|sgFuR1%Tm`Bd+I+Wc`y@)L8nmVQ= zFDPMdG|lY#{54(J5l>U=OV9YYti^ywNTWTDcEpR+dri2YmPmW(Z=@^2?_Utp2dITL_zOhU@fOn?2(*^P-uUh-vd{Nx9Q*bgt0d_Pe!31cV6r z?-Khm*!t$ig^EuX(ZM;EP7D0Nx3iLs9*8HS@f`#zQ%^tdEn8;IRNa@qwvT9FzdntN zur5|7#|^_7hOI&?lH#wav)7*$IjG0IH@26DzY4TEz)e(BhDQHlq<37RFp zTVkz+{rN2_5ySM%AX1Mx7l5}}_R?av@%3KFkqwLOC>pdfv^fJajaTJA3^v!bHdutkK4_dQR7X2&E=c1M5MNWEaICQbC7|B&1oTf{)t{AejPXfapDX z^H;9XMsk|zLiW&4fSq8}fm8=UXWEsPlfG{~MKZ=V zL$zhUX~r_es3QEmdTKj67?vfo=5yTcr`#(|8;Ek*+1(mjB1&6`=?V*R@zZE1yGWp{ z3X+Z~;kqGeA%fHZ!2*Z_s3#M6(H)Gy6@080t0}2=om9nhaW(FIzt^iM0(SHF+|Yjh zWZxulbXB=4kirG$lQ`Zp+c0{5{x?uWSQwkw8>0t88R0Go&Nd15R28M(C};Z11h4eb zY2wXPnarfTOmoLNd)`BfFMmI5W!rvk3Yb`)N%CJNxa)r^l(%m`0;uEaBl0drT|bSz zR1yV79Lc9{xec08jFZG9J0e@$Wlyv=1aME(P{unN%AwX$>2slg2Ag`SKfky+yto}3 z3c)e?Ob*=BQkrXh5U;GNnywunX5J_h^mxZaQ+1~o*-V+BW-+rxO2$#ErB|h;7pB^F zJ#v2gDLNS}R+%k|s5V(SFg(}i<~6Hlw81SIdUF`1(OTz4r&^O2gD*@>%S($gf#&dU zr?I{wPY1v^HPM{6q@GG{snen)X)avz0JUJwM!V*xma{lfEV& zGQQ;J2!A4MN+~kB`8T5kxVk%?R@2t@*C#cwADX8G_z;eO3C_29|3FQS*2=Vw7a?o2 zkK#zWSP~L*kc@&>DQP-fA~J@}k#D+@Ixb3XnCJU=zziGo*6&69pPGB8~vNt|o+vRQbv#SRz`?dO+0Zu9N;*f`kw=R~7eLp$C zSD%tGRH5->j}0C%4TYs8&LQ-lYK9<_Kg0y#IK82HbQ-5AR>)xAW5G6U-v6i#rbhnN zi@#V%+1OP5{O^0X|Nj)S!U$G1BU6q)?%OQ|e}avI=Rt9mw7dPNg3$^uE^I?y6s(}6 zI?aop1wGMu2J;)iEWO5L?+b(Nsc#DR&vP0$e{Q7JvRrblW>aXienaxuA4d+rrWS}E z=w+-E*$z;ZvKpFpW7UBVt1CZ0M~`f(%K0P#G;9`GHKN$G${-geN*su*R1s(i2Am$J zM>%EoO34 zR9YPOlHJM}$2!r0t|37|Lj76E?&WEd43~nm>au=#1;JybK z0aqe|90O8Vz(}Ue|6-yOP0VKZL~DJ{<$Re>uo%@`ePt+m3Hp)WeMaraGdVymxm3jF z5RRN?lpvS9RlaF8$$4bfWyJK>ksaX1*>jGFIAR1~^VB(L%17#DY%OIVwKm(nKcymz zE-kfzPxLM_K}C)~)y8!_bsEfh!SBEFcf1p5TL19utJZT=QF`dNgQ&)|u=jUxhGJqYZ@;^)%fn&XW9-)AxQ|DVP0A6hS+A09Eu z8M_8^=ttc?`I)XR@lX--V+}yQ7P9LZj8?que)rU|wh?~p_n_~~C@6+6SMUG{B6 zc5{3CU0k6KT7pHf{=+il$WFZ_OoG@l#pAUi6*ffU{khy50p;;mudqru7D&WX)-8Ty z4k)2hY_*!Ft#~zHOxMsK&$TDa-yRtYduJ!k49R4K+AnGDGF%BPqn#H7Iru_eD!f|7 zXfr!?b9o52VX|_|rELhHghD1v@`<$b3oP*A6D*NJ#_y#O1IOQ0;ZTi|pdrr6uD5}4NabCV-q z-^4nmwhSOG+qz*PZs}i)-ztBD^=eGSlT`4 zN_};i7d{bdQhNTdK;V~03}6vgAel>jyLD#8-+a`U!a$59S{JLgBN@b%Ke}J5ReP}O z5bIuqT;#C(1;87Orv3aPReY74=EEscq@}@0hq)WYA#D_WQ5(nnHRfIu1vBBZEUgk! zv`b7PRzyt&{VLm)<<7Il{oaU6V2~g3#IbSwHJdjdAiydIrizJ zx^*%?JyNYDuCNiVW;sQ*NgY{B^+s>cnDop6lWxLl;qRG32{%@NN(N$Ejo5(m!JVBta11DD`Gw?fZz(RUSFkn^F+$wYeR3m(f^4*>%c ze2A6_li-(JlZ1FMSI2h@S0xjR2H`V&VRx=)T?Y>+b0(g>1Uy~D8$OA%^GWec?>`ho z9m<)wobf>LKyTkH^}J4kLzbP@sqmMlyWH(LC9~7x0X*k$sHaij7kj8g*8a!Oa~w2? zNz)f@UU#XM=lt(m4fL0O*P%{OT=McUnt*Kr2hhp!DVe@05w@B4$!*u=a0L;4-=V`j zwWJR|rgo_$HhVe!L$UcNCn63Fz5Pem-dRsoGr=*GW4wcC;_iicdXg2cw88{~3yOaW z)ly)e8L78KRS_cU0t*=L2|7Pq{G;xHT=}<+b-tA5_M8R#u}%Fv3&M?rtZ#Gf^q0Ka8t&G}>za&&YSJJrg5%C!L2ej4I3dWyR#jlrOb5FD}{QA?VUfWAYs)_**(vn7~A1 z)Y0q7q)8qWRg++VXp`fDeDtlc%=lO`Q(jr*Ld`~hp{$a6iFT&%d(@Sqh038RN$HIN zE9=C^|A?c`gP~Q7*i6DK52$+fB+r)Yj5%f3X7JPirJOgi)_N_XFt#dXAz(@c>-fu9 zq@KUMU^^($I$XCY5!=`J#sjuOD&qXTWr=0@k&z?)>(XarHH*dFq`VSOy}Y_Uf`}gT zliiA>MDCr%>OXfpl>)^9pvNT2bNrr!ul1gYumu+#pks&vsuTS{*M7N-QcSVT$IJ=H z;ydncWbu68%mE81Qki0>)$($_uE*Q<<0$)wm+>PT+q?-yEu>dU5}2Cn;x%kTB_Xj zQ1_tB!q5!T870O7mvM($W+N1KtXs6mz^!Au#6`O(D!f)y3@!a+JHnsC%RZ74* z6&fgJo+lTZD2P(|0P6_h$F)6u=PxZAU50X-`#&3v)O&94unBgPzl}_IjAifhMk30` zTq^SNF|;*GKpT=v;VL6KfYh$$U>|jKbnu--4o6MS=0`WSZ(TT1Sdw?!!|f#^Hj3yrL9TX2Q7NzdP){6EtcRUk8M&A(hiHeF}evMLx3-^Knvq;weHG(1vg z54L`xVBlDMx3DlXr9plS0b@^cI1N-Gpt}W*D`c;8k|idv_Q%H43beV9OgLr5Jn55j zHJdsv?oY;g46~&3di`W}qrlJYc#H^qNyH!zM#1#4&R z;v|TziMfVvko6lU&B5Y8BAH-M;B2Y=c6@Zic372GA#8MPZ0>sWh1(ixF`D|K_sg6= zv*|E0x5(D~q?r2rAiXK(=mX{au0i+MAh}r2MOlgtWedkD5hV4Hy5Qz-Yy+UeNwegQ zi-7^$UPV!p*Qpau-Y3Ill%hl47Jois@&HSU2Q=6^qfd3}U{)K+`To^TQG*E9NNU+i zk#)l|{I{1E&z$27iQmo{_Trno zQ{mliX3sf%m1~ivrky=)4f_M5iuq^LP0=aTTK6@DfXB!crG1X!^XfCm@!oFyME?>8}%s_HtFR4uBoW_KAgG9^fdVkhope&iRVMFb-JMSyLRo*%wki7 z(fkvGN6}C2`@dONg}D)YYmrQC*#_2%uFluyn(i;=u>yTS_{A1MTlThboyJeUU!Xco zLbIoadCbB_4;faWi4A6*T}JA~vHx&7 zZx;VkVkI*{t7=R-dQ(`m{*10`WO|c!i?h;T;J$X&j=Dx^7?W=up=Y_<&7ov(aG{El z4{Y}~y9?9?!qt0E43@34sSBi$I$aXWAlsYtQ=z9h_XiE2uGv&Y$v)^X^M61fvhI>_TJu(@FhK645>rS}l&h65>wZuB zrEOf7vX;@3a&O$2#(@$d9OY+`t@FsgBpDll!Rad|S_6CQh|L(<>n!nvJvy+fBeekZ zFO`w?7IiG#leOBwW$GzVzUC_&`(+E~G@hp1x^*_!AC!-b(A$P7! zxU;!iwiPaiemi(w;9@0;x*tR947UT7*IypATUQej}m zaCE|?UAKLm2ArU0<8v}bU>K8_OsUx`>h5->4Q4Tnb>*WLFW(A&GSh{ zHIRINp=hW(ECASO*dBb^zt>8=^3Nhkc&_s0+9{<4Ru zU7;!YN7~dCi8HpGMAV^OVrqzbU#i0&^L#duV_;*X#QBlGZDX9gd2_oh&VtY^Tjw^n zbO8bcoxE!l+mEN7jHk$~@BwprWOD2$i@31f;Xn9nyi?ee;+F*{ zw*u#kzdQ0Hj=#yF_;9A}%cvbG%_on%rAgYSPL&6a94LQ= zk;iGCy`a!qj18{DJ@lb#^bm$N#Vd55I~=FT3d4aYaB(#hlt88Px_2sUMIIBo+53E} zOr!L7qY8+yxV`Ti^vV!volraSGR>kAs7(2Y!8F}@ElW6ah%m(>AF;ToNa)XE<2oBf z$7g?6;#`w;mZ?K0W0IzdIf-IL@a7INP2HCc5u-m`9a~m6xZFI02&T3yE?|Ynm6|ge z$mT=ve69|#3c=g-TY}!1NYxVe0!+^re_ivxaVaGHhp2m3*R?>YNoCQ6P1cms9AFeiqE-6DT6qr9YU=@fb^bsLdP= zxg!33f2F;=$il=aAY;bE+w`ORTUs1PyD`Ey97uS7y0(T_dFs1p84$^buerO0W>fqh z-tA5F)W%gMq*piKtlG58P?_Dch9G&Yii;LU$_tZ&eEmV)7hfe!S`^Y{OA3yE`?=Mu z!29(n_D%CE_vo<>CQw9q*fTK5IlTgiNcb!;PS^cnBoU%fCF=P7s|@nCS6n;sV~R6J zrfVN>PMP}hxtm$!W9VS9l)&3iJEUw}nBJBP-qhP|4#*Ui0<5@A(Ola}8C_znWHE z^_P@sxZhBFv@P1GBr|hX0YTD9sRkye;&21slhqj+kYs~8iCYvv3+MgssfSJF&DAXd6e$oSfV`Y$+Z0hVeWp9WfiLZ$l zQ}IWQ&_!jkA_&dSj<{lVe2{d!3-UoUxLHH#*dE3m?{s^czVo82Yh+Q8c<}fi^s<%E9 zLOBqhqJEYhSNZz9(4ZL79&)%*Q*-`EeDhR3S@VGQtnwn)75w!GIc?KzP<>Ur34o6r zjCv(vvn^koH?uql-+Y_k=6>~U^CSr|C5m{c)A50PT;~U-t^LoMCjlO^p(y`=agbNt*2`;Z5AN+B635 z>+uxtG84L+i!MG&c?lp7roSVsb(i@{*0j01i-cSQ_xD06Obaq!#_3J!1m%-8-%tpg zE-5N=n@3Z;+Ml2=s63`HGBe+Wvqjof$qWwj+-J`>?Sh{n&l#UM{xMhhkoH@zO*Q{3 z5Ck5Bq2CJ0BGDe!?X!21iDs&yKbD8FG~=lxiXm_clguxjyR#z|K}5t;MVcdL>0Z%5 z%#Kx4b@fHz0EzPN)<`D2{g=U9zz7}B4Ai1!dMKfh=!>JiYlXNivY`q3AfNMUIJjayW+>%Qcq^9(;oY0<@t@|Z zm5<6sz2b!a%XlPlsZYDVt=eC2PlS|qKk{E`;aV4eb~k8K!z`XbJwCZ(l}0pvv~9ya z2rM30}J;i_ilvmc+tjC#bQ4Q^E`T@b3Ec)6>TQa zLiP!@?o7nRBMAMGqOG^Q)IC29pD@7=AWV9tb!(~vhZ2-a)NrmE8xxEXCMA7GVUHAo zZ?PCCj!mQLyS^ku3P-Uu8d@0D%`9xA>Ph9|M{OC?c33*5q#{9bJ#*7*jqc+serFLd z8TzJ6&#)Y7s35}1nlqIjj4#8CVm?$+$RIBL_2S6PupDU&O{nmKxQc-AIg%8g2`#2! zDbJ0|{P_b0sgQx(5M8=j9-kH~fKuqw_iuXF^$Ap>M2V;318auZh*loK+42%gOY2~` zgsBIyR=h(2XT6%F(A+2~_I>rzMtp*}IQh?)2h3n8$hi| z_pe+P&qQ!?&)EPOrI<|b0KM2l;r{*D;e=TT$nlJgXTL!jbT@i6ozX=Zf^R|%Hug*i zz5OT_sPpDY${R2HCD#l%%?q7N!7_-y*4C8-f)L`<{9%5z*f&MOtRs(pwy5Rpe?}OB za_Gq5Yj(G^ZADeiJ8W^Hthnv&Lk;4mwVOyx1BaM9ECy}kY* zy_RUZ=*yvwiFkWtLrEfszSLwb4Xl$o8#c-m9 z+3Rzd1e@#19`W`3XBcB={SAXkO2Oi=trNz3pTX#(kZlD?FKaTsL1*3{e=D?Y0N*ZA z?y%T;E*OHWt}E~>p0+ok@B&?)Kog_YczXncA_aDyei>OhFqOw%+M=tY)408IiGCspFV|62C{XrS}!^5m(xyi}9m-#=UX}n)a8JJrFS& zpq&vr9~`l1(;J-EGoAwUo&{|%Ra*1T9mRW-E@O$G%M96RH#F zgBH$F>?L7^6242#M9#DcIOfYhf9$g2fX`h*&|;%I`C;HPoZr=6n%PaHuFWHX-}-0t zEX&i%hx^BamVeX5#AtunSjYb&Qb0?|G#hNCnBWslrsOa)+aok*eU3j^k7!dZ^{e_S z#i&Spg*FW+jRbiFoaWUkfFYY|O-VUvC>7Vfcor2p<>jZm;N|zEr%h6A(8~-7=u72U z#Nm@ZLdCm97)hUpToYG2REC7;Ek$OYm{()m$)Z6-f){sTC>ZFJrQ>{lG-`@uApUxf zf50qz1JNKO0mczhL}4GzR&WUU{A1O@h??>6c1u;nlm}TdL=ch~@CzIgf<3)S{wRV* zQxe8U6mjWM)WHn#n!BZ#p$<*A!+3V(C71rbY?aJYvm=vEA2+*ExsL<1qaj; z4{^g}Bf8e-YZ-p6zhKPP30WAqu>4kU^~L?GONl>LNU!J3n+g<5-(iLiW7P+#<&W*F zbrAW7(f_QxT`Z)Vk4&nOzx(@T>X80a8Q!gN1FM3bZe?!{=d73Js|>gH_M$Y3B&lQp80~LH}0;GuJk2}VV1r_3ZW7p-YC=Nzeg^C zItLmUf*pxS%u`9Vq1a)>v@@|KOCp|+`QZeJ=41vBn--g$VQrKa^6#PX zyR*QUv+w&d>GZ#GePMb%04`Wmin*uB<>cK=ymB$5b_7cq(H~eP^sTGhQaAn{+@`k7 z?2EAsl&R7Qm4!e?%*M&QWMqFlDlk_V)G-26Yi=jFCGOvUtM6Oc&@$r9?|c&s*z?NF zUm>s#%^&gn`(l>80LzjvUqAk=sbQ`SpHMb1-LN;QPqP57l`wxWPUA3*9ZJkq?1!(` zt?*}yr{vZ7qrZ;aD-!gl5&c{k3#25QOWT;q>v+MQ4N0Kt{(=PJr|=D>($V2tgpZ$x z!>o=31Do4J8qud*dQ#zRu#zgky1;W0T{#)EKj?spawp{9t~QtKSwhf@7R+00`K!Sy zhUUsdQyhvlqs_k#HNn(3IcaR%HrRtLX$#x)VdZ-K2TJ|R8CwTiv8|oO94^jBiMGgc zJExr*i@#jnQ@z|{*b?TXQnb7aN)W}j+uiut;%s;c6L!NWid?JEqdXB=8JQS5gL0J<77+sGjg|xtd-}+-qKt0^Yz(ZZ0D=Q zzt|^N)Wg)vwztm(&h`7)&dF>X>M24mxtY3mF7xze33N;PiD9(zuK9hJG7A)s@9xFTY?@H{)Cb<=~&3*ahNBGGtq@dBx$p1R8mlcL$=DK{7GJg9?biZ|8=ARp^15JckK9v86B&+17GgmIpjyRLfd}#*Q z0IQE_`jxRus955l=EHdQXBN3LJ3y|FqdK_MRn6}>JxwCYqGq~MH<0J<8k%X_#npUw zA8_}|;u{*sdR*UfU-0ZhHAt*bjO1ZPD^Xq1$(jNGo(U(!IS_G;qAh>a?DpB%O<7?o zhc5gabp9JNe58rLn&Ag$7I%#$!T2FI&HOUoBz+e>c#9IIw(xM9aMn>A+SD$F6ZqqJ z+25rGDzcfcrmv}$MmRD^atPtFTf43@O30(Uqct@xEstW#P8ijyrw%!8fz#~>un^dS zPW0%8IO5|RSOFG!m_&%M6)R~ZHMP?~-;Sr7?Hl5Mj56Z68F9q&C7V5`TlZUk2t-7= ziPBnb1`5WO(tS5kfL~4H-81$JsFXAeLV`ytI5yl`_5ORbtN(Mf1#oFlNf4)C_b+Ot zCL1M}1)}%qD$C}umz1=0@quZC8L&$6pW*yyyJ>{riuD zJU3-=)`i)p&6H3lb9355_CBs@@2MhrZ2Wehn{`^vt0Q*N%;H>`fVC)4c`fEri@&1% z=0w{zcp|qUFBcX7JQqVM^EMj0h9TIxa^t$9G1SmX8G{-H8-R6kPgg0?5( zjG#S>6510isQ}VI<8{!H{Pd|cJQs(wWR68I%wVm#?3Vx)5% zIxzIG5pSlxqLR!EwLx2bsV8Q$PkFJxL$65_9Ht|>>%;hY`iE70c_!TN#R4Na2&8r} z2(Rozqle-g1WF69BTxAIRE4;S z8nA69ve}9Zc7G=+Rl+^zzUl%*3n05uQzLu9IwmM}+B*90e8ugQ%xwA*dpl)u9W_q$ zRX>qhWXv=Zq_U+l0S~lI8=_|m4HTzJRYFa4*BxK0wS6)kR@_oJ#i>nUZ7!{s%Zp3j zx{!-Z-V-WG%cMiQ1s{81DM`3c45ZKZW;@GE_ge=hPA04H!u!oV*!oxJ_fvWztNdtc zw~2#3LogYqijRnZAcAe;Sl@Ecs0Mf~%^NhobJ;R^p?FkTqry&|5hDCwoGJu{c)lbv zNgcp)f@^KY$u1goDs(VmeK0-E&MWE#Qb-5skni8akz=)pV7|$+&TCiUc!Qe~*@q+Y7ld@el{5<7F<^7^S!YqWh0TS^ zI8?`LXZoj{fD47em!~vtjRp(UbYga9DzLmQQ@NR&i2tCUwZMD69xZ1=Up8%t_FC;3 z1OO~VKr|K+AFC%LyPs-}5gi`BpTJT}GAbOqdZF=vxR6z`9X#msHBKI`Kqm}^P)y3c zrUxxF_bnWF@<>w?L7gp1zjc5go4$zW=6(}Vk=51zSv2t94>+QiD#)mAcT-&2Mvr69 zGt&Ea$3MNu-L`reFsMWbU;!J_LUtGJi>pz^2w1T1V^6PYP_UA?QiUK=gf|I|Iv@LlF@YPX`8j;-;^BkAz39Ux5DRod& z-hgf|qfTG^CC=&L@FbA2Dd-kVXk6i0(B-kHa8WE9-|;jg?zWVOhQ<~-?LG^nG5?{E zx|7(WjqOmx1_>MEN{}YR=WL-sn;ie(c3auj3N;;C9?hSWUD=D0ZiW)lL94Shy^1?R zyC}iB21veVB+j9^3p8Dv8b%MlV2kB$kZlG%#+6UeiDV0gn<-i0gQ5CvbCbIUAwN?( zaUCIqk534#M{-@j-%T|5;g&g5+jEE*l6`)78MwN-PR!qYqcJ5!h0P=1$COCg?3x++ zc?diI@S7w_tr-9-XC+}w6#Zg*9rY#}97Wn))78Q({2t*SfZ9!{d)dOA)1wO z8FeB@nCWV1i#On>*AbD0rKQRgbTeHvfnoR?7i0JSiwPXu+x15oNo}ODcSc6m!z8;^GdHx0HoXDxXbE1=KMHK#lCVX^|vKX}+{PUBaO z0=AbQ#RR&l#TlE`29{tw;THPH$9Yc-3Dy4+&;v>>XSydj>r4?uI$M#X{hLB%3lfvE z)8C6Od+tww@;};nHG2B-KbLk?p_mcdE1aHUIrv(J&f5a6=za0c5CjW=J{R z>Pn0UKG{UgyB}&)P|sYc4Yo)2-8ZiSD+MJG7iVr22;7QK8iJtNOaxk9yG?ir8Pb40 z#4;4)cI-$UXtlQfjY!%N7C2HJP%%NK*dTov?cuHPqW;R+$ektSePQIsvAFdGLLx;C z;_|eaND`=l!A8j&$$iKTR|F^UBQyC-vg~_Ll2r z(<8DfPg^#bQv2aO`G3qDKJO8X-u~KO{vAG(GRGBI`uGJW;PKjC1MD^Xn#yJb3sH~Lem#NtaXL{5~o*4xmZ8Li9W?T-su5d6}Fp{b}z|_DU#>CLw z*E8MYN};e)oF-2xauz!b?72jN=(4%B2#e?jS+aTt;z;mVf>piczTXfS;qdw29VWt} z5@g)H+;62MJstmo?82lzR}q}Qj~h8G-uxjq?ymqcL`6c=FZ7tp6bL^4kjkOYu&+Qa zt*5|j5VC})M9h}#TO}wyTt&lWBIj2)`JFNp1%#*wAftt3e6!IcU(z48LZ@l0o7ElO zW*Aslu5{=5Q=vtCusc%Z{WX)Dp??Np_b&PqLPQ-^)ZU+! zbxvFs2x)bdxK4uBM8&2MwYWk)K)p6tKcfI|>~dT&3-%o1ZF5-;Vq}ZCXhzEkO$R7(KVuy5j^ynL zO0|DT2-{25S^V`RBYtbAlIvpIi9Bym{82`nyVFM>BmG(YJD9G2flP6pxX2z&2fbz$V*vZ zs7kSme)*Y^rnp+Ugzo+_C`zEF5|P|c>WeWRw_H#Q$VkZX@0~D#ZvqHnvE$&7RMX5; zSD&uit^K4l34Ed-Oe9T|LPFcNst*_RLWi%V66B#0^ zhS8v^E`~L@LlF~R6Ivdr`$%8jIzu*9>5dN*{v+^0!D(COOYkvTQ9(26BR3Bj9slfk zX_$F_!kr*LwhCn(BXw1jX^XWfhfLmN@cypXlx&?dQ&ivOW8CD0ck{-XfO(vbu=F0q z>^_6l+Tu4Z)^V%^C*AZTb)&H98@W?R;&u`@URe1Or5?sLiXKaS?>Eci4di0R(`st9 z^-!uPK8{aMs63Y$3*X?_%?<7UvwTiaWR*o}iUKUm*~ zhRa6uvr?nU<}Z9Iixlf9UD{Ou7QIpo;~2NlJ0A0N^H#mo@_u{+QnnucZfaQeTH1u2 zr;T!Sgmv%_hKH@+6Xm{FH^ItBTIBX7Hokt|v@TTH2{$V?mJ=f%eIGXkprx%AI&X(C z@Rp3-<@j?}z`LE(q+x-MAd${rJ{b2mg24e-BliLJu!EQN9R}0R{Gk2tt2ZNPK~#=HCo>tuBd^m!|pj z%{2wNdE48H2y;^gkw@iQ3mUGjb0H29H}Qo4WA2rya~AYmI7vRoNU@crb^Ab0B$ zS@?O3K>6|aH|TW?9^F4ot64S(^IE~@bD)?mQiXO2N)4ifBPbwj&YnGa0<#XF+NE=w_mlfgSXMN3r^75MRqiXG zX3pV{?5s@{lFYT30ALoTVtmieT!nsZe0wI2)8e`YnUHq!-fL?Z&UiJ1_9Jp*el{?F zpE6A*@fjjE|Fh|cg)^S;+sku<9Ct08aEa_^`Izs}f)t6-ld>sI>s{Mrbd*L!Q+B5O zX;|>>`}dB_L1~1_hkO1LSM9B(lT%q?OrLxRHVo8j2fitCj5<0 z6SZ6>SvsoX!@DgnNc<_6$y>8?mKN)(40bbpFV6+*RZYA1F|!nXxm^B3eZ%Vlta4Y8 z{`%AymKH=_cz9iFuRMJ@9Ekz6pB-n*{$pt6=7u}N1gSKVb6yik-*AnfT3+G-^*i=Gr}8*6m_1nO@7Sgq8V{1@rMlaeFU}&5*7xinMt|-dpOqF_ zVZ|1!o~Q+V$DaLRR%ty!giRG#T#Z+GGCd_(=eE4%Q22TVHF*P@TEed3kcrd~7M ziYWg_)LTYH^}g@hfP*lAbeD7uB?y9acMpy9fRvQL(A@~A3?YqDLw86Ft#nAE(%m5? z@NB=I-+w(Xc*$CRd>&37HM{lSiO=&jM}6j52dW2UKp+7!`XUjA6?tozEiXfxp`JNjI5RqT|vRnY4a&7u5Q3!cQ&; z$RZm|FFP@qAeYpUolx@@p0Uu|jrQ^5!7&rB4R@gc5;H6UN;V|t5WW&UbId=}N}b*4 z$0E2aL`;05YKU_h3dp5JDV`>wd1)cJt}1x=hsGLHak%c(rM1#w=NL-*GbQPQwP3Mn z9jZcmlN3Y!{*p%BF8ed7X!yo!TW))967Fb_(UXe$l=^GrBavS2p(j0U&$3K@nfdk& z@X$3ufw1UpQbJ;C2?lpr+XJAa9QXuNBi!A>ks1hS_I^th)ZYHY=Td#3Noi}f_)P71 zeO-M?oFB|L%F|tEgJW`;*h{drxm+AiOKuQ)aBtk~|C)F7NdNcmuQ!#jp^$%4?|*6W z8;eg@1JC`1Cm*a<4}vQ0i(?QUXC1p-t9~!v4){E?mnYas@CsbSHq%LN4S+K{f0`q1 z56Lg~IZZCUN=`f9|mufLc*I+^fK$HMq!X`zJdL?GIT zbr8&IR&6t~GquIuM;8lsKiR25?|+G_5K$9g`g=mwBYb;V=I%8}?d4Vshp< zzND^XWpVcIoj9_xwo}x$ctImBH1awWk znbJbgyax5sNoxv*rAd5gWmtfA7#Cyi;?DM?{cnA~QG2WIC3Ykj^TrU?iRaGy(WE-O z%mJt3zM8{JnvYoYRTQ7)9i?um!i)Msx%kGugPM!*jpi>)D=;zY9O=UN?#dzz&84gm z+9Ni4fkilFNmWg1svP+tO>N~p>7}&gAut=+CCy|~jm z@m8#Ab}vumwDT}j^*0N8e1G;4ZqwkiJNdxB-h6Lx=Z`6fwao9%X)9tSQ2^GD%S(gpanZP>W@?HKq{7j^&glx2GKcUR@G1u#gSb26q zv!9~qhJS`pG3HOKOn<0bH=0oBq@damtv*{Lmx+2dE-Hr~K z(Y0N3Ew3;mVkfC7Nkj9NIYeIiavaCXUDDsV-FFLRiTL6pxMouljhCWsnV##_!1M$d z8$63EjjAo*mmoogVfb6Wfjtd_Ot#G#35(E|6F+b$Z6hKZi8Ls}%&QL@ccc26Lsts` zkO~-_0A=RSRlk%-j)6fam`1{{arwhmg@IeI#kQEsyNJnbcg3vEJ|`DUIla}iHDu@i zMom9O2miGUa0rh|_oWT;>YH;F&F32_u`G*Uj&wc2E^iBx@T1I6KUy@;wwF=zt ziurkR+>5oJQJ-b!cR6yjsnK)tJ#yO24N96_O{7ZBgC`1DM{_$lbeOgc*&=oY6qVWP zCtpfOrXjeyArckhSiDmk^?nTty51whlEklJ3X!Sk$lbPF=mzVOfpl`o8Po$@74cS9 zf`m!tuLFKt7rG=RCGxe=4l1}?0Gqj)d0dXhN1e`kg5$r> z5A9qOex9C`WaPvpqggC<23r&~Y^QQOG6#%^51Id^=lGOOc7o0}4ZrV`<%-$UWAeSP z9(*8r+*lU9Wk0*}wqHAIX!{)ruBobgsF;7$%K0aHk;Vc+d|n&vb27@=CQOga48{f{ zZojt&Y&lxqt*f}1K|L|aA}N{`d7FWl>exIW0St)6KJ+s-`T~yjSMR_bQiZ~){soy7 z!wOp>=XqK+7y^fz%n*aEX$lFcz@*iWqwB_g3NpVj0ar?PFk)0fO&!Q6g#&0cvpX2b z(Phg%f6O$Y=eCqpNN`gXN}QF47s?K#=by`bYD=ELkOKM~GBggL(qKE#3$EhxB4ENq z6+g%+Q*Z5u8EWX=Tc95@2vMS9t|wLnBijt?akUS=+#q}G+^IU5jZQ^cMRTQd%T2VeBal$e?2XR2nEgIo}FZ{o~^r!068{{CwBXqks!PebMi{r~|(Cbu+kf+Gg2YjB`*XLQp zP%7qhx!y*{3qrFD9p~*L7OS8j2SKByW31-P$Gv>$#`fqV&joI*r_{VXp>GT+lr!Y*8lSPt#~cXa(<)`URiZ&}g2 zvkIU7_|4*&QJr@oipt`L^B~^IMO0uY?e?#FoI^U3kRG+xZw!wTW?TKe)y(E4W%DjZ zYcMIN%bu0vq%*QgKBk#k)Ks|VE~ zXv{eESG7Dj5)bI?TG?rYMrPzCr~)9hTu`a2f=INU*-ej(i;)PSHv=?u*3abP; zxJilAuXUdqiQCCSi3{W$z}j1K3<3V;H7iBVVFptuY-$tmC+F^BKQ-kIcWe`CGf^!7 zx^}mCDNZits9&lrN9tuF3m5O^M^8r$-qq0(#;I@86ww~z;8qU5!Ae?aun{%%a0ZJnEea|Q& zKW?E0!CeRhQNR1fkw%ix5akege#-KoKtJaY`w&G}DuT0ez{|+nSCiYd+--s${hV!hLkki~F}M4p(9+fgcq|U_&lw?)BDLyqlT1+HE3Wf4+vQui!7?vH^DS<#11r zCl%b?m*kVddH)|)my?6($mU>2$)M&MTvoZCD|?pj9_P*=oL2MrXt^@UK2zzjEw3Cv zcHcitkmg>yMh+5J-VJq9{*MUS`Y$S%tKu3-)={u7R4Azy%w1#=Y;aVRdvZ4=wmp}R zc}h0O8kYpJ@zIl}T#j#+4sIqN4(+JmTAS$-g$D%SKYo!Ux3Nsy9Bhj|x}OpL{_fLf zWqLs)vhR_-5hBns6SZ!2BD}&ib@`MKB}d{%TbU^$vWbrkZ=O&&gh)wNX$!84XR8u0>|dc^MU9ru!KTWJ97Q0wa4*I?~*f9A>>%@8`Cfmc7uKD zP>G!Yi3m6rN)*q@ppLCCjjRRhk~t&&A$k{!^3fTq-yGdo)jj;_REOS{8&S2ZIpcz% z0T9(6;Sokt$Mxd)!CDIpaI#t{G7?80lsG}(Qs|qBs=ErzM3Tzl;m`V}` zxm5d#aoH27r%+@+Epu0N_@)DgL!;-^Llsj3`ifaDtL9WD>9pr|%zgdXSRc&s=mmvT zMA@x$148t9MB@j3PF$#tvCiiKAy!s00OTT%DLfUmzM_n!Q0qhFA;}C=MN>I>*_&%W zD7e9lVX%1E$Guu189A;a!B7jsA4c>>rE7tl{3j8s;~8=w~8n%G$Pxq1h>h59$( z7xt#Tk*zE1Ijr!zeTLmMFVvtz?pj}kesiGr6W!0^gv+}jRi9oMhU`D$^LZh!5YaWJ zlr3k8wvV&bUzy+lKiQ7Jm@VEVKvSBzVb1EfJ&!Tg&4xda{jExk=&EnW?iyf)0(nl)}w z&{LjU7Lw-hAOztpe_Ks^{K8ftVhFn&Wb{kUK>78Hd~1tV=qFC~R4!(2g2Tf~u_t+x{VJ5${SEdLH=Rx$-%=o$Z=&j z@DTc9nnwSD&CvS>`^PyFBIT%*aLWgJWb#hZ^5EY;b^qEJf<^wz;DzrHpawBtp1|ZA zF1Bu)179=pI#b2}jK^YL7^3Ym&%vMqphGuL_pq{Ty44<8!oxkBuVHrEOKsHjS&LD( z_QICZ(F@hX_E8`D)~cN+XnWsu$2-bqssuwUc#i(g!{-9+MO z%I)YIp4t2h5~(H8lKaPQ=dvG9Zw`+l(98aX^i=;l-mpk4WS#ei@GFbvTDTt0wcC3Q zmVY4cMQX~$=z&+b&wIsPBV1Cl7=MWEJ{+F~jqI#17%LUOf07=H^$tKm!) zZ}n}nzb4W&J^gH#J@&pT4}sF0_t5W6+uPp9fY3Oh8$PLUep$3SI9C92?q-zX6085@ zk%GpSAC6MhW^5x`r6fUz_R2uT`=DQ$#&?* zOOT^pU&NMNXJu(PdDjR2Abl$Hy4ng&&7ncr0~<;GC!@5Qu-%&NjS zBxbcu&FMbt_E8^S;2U(dSD`_s4Kzj5<=;Ag=v}WcD;3tvX%6|?l)F0Kr5A&(m8=6y z)u*^nqflC+_`L6@3UjuFv8klq)vNaXM=;j7jl@0vI_qAK;=2l{P3gU-6nEWH;x8kE zIqWaoB*WC!4rG=C3SkwcvevaO)l1bMRx7!z%+kV{uCA|3ZLZ@_CGBt2vt9<^9eV$X zIlYuCsbVh(dvxN!bBAb%s3E^jgzXE(n3@=Cf=k*`Cxi<_t zJ+|4}r*94xcqC@{F1pDRy}9`%1EVPBCONr4qL@r_vi$V7i5X&V^6TYIYcLH2my}!E zD22>z z5Nb)mJUC-TQ23IXyp?YH)rTt^rKnzW6k?Y~%%;XB`3(;Hy2J96s46;Ldm&Vm=EoZj zB;*K;5b7>7fI5&dln@`6)(bn%Y0Fwp&`W(32uQ) z>M;qGOU=#%LsO*7Ago!l3`6z<)8F-7o-*-}*Yk}(3<|98FLQ4o%|~vIp<85BfI?MC zEmGNpH9&*eqos7Ps6H#g&*t{@1n$d6a%=dm|4MTjh87OV#9IEIuL6g|sVnzC#id;) zl}ZsytxmhTvOG8{|Eo0mf5#j9fHLv3zejcMlJ$#IrS%zgdb-{!f6%2OD!&n+(E44)K!rvPXdVfHgj zS}NjDVwKWUVz##JG(mL4y*8HvR4D^o1$xHi0quI;Ow3EE8>6wb^a8={XEDDLpRCHC zH>nykJqSUVakb(-QrNb{dbUG$xQ)jr#x8#aVzBwHD(-(n_ZXl0i9eQ>*E?9DL&k|& z_I&Knh#U$b=ME%1L59ex{drA=OS$pEEJA&C6yknjlCzLCfiyHSXBN;FlT#KlX&AxS z@@7h3ndS+JgiKJx4WWTvRzfm&!FR16DY_8L!?z{V%1=ItOXk0yrKiX)NF<4`R`$}8 zi)UnF0zcE)C$$fgu2|YV5Mljm*U3BTL^&<3YPpdz56bOhbwp$QbSuPJx*r3y7g=J; zmX)4S%odXU8(HL;r7<`yZ2Bys1(uTy8Oi}7c#tKKD)KD3bolIJfG!KH(jO_0b4goX zoan=Jx}2(!UqG0OoY-Dn=cQ*S+g(koJ^++}s8yIo+|Q+2G|KJh?i8ICq`C)#Px>Y* zT`2TLJ3q?t#hq?)$e?^R*!i_h?iHU!zPlI>DzPLipn`5*CpM4d7DaW>${B2wf5xR zymXJG24ryrUdi7v{+M5A>Ha=%iY`-+MvqXTxhSx;XY*AlOKZa0LZaS}E5bj|>Z0kl z!%M~8b7X#B6Wi%MM~@!wfelAI?gr&Y3<7{qD*EG)t(0WI51!&!_SmqhX;~G;YUJrF zFY@SXT10%iV8FgJ;ie-&QUT`j(Rzp~4D#9Hx0N*&N2d9!r~uZ#fH<_PXNacKoF1cc z;Y_&<4Ph8oM&J5};JO0m`&`K|o=o4U4y{=TvaC_9nuNRptyONOxWQ4yzSzgzvN--!Ip@kXOh8WSO0fmf7c!-OGE+kXzCW|Z zyyn+O87?AtG59i_*4A`;dpOY7r(4h41(d}CqarXcFhWCf8}vg^DsVE3{Dr7EqpHKe z<(2ivT4JVnZ)Pd63^bHBcX#G$0v=C(AbA!vEWh;ifi?q6vuB}Sp&WzuEoyQ0H>m0` zXYzYOjRd$dVP|mEA^~>@--P-QI8Cd&NzI5%G|*`HBo0bji8bez)THx$5ECFI6p$9|z`>2e5O6U8>Ms_Yl%WbGDQw6BS=lfw_`lLl&(I0f< z>DQU3;w`T2_?MiQ9O*rCsR8zw3^Bk1n_Y!8DCa~gyQ>-&7oJ^d>$TKJP(OK}6{jJ+ zkD>EV$&}0$jOR0hgeis2uqSoMB^^Gpgsre-*I@&giY(`)j&Q{Xb%;SpVus)*Gp{fe zAipYTCVu0q1+IiTmUeigTj7VHLit~lS^6@!d8oo+85`n^DI*Wu4^R_hU*_goPnxak z#mO*Ol|&``=Z4}&Js^|ZeY#Mx zo?R>DDY*EY1Tp(oU?d6d%hju}N_c=9J~i9CrOD+fJSd1xAa(TpT#7SB;VP%ZrOUOf z4_V=~PAKCFLZXuDaSRS5a}Qhyf&>)_g)EX(V;fTQmZsEt;_;wmc^sox%Aw_1_rah$ z>LXve+}z*3H^2GnbEsoU$evw@jRo}=tws~P)X1yQxzl_8&;~vYwvD0+|GGL$zU@LFDE;5+Q{w zTS^^AhJMJ%p4%RQ@tSsofy(WV&g$cY2vbd-@UrgZ_l8`@IEWG7gLkkAVDh0X@`?k@ zEw(D4XeI0bA_3pZn-^1DT*YQ@Fh=3miE%9*jXrK=c_~{!BkJp^+2LE1I^{+?qZ_ez z0}?5S#l4(jfVS`m-oBK0J5BZ|jB469XduxYB;p-mO|^Q&L;gO5a3`zJsB-_c{ZUC? zgO`$7r#FQbeQ-QuxROd?%s4eM>1PH+xa2r*-j;?pnxAEcB3@>QSuUxcy$ZuRaVoeq zVo{fMD4t-Z>z77%rOJj1!afIgEH>A8-a0Z2mO_VmyN5PJF~lt>*I8rz&Fk8q*sq1Y zy#i!lPI1}iwAsE~_e~kw{Y2&X^hBSG+vg-N{;nt;xqfxMww-u^x}4Qv;^1TR(i-@; zyYHU~YVK&4qJNqhw?=ihk~x52=RR=mXf17s-H4Lh4DJ^F@HMhDl^186qh-2^AtbQPsFF+OzA#g*kxBcX8V}HAishjtKGOg((-PX*L-ck*lYVUjH zISL*$i!n>g3a68+l_ZQByo}yaQE@&UPl+~=+5EGp0Y2U8nCB1V-%QaqBZvE5N?Wo9 zIJmJ|J|k&^^GUkSK|hUvqayTf40e2{@3ltHZm?^LnoC*L$B`kaXiD&6k0IY~=C1d- z;A@q7+g_x9rWvgc4y~SQniAB+OXSNB#d&i9-j^bamFNAAWOryX#Wr zbE$T6%RqZLtln>p?lA-i?tQ~Fx!CX}ENbp(6x{x;_8Y5WSohg}_qX{#)351{UH}V<|pLl@!EB6q=Vy z7uy5mGqCUqt#?ZMMI5+1SSUuUSmw=x&*>CLp>~U-zaUTuX>$Q%OaBs&)Tuh$5=ryI z{Mq`4xDztOV1?L7Msg1cnKEI2smD*@)jxdYyX9dpgWX6Sa2*iC+CK%VqQ#bz+VSc+-jb9E zx>n*y_xA)Dc#t*yp>1N<&-R`ZZcp)?eVQaJEVh-?!_uq!QJo9>4gbE11(vFZN#KiJ z@g|q;f2Sz{+uh3*+|2{04MU*^)%Ld??XgZ7xNa_6B1;Rxw6iZRdcx`C+Cnwh`A z^YKm?=t~F^Y50Qs#`$UDzZwe$&K>M+x@4cF4qrH7dCUuzeGt*8GmYW``ib>-2lqIvfba=WtM z+STlDOVr4l%e}n2R@wLj2qq>RGzVYO?Emsr&en^e4bQHIo6)F2<`x%J*~$f`np9)h z*!R$4W;g=5;45o403hrJC{VDqDfv{^B_kb$u>McUQY zww@zn>BVQXV$gCHmcEAxuZFUVnMZ*HlC7sN_G9HKN+P~dmc?X}Z3eL94X^muF7{aU52?WKJf7h-yhrh!n42cksV5dT|{ zSf(dRgT$kVGEsWEDBXJ13xt#Je zgWwd}eg&>foPe&FwbnZ@Wz-n%Ope_@Xm2qgT#9 z(jI;$c*x+PSy{=es2hN#JuVali$E}&A{bNu1j4TxM_W7 zgJ*dzA>)Oa^Fn`#_OZ<)Mv(|4Zh37uJ~QTz5(7On{ad39jcRHh1~oBsGN;3M2B08O zDM#>f$fyjYh7Y5rHmBufv!0s^33UfV;}7EGO)K}{q&9N91@dOzl@EJvgHCHc5pUo0aHhEjL-nW>LM%VE zKS~|lk5GsQ986GKq4U#L@YWJvu^%0}SOl7B@PBs0RdMkSiHc#um21nQT+f<=%akrmxXTw_VFPyB;pAnnSY zBjbFVdHa?v;ef{_3&f5syt6BU{r1s3gnttkNjadT3Op6>*)7aPL_}f~A~x(UQ(d;_ z^Cg^dHs$kdWR|{}VTwy6sz^vGxbq4A_3#B(zB!Ec7sFcHYz#&H6e`I~C#Y*p>(5lf zJ>DM|5f^=q?n9v2wK3dswQ?eQak)-&;S%aRH#STviPBZd+ zQ^@?`Cfl!5994KH=>BGnVQE2v(-#TLhC1hqPCLj61#o zdo#n1<_zF7^&cfsz1H0fnll@8xw0-^=uH!}IE)}hCZE}j4NS->Vb%sLwG-`AL=Zk$ zl76?xr@*XEaN612=B?o&vH4gH8!`C%cSMalvx!vUj5Mq%oaeE(bKI-4BI}bMK_&W} zI@!etd4*$bLc%Y3-zO$;6^0L!5!>@P%W{Ht55dMT#|NF!*74&x*aBaa$yVd=j zsnUgj8>wDmJt+5|7^7TI2&d7Ah+lYDJw=R%~#j)R`=8E55hT787bMbpZ~#RlaP6Alf#5NZh5 zvsc*7X^UT6vV8gC7-}XWLc^DvZ4hkN0sK(%4y6S7x)AGVx?fz;EriAhEgCS7fx3DngJ7=k<%EzF0th?FAIK zS%{MR;M-fukJ(iVjiCp-`k)Kk{JA17l9f+qahr@D9AyhwIfV_TK|=M#t8f@fptaz7 z{h`KFV)6}W#ZcfeYdIOaEKjjnS{zANDxdS4o-~Oh4Vc?@UjC#^nfqrpjPf^$l>$8J zVp6mfWZaLVdqyY8y^u4qLu@?bO6bFJkwb2q-&CHvj8pz0C+8o#dyi^{btSFXT97v4 z*tuk76P2SrsAe}svx{fFT0Yne<)LX(OD~rRA1K+=8zQqLj!AF9tQlgU+Aa{GsA@i&i$iPtlYm|DW~Fzsqq)WxPqSh_a;nU4bsb4BQs+(h zhkHNL1`@rpkf=c>KCzGDfsoHnw$uTA=v{g^l#+)6`&zf z$PvGmKl!5coSOmEvD>$A>xBEl-+vuCR92YQQ;X?Y<5CfJbbrU6=l?>TN`m;Suxo!w zSNMBc5=;swwX2q|-9tSJZK3*(29Xwdxe1`nBj;F;XXr5}Z)FoY2^pw%mIMT8z# zB}hLEa)5qbBQPa^S}~g^$z4e1-BYqY{N@IF3nI=TNYX7o$z;t%caZD6l6YQ*e;O5-#FhCx2kY#bToWY zbz=dh(r8kiIluKV*~})L)Huktp~-5f&6d-pX1;%*kwtkU{y1-!6EnAG@US@kEIXbj z&0+KmS{PT4^0PQl*Xg$|=1I{q?I6#9UnNvQ*BdXK=c@Ig-*9&H-A;Rrf0URTemVu0 zgZwM%9pS9?j=5!N_JoszP;!x<4QqMQ&TnnwZZz-Ab^3_5pT2vt=c6i8aqclqR(^xL zHF&Dhr&=a(#5=Ge`SGJ_?5-N?bDzq;7-_(2!Q1HGxC8tpz;14-N{p5G4a7hjc3jat zXdiyoMz49a6vPnZDrwm26+T8DSZ~(vHRqd*q9*w~7=KgY#eyeknjl$i*~PRza{Wv; zfX?lD`z4iS1YP4~+lZUBuVH|v9d+dqO&ASU)Jk;O+52auqK_N76OSs(Q$uk(zSa;N zNR`FCmeR82e#INu@b+O0m|#5n-{yhlKT@t;zWrjuwd%OcFEik7pNb2isqp2iXkuk< z*do^EGT@AR|JpU`)zr)7!Kf~gwq}V$-n}p^rQ*-7A3M$#QHp~q=z92}kV%fmlIb=q1Oh3J2+8p{6@^9=h1MRpvEgDP87`j^B#LYS$ zbh!@ORLj&ThJL(SwJRp;aHeYdAW^CYi4pVPq%~=J^T^&_wuS_UlnbLS$&*8y|J{nK z@ekV3#+h$rc|rg)wf6W=*O!%Wey47ZEU_R$3t@*CbcwIlKaxX5s+}kv1J1;B2mwYQ zX~}|Ep5wb+Em7|p2iCVdYip#>+43)e*%B1<9+gNi@ny0w&i zu_|JG1?~bFj-L5{hOqtr9H})KK{3R4)SnP0kWP2Na)n0A7p1R_ZK=$ zogd-d_14Z5dJ?o<{ZUfS;@5xqx2C+Mbb{$7}Bj(}nZcc8goSEn_w%Rw!=t5<)pM5;mVu7c}3{{qt$hR*`<;g2NzM-j+iD zd;D$wcjoJI-VUuy^GU5u@8!BZtY|jLCFjHx#MV-%rh?BE) zb!-h=1~eOniDUCE*-FIw9AxtRf%s42r~m`nTHni;Us2!tbVe4t=lke=J=62kt7uH7 zOF~*%iK`vD)Q2mEEBp=VA}^^u5B{h6IcIL@})t2X)^v3!KaT|FA1JUAPO!PX`wN{eA6 zDR8hQ5J&k2Jn0u_Kg=}1G{kffzn|CJI^Lg{#j#BLepg74Zt$)uHz;1_E_(3JYCRh8 z*)4bdRIC3WZp1~v|935-Jgzv# zZ>)(9eKqlUVbDHCdT1+VjG(yu3+7{w-ex1J(swQHYelaozfcViOMW27?)TXc{Ak2& z%*FC|m>kF8hWLl;=pfrrQ)V;)wXkD^WZ;eRyjKGd@6^_^J+O$fpg%(0P1U)(TpG2B zd?oz-$|zJM=Pej7=ke?^%5%q zh=#ZS*Q5K3t$UBJbKK$&byDt#V>- zj^F{TWd9^G3i@PZ78XBIB zaq$=Phj41axQ9eVNe4ki#0w1cY1Qt0bIote5yWQktPn~KuF%1q{TO}n(7wT*8e5Go zf2iY2MwzW%72#uiR?E}PP~|Wc82M5OENVDdWVsm6Q#=y<6Sw;UNwh`Pxyf`ekl=ES zE!oHvJ)K~+LU73B$Dy+=ukkmi3k|}1^6KA;pk+xo9W?m@4c9Dp(aHbOih%{Y)u(aQ zMf9z`nKul~WkloDKd$k{a;sm69Rq14d0#It4>H!&(ew%C{_p%H37gu*27$ES#F=0p z^Q-D7fyjE>pC%6~gn@T`L2Ik;+8cD;pw01W1b~*2ePDK^a@*@CDK~D{D941p9?Ncz z5^KsS!Lfd#N+N#SSwmW5Xipu)m8RyO#Tb+dshWd5Nyj^cdl+)zG6{ zObjk1XTcXu(nscjn6}r>{C**gj|k04h>15u3t%BIM_a<98t%XKkr1&e}Kb~iOf>%c%hHuveY{*$WVC38rXK;zdiJv%N1s7Wb~*UluS zxw*NU9^c|pizl<|ufN|;RAi{)5PX)nxSpiEx`c;+W|WUTWYV-C1^O*4Zz~MQ=^&|! zdmgOMO8T~%z1;}NHL2ePn$B1~{26&YTZ{SlaxZ=>DaR_XUs3c0zNwRq4yi*8Iy|T0 zkzu1|S4%^Wdq5w5Kwywq$4z0XctR-oTS>JhlT6H*lnGIV%jsQ1JhB$Zg-$L1M2Z{4@iL2^j^aj;vW z9xqFmrU3rnt9&3uBBL)UXQXOOwV5JuS&E@3_*WmE_1Am9fluQahkKqX4yV{aVV+aH ztP7+ZlqL~|mY*_I`b_`>UFJ82#xe)*a)2gIj?Qw>`0e1R=Ri_ccg9C!5B2^@*7F(< zc{kVqrz}?}VrrjZXxxaFvCMH};c6#(mQu+2!`sGBQa+-Gzx{c`3Gnu%h#{#}6!EC{ zJ;md#`bs~_rsVb2bC5@h@d8e9T!btLT*dxn!7hPO7|1BqH%AMoF^=3DWafSd zFmL7s-lYJb9pBJz99MGo`jkw1RLcVwH5dZg{raVsR0r1H7Qk{QS`eK0Goc(M86E1~mLi>hPyk`_gyB^m8H&G&xzuN#+&E9!(j@ z3OCbp^-orT;(_vgRz&d(gU z9~$0Vl(3yds={KkYsq=dVv4nL3mg$hHylU>ytaC*R>=!kv`} zdM{+Y(}n<7nrsphHZIx@dRdevJ5;|)Ia%;blk0W1K)qCBrE#KCldE)NxI(@(qNYy-8w^7CYOMh3{{zYTQuh8(b)MMG3mP?FOUx9qNB4AqQO_iff-kfdHnetgk$HL< zv+RiaH@X}EoQ+Z$zuK%Q=>LF(?sQh{g$4I|+314?O3e*lDD1hMUmmen<_5O>8n7^Z zaqFJZ{QI&_5{s>}O6pAP(6H)kcN$_mdVVjueQ}>jTopY#%!!yuNg=(k7Np?MBS{TS5Ck$*Y@Gzscq=nrU44)G*eLGEy@jt zt|Vki*ec&(ffWJ;VS`P$gdH8Sim=M{bo^Dmu=%oNQzBoO%zPO$^JS;40#utguRX5> zQNEmQZ52qW7j@shebK8|FIZY~2umyVBK8y&*;&2NZERhnCwab)K0<<*8#>gefVLG% zqC@#q1+2x;loDJkGeTr;-BQu4qy-4gRjSvRn@@N`Pb&Hert7#NO`h+O)@jz60d9VZ?zV z1q+GV%18s-w`|4Qj5X4cjFAu+1D3txZLMqtPziVRbJEMHVUhDDs4SuGKjXQ^h+Uv; ziE=XjzE@N#+)90lGX3TvvFk(xR&EFn>7ei3+O+FJQ+n0x09M(o0NmWkrn; zO|a!NK=qa15n`uLn=2qq+W>);>vBryCAgL;Q&yB#J{we9`E0WyNkF9)fN;u8e=9+j zDlESzxU%Jf$K~@#I}e{t0yOt6YOMlZ{+^8E>!*$t6&QpNcL$u@zY(|2XQEo!VsN#w zMg>(lEw9QQ2d>~frOM4`fTNeOEb+Og{eYPOd*}8&f!3EVe-Z0|k&I*{Q!>Ey|1oK} z(?F*IPbV(V{#k>ohQRFKW#5+TaXve+a;m{H`|+5#o?iC1()-&nWd~oqT(74Am&^6J z{7;VapOAPx`ugtPy^E41ODgay0&j0`dHGYVadGn!m4zKO2!aGezO;h<{orY5i3n$N zY??b713M_l%4H^TT4&CjiBIb`L{STS1)_Kmil2E@|bJ>I>mm ztE~Ks%#QvvBPn zq82Dz*jzlL$q^B#nG}c5l4H@XLK$?fR0`dzltkz93S7%3qDO@i=v*!p-K&{+?<&*fY1W*A6M|ZhjeEAp2UroO=y)dwUf7GtQP*btUnIngQ+1XQP z6=ZeBCm($xz(qKun#oRC%!E8`8PFq4l`T~PWz(uC0I7&#FqRhGjmbMpgN_gdznb*qC9CSgeyWECqFFOno z`XAkYjJ><|%6!VE{5#u9N%d?xM=Ms)(?Y76FUE z9PCe3nB|rgFq6M^%;-s?xYE0AVQz=z%hur8)9(aE+qdg1EdaWipA`z05&kZOV0vLa zJs5j69ox6>#zh6tj1|k6uk7GO80L0_PO6ct;OXat6*a1_ghvK7O@* zcJ&S}U%V-UJ!sXJ)`g#cGX1?bz|}}b`aK!o`u~u$Quoa_-(cm+m6$ML0yb^h^bQ2G zva&F1)+{Vvz8ve;t;4EStFU0f0%T@p%C_6KZNs^9=LDYgHs5{s9X4;?j4M~JyaTHX z7cOAYqD3;*i2!;1`gLgv-n)12JD6mXH_u_|(xrdMFJ8Qm^||j|yLMss?%i@8w{G2% zef{*)PqH1)mFqHbIrE`IhcJKsd|bPB?cMVK^pqXG@87?Vq@*O++uOs>k3Er1FERF_ zwzc(yle4#s9+jeAo_vY(r5>SP#G&ei=4tN$hoa_ibFhX*;R5K{y(>C*?kq~JUqA@F zeS!sEsraSDmynJ;p3Xk<@+V9YR+;%Sq<50dqkKW~rOTH!mormwr5bBec}zoE5?0yV z$QLseDZb?S0_Mw>@JiK{N+GYSaN)wRR^UjVtF5gq%nKJ(FZ{d;pb{`+!YC}AJPzGI zua71v#n88QCG@FX4qdAh7kKSjAr;*!mBCk~lhL7SS&Zn=5^k1-Q6yg;cq$0?_w*GA z6{rpfL!rVJsH{MY;jEk#O#8a}z}?;jRthkZ6N{mF)5Zc)1TrdnY|Mghe1JB~=C)ph6fIQA|P>6;DV- za%?FiC!`@JB1s^YzajUnoARlm5+VtcCV2f_`Q>@>e7LR&TBAh$#X1Nb4ry7KHga(d0wr15@Dc=w8Jrre{_6quEzyJ1o35!NR zBD~UPylCDM(BI0k$8yBqgOx0{5-<~7S^1(xg2VroDO~~Gx^l!TPq7Ga{>8UHWBvNg z0+g&+5grMJtVGdzLmLCnk3dX6EIVUam^(-`g24kv?8mTh`h8N!Nc zH_wgxA39{D42-aO({^cTU=#wAU4fQ{C~3XWYAc@&+5^}@lFtT#l`zW8=Uiu6YzU%U zhb<=jo&d@3Sho3m5_Ac{T9xH9$@AnfdGBi1t}D?p)~{bLl}4`1=eSm_Po+GwQow7{ z=lIRn-{XcV%Tp%LLe^Q1DE1A~(#k1VuO#X)2OE)2S_Zfp$w=>#0j~dKB2W_Go;-Pi z=;&xvtXL5P2M$DHVxr9R`xPrzAU!=DHEPt5rdq~04@PFSFT*rW1aiaN-V*W z3K{pseT*41M*Z>kLcMzRq?wn1%(QITG65_ukBEpst5&UKIYF4pTFsg@|BxR(e2DSm z$II}PYz{A5wk&ew$RSP1JU-7mEiFyFkn}-bzI<7Z-@bi&^+!4g4H`5M=+Vb#`cDQ} zeeOU1{4>(am4{_f3viStX1-v&Jxr?4!uhKu7Nx7Li!=j(_3{Z;FLiVqAdw_?qTl~}%LiK-M7fwh8<*oa6p|GWuSEMAI+b?PDa$2k-{ zyP;OqnlkE_tp($}Qt>nmEI=4!GdiJ>9jsDHRYGLxT5v307v=lRMo6on$eUOhUh3R9 z0+y&}5m6|YUQwVUJ~9z8!LcY;s=U|>B7)Sih~lVKt*(OZbOBpEG8HqAN8set1g|EA zl*i|kz$xdVfRvD4t9lJotyERkXQn^6SX{hx+G4rXF>1LDm0dQun}&Eb?UUtzzE_qH zs;3+_w^RF00;DVl9DR%c+xpAa@|j`F7!K{(*WY4Q##&j|N>wz9#UzM|Th!7PuI?t- zBW!Ey1(jA>1PJNwEVQ^N^_KnO`7ganch4-k?NEChFVx8Uv)9D=(SDO#aWN~xC$rACdqySq%MI?uoE z_hU0D!_1s>{;_k&;#%yT?fUI|J?j;o5xUheo1yWA-E2a99aCNd%7$3<0i56H@~5H3 zcIcjG*r)dZcif|`7X*7&_Cq3$KmPEG*&?I1(z5{!(nG=e042u&_!haQn3)Oy(!7&Y zR8`=U#vUMw6P5?H%wrjxrFbUT4%_3IC}{iY^^OqZm4+(Y13X)}dxsNOc9S;h*MFET zM?;cx0f4za?b~(MD=)ucy)0$R1iABQs-J%R&BAnXEGYfFPyPE3@qz3Ae!ZZu6qbKT zDFoO5Veu5ZnKNe^)KNSKAJRb5;-+{|nvs#=TGnq~m`2xhQc{w^C(5i>07aCsB}jS~SHPcx>H#b)kCQLA>W0_Ar`NWpH@x~(tC0@7|DqXw$jsF0Zao^tst8dl?(KW@^Y_1K`QjA{av%4)$*HR8K5UIL z>M7pAW7XhLrMQoBbhRjjRSZ(az_N-A4|Q;npjwHEYMg~Pdwn&`%usS{teQ8d?5J_O4&40~=TC`YjFw-hN%X7S2_Vx~ZDnDo1m0&T5>Y{61Z^ed>5c2l}gG zsp4v!o~Hh;L6n)Cq8QhpiK!Z?YN3_Yt8-U%@6g!+Yqst?d0aQ_-mdh77^ON87~H3y zgVie5Ws5=v457XyIFJEqvr-)t1qG|J1Js-LT&G^}yYC>(lq&ao06ffu%~gdl#VeR9_e>KshBTQ5gpW5|7amldQ7crnVFyJzSZa{n)MDQPZz!7W+O)SWcGS@htvVVU;ta)hfouTO>#oOU z)w4^b;-uwG^SbweX%ta_6%zs+s(NBzuln zG)Nc+ULSwtaSLL9$H_ZQxh8%vQ42_Nl50rcp5{$LRN&O7he zJ{b3GVOf{$P&|mGay)=Au4N1?$(YzVP`ks+3S)!SPuNjIOKVl@nAtB1I)DCu+#lC3^c?>Gd!E zq&aJM$8x}r0isZ2zIg5&BcutuuemIIE)ZEarVWCxu!YbhkbeXyfzt8CQ-tBgma zG*E)uPR-2bs+QW&wjGj?VcRKDIaVdB)Kr^+W91iERpn!S$LLq4ifW`cSDohFbaha) ziiOlvvEW$wT^*=d`Rldq;1M-!*-=f~ch`n%59sKfr*!bxNqzF=4+aL=nb{iHp__8M z_tpFfUt;Vf%O@(SI6`7=RaT&UzQcYE>*G6^Q_R%$!V(oaVB-T@fs3euF6s2-i z<5W5{R#ya6QQhWU)Uwwwoq73v?YiY2J6FGJ0&KrWAACxuUwTKAmaK8d6(qk3l~u+~ z_X~)yds`*Fu_~uEQdnxXD%NhM*si10DsQW5jb5Rsw!>6CDbo@Q&>%!vL&ZcH2bxIV z3TUEw1CPLL3kQnz(%d>(*;WaMM5A6>|w}QHR$38uJ`m8}Nad%&M{xv=S+^ZVcfB1#0UO=k{ubBA&u$U1L zJ_`^9wgF8PTELZ1Q~)ag%6x__1Dvu9po+-?-TD>^%N;l84YYbTwk*qX*g^xX3>&-Y zEW4+OVu+h*PAsGjxe)zi_VM=#8$U_VN}YwT7jz#;agbWLLS+N@bKn+^nH zA31mKT#Xqs#(073XddzXl zFH+UvtL*Q>zQ|9nUH}?Rb$M0MUGnS=H=P;1AEW4@k#?1sA_J$%J!J9 zfSxn#@6f@ERI1Aqx6Eu^({`+`YCX#42lmag8Z=;mf(I{_U*o~5Hgc8fFFvf2ou|6v zobHZohAn$l%UpHaewSLUI-=ys8&q@bYR!4zO?BONyT%?ntCf#`py~r=tInu=jo5uk zVQzodG#;X>n~!kYnk>I2L)CNN!|HwDF-47CudCZmRG>RAzk2;O_{OI+{k}I8H)fey zt=Oxf2k%zI;Q1=vcAOno@Q`IH({H{?^`4`q>u=Rn9VWQzKgW)%+Q=31?>I!sbP z_nGqVJVUF_{iyD{9@6MrUv}rd%5HGSXesLCX|4aEZc4tx@)xn=K<&XuX!I-Kdq)(i@m50X-Nr=1@P=9B5+C+@wLa znO-oT3LJX2t2p9x@7&YWRiG6m5wP^U{ynHA>=v-eb^%w0sHgy@DXH#n>{GFE1yX@g zlvk!RWLaNK*7Ip;&+mtrtbi@u|F<5yRqww2p2m$HXGsPI_8X{&?tehLcI>oNq9~bH z`xVow%$K|Y6%d^l_{@9^OxxK183~|vi<9JAJEQiyH!4* zqB$usK77asl`U1yobMhy^`M<6cA*>AZnikH0599!b?ttOBtRsB++kxaSpm?Bn#noT zuh+yJzi?or5;6`I)B{vhS1&>VUH2%l-aKHG`OHI2_3UbaNH0Sd0L!u{qAc$zx2UtM zhy6LqEJK{fP+kF5&m;hNMSTTmIZk5VKKQ_6wk`J2&^>FIHn6R^a~7GRoHy4OZNq+l z3rk_Sj7uT7{(qD|Ie^5*6?KzwoR=(rb(JaxfL=k##158jdd37LfBmbYK#ojZ5VpcV54Z&|?gJ2zN<_p|DG?Op1%@00_X2MlJq?|a0C|H-x6 zo`=Q@5#>o1QRzyOL*a zSNyasN|>@qwPtKr%`t0L$4zgx;)rrq9?_s1o>12vcPVORsZ&K~~*C}q=HXFvf^>z<+2OXiS)H#vr7?HB zs$sW0r!Kqhch_T!U8hvHjigz7mA2@5+fVeUWh&dSixM1IqE-TCbi-rINaGXrlfQvQ zz|aF$UwT$DQq?gv6o6zooXdb%y2t@a)KE_uMS1k18hGH!xOi);*hzni&*dTK*1uM!Vphg!wj#Hb~Z#9+G zgIul+L!9;iU;rPO}*Y*JlXc^?Hh1K zWxZ5k8IB=2Ioa%D*@jnEu3Tx3VwfP`DksRfVCJHFE|f2=EmYA7nBr2?Zf!c-1?xV?9Dwe8 zy7n1oKBfbh3{+04r*hTZwh}X4%~H9jS_+6vwegm{M<}LVOWS^6joON<-`e(5DK68h zUqHBWx((IiuYacg6XvNzSe*RIN9dZ6Xq5=B>E>5fk)TMGtQe^>m8z>tzg%_dpR4T7 zy)|>i2IX(RPU$T>s&thaN^aO(T?UU-pHUOlWB3@Y-*-^g9=ln0oIR@^qb4aby@^Uz zj+bA#s+zZ9r`q%%VO{l{Z|xS{6zz_)bTtPR?fc3;71rJ~>hs{kxu%l=rNp{Me)O`r`07l0*2?y425 z&Dn}2%ItGN_pUoOuc)Lz;`nh> z^_x3yz^;5?hyiQ6wq49-6fi7RvaH#M-gobV784fr(^Fo7Q6Ld;1xh{pSI@?kb-sNtWkkhY+6xYQCi=5`y>7Fhu?J9$@^X7VWal$ zIiR_77MQ69$AZbjyu2lDe{ov8DBt~Rxu4!bOM$|2nU_Lv{T~(&7H_%b7E@RWBZVmd zf8+g+t8CfQZ7wHV8LGBmq47DcG`NDnJ2vM~)n6swqk=5e8Tv(*XeW z(MKOOsH6)Yib;7B0d0`kUkLXU?9p4>XQ6G1cM}5gMg2!^i8oo%^+F z=^E|XzE96Q@vL5X{#C7BwnmYaBUL@ThS@pd>{Ofl<#p>>98)~n@ovX4Dy~M1!b8GT z&cBQe6JlyAF*eREpQ7g3IW~@WeB-PJHm^y8MyivXYTHPNiMRPJbDEi>Rhok-mSsOU zkWulR5A-i*0nan*WVqvsFmHU0iDMvsYPHZ%1(htJ2>-HLG-j-hY~G?9w{6v+?p-uz z$^@%h*Q`+YcCA#V$d#Hja+o%+%2)1yK1xrnscs#cDkQkHdUxw=$5*C=zdNs*Dqq^S z?aD#HYTu%*8l=@zR_zRBI-ppWzgpvS$Cv|KmB4bURH~@P4eX|yc5Tqpr|vU{tEpor zs7j?!HEqy9jq9eXu4_c~?AS%QLx#HJE~DsbF{&CGq1cER)rza7`gMFk-3g_&W$h-t z_T0;A-YCZ%V;xlr2r>t>U0b$m;jFo85a^W6`&*zYl>?;q^D&YWD)MFe%)-PB>12duW=71Q8ewondHT7gNPA#7ZM zLm;dmxKaUDzzZ;AI{+E548Q`Y%=4g_$~2#{>$8sq*07mH?Zo*BMVQQDFFyC8MFuEx zRZ)!{HC7wfZ8F=?S6+BaZCZ3ybYz@C>qqZ@q8HD->h5K0g#{CmD#9H4c5PU%`4h%# zRPUZ@;C`bbtAtx(10d3i=?Y}>o-mGLibEaYt^hUC5Dy+ST&q{Cv-w;{&bJ`EnvfD=lr?WTqCXv*MW1!78b=BAmp9`uEamZ#+6vEWH|#6 zQ7=(tQ7}~2wl>G~&O!!u96sN=WXq0{$2p+`?YrH?=Q(!dqPmE-Uf zS0EgK#X;+*pZJ|EEQRIrErsCv|53cIcVHEJQh<=Id(YdSc@%&WCoG(&yn-VZ({Qq4 zK58qmS^><}t5=&HD(e$t6#G@Y`?16G9J~l|)x3Fg+b3QB%*Q-{$N~cg4m`h?zbpWD ze!j2e?j8TGUAvT-nQ5s`FajM?HY|jY12$^8@xc)s57LW#NLpP_n`iRE$kH)XBoPz0UOd)QvDs6l5@RSiINHk zte_I5{LMzWtb@j2|6=M`KU25u+@TxSuh-c-PU^(<2i3c42hE!~MN8+;)`~?7lsmA$ zrKlZ0Vz?I1ovkkIS}HQUlCJRcGjIlwE0hT`XfIi;v?`PfHh2Ko06bK*)c9J;&T684 z*Y3BNw?t|vSF)so%aYo-a*1Y5n5-$|r`ksw6{~O0Zo2ElF&#a8Py_n(RMRFomM|gA zK{#Ez08(Vt7zdI-eVQr;1S_t3ylN%XmVdD_2DiY_`c)hB%MU->bt0Jpv0is=+o3N$ z`B1OF{DLxSrHt?O2Vmr(^1EW;noom^ybw|6-*xeFcfuszC3rlm2 zccu;KJHQ})@W3Gkk{lo1?>IP-#S3^vY32MFG95_u^Sj!;BgI|gyo~+L&>W`Rd9WSe zlWut&vX~B#Gu=~O0Z8WY+%k{%6qp4{`5U#B>%oxqQCeBnGamqEQCSHY#xZf6gl0=h zsB5uo$re^6B+5PWaSoVcZTmRMu`Y`1g89qNE3PZ-9u_LDh2?TDh2Z)RD4v?>6=3k< zX`YwA2eXt5-R`cSVqR)J{w}x<#Zx@JWts0SbE$0RmlG2nH>g7s2k zzWVR}ck%K3xxV=FD+ZrQDRm5731d^eM!bX0WH&v|6uKif-)0Uxl|mvE7oV!=m?WEr z_b|(oI@KEju-3<;E*Yj6GL7{zG8-to%}-n(3YD?k!p1U>;V{w9)uDTxkLfmak!&lw9~`%7@GYeSSp02Dx@ zOPmTE1E>HT`v79804uhxKr8#D@$%694{1T(0&CciF$@!dy}R~nW&RpddP@~AqhW(a z>VtPaF%|FQ55INC+g+7IV>No@RMkmqsK_W^f(u}a?tbEi;tWKi%MxeAlljaCZzzwz z8@8G_BHeY@eFmy{>jPwT#nXL`8q75ST2WI64;W^d(16U|J^Hxkt+mGFj#kT@78*KW zh($sGoH<`&yrNe3>DBi<+^4$drL8)5?BuS4Yv|QUv#e!<2M*GRVIwUA82bh&c^8d>j9)PWO-nf`82q=P5`U7JlBxx<3$l5ssO{(WS~elw>LnA1gkFOk;>rO3-owj}xEN%esRaO12)B;UkOpwWrXq z4b&o_fsY)2GmeUbtsVApbT9HZA6nMoqev>tg^Tmmp;I?i3azZLhzJFRh8et~wvz6Z zgal-eGTG^}q=ZCtrrk3aN~Yn}W_ zc{Apil85Iu$AxnVA7)^HI&;Q6^ModA5?)Aa3yWqvPF55CTZ!+>B>xUpi!!{BHgt^rDfl26DY129B#IY+y|}&VBy&o z?%BOx>(_0zYf`*;X@j6)gNNzuH{P}`WmHMJ&j|xX>eDw~e@|7zq8yNi8UO=?fFVFh zP=A1e_^nwEM6t&NFsT3)a0-wWtN<$D$~Zu3rUho#iDyoH+OVAEU6z#V5gmSY*-AD#u05|C|b?b?lY%)CpyGaNVI z$UDb#!#VIwb51yuaUQ%^m^$!0v7QHs1J3|)Ye{{}JHvBF#et5-kEi1MoZwQ-M1Y1ICIdigA-EQn z%e@qW>%XY{Juv-y^Z(Pz|8{8o`R8Bt(o3%xY+7z`_mSg6LpC2^32mrmcM`4dOzjvEi@hTXfAH+7o!Zr`b2|M-h0j-I57fuRPeKssg- z0p;BJmI<>M zy$V#Ix?Yk3p&#LzDtCTs1I-51UJz&;TlO z=hI+7DJ7dza%!4gZ=QP^E-02f57_ou6kafTD~7P3SL%T!WU)nw$AZlSYjVSXmBu#asrkWxoJs+cq8T z-tnH&xZ^$My`k|3Tyw0zCIAbZ7AsmxMXo7f=fgY{V;r_vpLf!OUEW2u%d^aM{swG4 zc;%g?k@n0p&)cySE9!4%3xF%v7FflmmERQJCDP@RDi`yYkf3mPy{lP`sO%cU)f_ZO zC%J3lQ{{OsXfXMg46yfX(Sqf!5gAb!RiLmGmh+_$T>nMo?}6#xn_pP|@#XEe-Zi^Q zvVr-)wf2ROIoQeJ+yOM9#PV_DBgcmuB@zV@SVdJWRnp(`ij&fj?E$Q$jKo%uaRP~> z*mxg%KB|1|*e4a$1{*tud=RO8JiTKgFZ=Xqvu(e8lmTY!^iW-cLqZf0;r3m=i~@>Y zp|+WIG__B6P3zWC3kUSlnz6&RBzJ)34DO|A{k!VW`h4Aac#l@kpQ97kAJ)?kpRu&8 zIC#+o55(}H<-CdW$+?diJ=p-qfXe}D)9hAONqL&xpqb5UQoot9(&#!zN$g}FVH81N z9Y_H7xn^81((2-*h7(m}mCCB>&I7XoGB=@aS@)|u22XjV(ST<=x$~{7-F@6~5JEY{ zk?5N*zt@T-%Qa!tI8`d|pteFKb!yvD^Je8~_@G=3?mI-quP$cbbpPF_v?hP8dC8l) z>p-<&mp|JEK)t_Fz_4BQfYhtZCzKY-D}Q^+E87A@QP&FAOMxrvu|C(z2dxbZ{5)G$ z0G3q3ixw=iEj?ztgMlP?fHLx2dV;{Fm!ieunfq8@sUHHHynlfxk}q>813#mplljCZ4&EklSc zKoIEl!MhK>u|@6Gy|?=G>a7M@_0_&r8;u+~Of{?5P{%gy%zm|2a*ElmGQ{2&vkA;F z*ak6eJ%|Nz*|rCEG#YrWc!zjDXw>mu@qPf703}17BaV}CdI11WmZLJy3tQEzXFq$t zndZSM=jO$21~(wc^^3r##x^C7&RM!^=xoyaNyv^Gsm+_!-?mYah%^! z(@BF2q!U4b=ZX8u@ywsM*cuN+6(9jYp>tMYx!g-3xc-aE-viUXH@~p_V+-AF@4Wq< zDWvHR5co**aR8h=#fC0wlny=~!-kDA+qgS!zei6!c}`D1{j45%;2~|4{F?j`Nob)Egq z@ljEW*jH$1sLBVHQQ2ZwsC}ahgVwwOy*00YcT-yz59_DJ4qTUx8l;sIM`-@&!CE$L zoQ__1t&U%RNH^}^udW?B84&St1=xX`QYFfn`aEmqe6vk$n3ZGD3YZ$GHpJV$i9s3j zva_11Q=6{V70Tb(>*4r>4I-Z2BXY;-$dTjLEzW)_1O~Ywf$po?H3IUvUYtAk!aTy= zv7id_;m2kcWs%sRp1KJL0FToq&oqahs~tpUdJ*)D+OfhB4yjzj!iuzK^n)UF=%{<#9ae;r&|#)Dnf<(wEt ztpr->KF2(uN@$n^*mRwH`kXztXHGxj8W@4r$QU*_*USb8f5o*1UP&x)>b{39wrS-s z_x#l$t5d3L4EcH#=tbau08~IL*O~5Uk_2%602}WCiYw1qyY`*crd=nq(XQXHiB_-K zpsw9|8T|1)6BK{P_T84gm3sqhW2;LztC;FBrWj+hS}QTx;FU-kG+M0tzjkf2Uj<%S zk98P&4qd3Wp6LMB$Gb*cHxzx2kw^i&ldrw{mL`m!VhyBmV<*|W#PP8V@0j;q(UUA)oaSccmSx=n>b^&S{09<2w zFL<{}tbm!vj;*^aD;VL!xaOF7@E(MPR5oyBocO#vgFF}P2c?z$uUNjuo&n&su>5;U z;kWreqZEQ`VYw{JZ@)^fzVf=kA71=?ocOr$VPc$*6CbZFTXyKHFTc59TlTwJprP^Q z7hmhp!RytwO?wBsl`SM%ObqEHafBh4dR0?qsC@7MSUyH5HGCjZT-i4tSN`^bm-FG| zBgh95wb$$7^mT)VDKH>Fvi4keR}En7YvF6N>^|o*jkGhF4Bw7 zJ+A}T9WVzbK-f#sio=%&tiXb&pnBs}4_KKFpn2eGW(E$Zyk!9^pIZB8SmpY7kWXct zZLuts^;jP@8S?;49Iy+$;qZ-aAB`MP`I&>$J8!rDTw|UmppC!jT4x%-gN2ao6%c*_) zjyink2F;i;%brJ`!^4MevNWY0P@)#17^9K`q4kMI;=nYsPF?ls-a`ZW^wrP-gUp6C zB`Mj!6+2ecR)ClFF&)50mdbRWseljiy$T$1E{hf})5E79(|hlJWPpbm3CbjmLco;D zJI1;4P63%z8itrY0J^;A{re9wdsqHu9nWk4aAcez%dt=I-DF=}KVX>S0Z?1GMh;oF zc#nZ%OoaaM{U0sH?giT_$3DOQJ(>eZ@?1PnX}m>ex$ zwAAhe%Ip7@a9G41Csz2yg%sl0z2o3ZI7Xu85YwE9J4D3cx72e6W?7t?3pyW@o}BvE z3fp1(Uh&prKLw{#*cZo1gdfH!EYGpAUlIy=5p*al^Y@&e3(LQz6oPAExoitIu5@2F zsNcvw3;-h^IX>!>Cr@=hbfhZqmA?k8UM;xHrcGN6TI1v6P0^+DF$7xq*zwT=LcK0a z50(L0jstaf(!^;tkM)2AZyo*yF4z{Ch3IDQ*QKlOz4<2Huz8~<_v@tv!v|~C_>r1F zw2#JjZmmh(+i6DME~dN=Yt=;42ldggKHXIGDnE-rfcn+BQ&+S1_288>lLT|eu9Zwg z*slVB04(4Iz%m3Si1ykDXn-nS}D?M@e+Xw zuNteE*i?g4&YKD#a4moYKK{ThDj{9NfFf`OtkSg#@By@BYbsf+q=UEXboQ|)O{t{& z8CzFWEz*!qo-o;*eTo+;Ze6paBK`V{?@R$ky=1$<5&Hllfl&`k0ZNAajZG?n^XXRi zftpWkWt??5CLf6YxdN_$JVS5X16S5#d4pE-%ull82mD@t^$i1?o!hUq!Meq6h#-G&E==@r-zlFJKE$^VDpfFS@mXE);#b)`4JP-fKAVO!BM& zt*DwblFA1L>540^vIq{$1N?x!EBvmp>*oV|pSb|=>QhZKOm!s|F=hh5YxhoF3|3KM znb*2yOM_g_50w?gnRU4a=7`1i3P39rg%i~k6_odba|X~kKYB1YKJRZ&DFrxLj`IUH zdDgiGKr7da2Bl{w%e%*Kfp_g#hvySm=NFz0E`N%Bk z6*4_WMn+orM&R`R`|nrf%9Y)_UC+WX5^j-HAW|48c>}BQzt(&)3hc;c*re#M{{s3UY|AbeGu^JLwO%o^1 zaX_Est_99&4%Vv0SfzWJN@NBAmRP#P&&5U)vjN}`NCG}F69BeQK!F^(Tj^$|E4^&# zvgXwE>{Czc!}s1d#~r~2eVuQ zpAGAuowzuE?{DuKp+s{nfP1>}Jz(_!)(3gM2nB4DS*}{l%)A;NbNqt5)1%Z@%`r#juTzs;=tQ ze75q_r_Z$CiTwOkzQz6*fNPsJZCrz*gvAY~a2-f=Q@XVKy~)nDX(Y`dZaCM+Q#Skb z>0=3ZD8S=QH{E38-tX|li4(1|PQl7LL@(htn?ye(1tOjL@#DvBJNz#5H^0dw(?PW* zBjnk$XYJTpw{ERjvu4>o0PCeom)i6V8#Y*sb_(03c)$0B<=pj$VU%|MfIWb zHy>OQ3e2CsPqvMM;w(CGX=byfh&Lvdr!cXzq@ztY142pYLwYTUD|b1?;ZoJ%Nlq^jm19Imp4Ak zK~e_;SR9Amc;jPt{XbH(oOTAYcw76xwWj5#2hJ;23Q@S57UuvtIwr-Pdx+V}0*k1P z*axDxKKs;j8aimG0c&stV!c+?zPiN_vu^9CEVq6Uu{IZpXY@^xtcAyc*h zL|}3LoP`&hX1sIdJW*MJONKaVF^~N-4buXqvn&iN6;^~5bFb>^YR^yni`nJER) zAlM!z6C@H~8J-uq_Ay}rI%xp;LbbW)FFe|!50EP#a0OapYb4q`;K3^<1;8H9MECAJ z&5oP-SmJUvR$p#8mo=f17hz5A}V=jPt48#Jb)`f4$F4F9s zqag-d0=KBE9J^=l%6z~Tm|wkWy{_H4*XDalF59BAKVOZr%DO~hK#|75tD9@Yee=zC z_U>aI;1w^?OTp?ja6J_dp#AX&-#T<_H>}@4I5G0ufntma2+;-L-5>toTleo36Lf?(%mq`4Bg$*&Cno74c*eu{rP`?Ydvpf zty%MO*1hk&uYH`y31QttxBdJ%EcN+Gdh`cmkkj#M8;1l_s2Z|Bv*Y1viM=Ye;j!&{ z)%Gi-{T9jUX-FW~Wlr@9?PuH6u+Lx{E8Ekf$}`|nshYjlSqgpY9D9pkd5c66-w?&EJaok&HP} zqvfFoE+;{Y=s!TU1F_3_QZ?slb$*p+Z{_CbJy!}_Vpj{690ha64Sl=R5ZVvERvv3d z+qHb|6QG)KT-VuY`nkFJMv3$2Y8& z0BGwxZ3L&v!Bf5NQSBaxS%%g7F{rmf?CJK~G{JiKCTSEDvlOHHNXLl#k9rPuWlz>i zhS;HpzhYA$$-Q$z+oLv;?0C9P>;o6O6l&0VuX10Q=h%pd|IGq|c+m!++KDwu(g#`; zR`bRE?xfuhXL{D(FSEBe9lh2)+AB7ww2YQ`3?bT|sZMksb$utovusG2;q(ZuBrs8B z!%?;Bv#}VPERwR6y-+IoV2-)w?icxHOaM!XTnO`(NhK^I;+gH2TnE(25IR(7km9%; z2tE5>O$y4z?&2t)LK;*7M##{Q;6+c`>tsiudiA2xEV<`C~^FJ%r&JR_zKh~T7W&MYJTDHk>eEf~5EfGuMRG@=Xyh%Kz|9zau zznm6)F{7eMVoJS_!QMZl#p0I=(GM zwgZ1ThVpx6vj8)47FKkpz6`ASH;ICQrY3d%cOL1A0uKO%Z=aq*#`%Wo{mECbAo!~s zwwB{WjwHNldb|yr566MoeyP5WcZYD!u*M?BynMOFGR{23j3R+C+i!|Cjm`r7KEM~f zFUj;GiT(e7z#yy>GD&I1Juc(Gv1IJ%dhi|%CIt~02R77>ArDLW_HV0~5N3q%hu9W>x z4zyzq{<_YSuU5g*#k=iBK9q*&*25wR7+J*wLl@Zd3aapF(MfF=^4dzA-Rx2Q<&gq4 zzrlh=#;-tDpdy1WY<7lR_!6^!9VLicv_6==T+epK*L&`YUa0|B`PdhQ3Du*$il-x% z0x>PMZ|PkB{1-3waN+8I*4LoZY!ZwT93l2&W1U}8m2q6-24v^wj~EhJruzMI18YeY z^27hv9&4psCB`KUd`0+bFZ?)Q@>l2$2H^UF`k3XR=tK%dbwB^{GZ%{!LreK{(EPUv znXLeqOo%Eu1xc{2q}Nt^4KAUSQH*o!Pr_nog4bWuXx(}>q38ss=|Ab0=lC7S`ppIk zKa*jc-S&t67N4EbYg{XOR_V0rXxBM+UwqwUu>pg2H)|?!zcvjveG3IWrlb_i7Y;ZK z6zb_IxqP;QT6h&DyT8$bHIEohbl8`NH8h6hIKA+kA>E%sF;oE{h49rYlRK3AuVe!x{$f6R{yLt=DccS!V3HNH@66XO)nZcvd z-jS=QVY}i4V*SMB(sYybT1~Zwq|(XCx-xr?nZ^tS2Ory6YlQSHvQFg-%uZclSlP%= zG_+Vi^^=9IKwC_yMQ!bkT$xHk$uHe2r4_sf`v)L4w?ECZ)l?G{iI>#PZ|Fjw<(|VUAjl&N}>7i%IK{TxgTF+6p4*PCK_B5T+4? z_>RYzmfXO7pU65I+c%SPt8oH5_K~^{+UeV2T8QyAFWAsP(Sn$)n*8+gsKCO-_44@3 zVZG97@iGTtwO`*2OAWM+DrV334Xc}P(BmFlH75mDIJQF9WC@kzP$8cn7gYn)s&Uk! zZb!>Ps45VG#2UMWYUFHL@!-e{rf75uJY$VDG89gAd#q9zgolV8F{q9qRzE5n0=l@Jj9WE1O zI6ic^L0-?@~ zC?u~^Z18A+C`K9*t1_>WyTW&86{DPL$)j$jqC9wG=tT`UhvZIZlH4d zf-9J6E& zZJ6QmHM{3;(*0Wu9kQp}Xz|@s=`owGWhsm>$o|Y%)jF@PSE|_Hcj6taY?RZm0SCUN zsSQK|?-p@q0rsPb)0Wtu?;lNjY697w!Fk{B%Je&=-Qm?%vqNzENQyZhF&e*W-~I8W zp{U%*2|Zr`N>^&_&+%${`ZNeJxpVwB!(g`nkdPuEKFHJhG)UzcrlKiITeb)>NiL$}KuRIaK&mUdWWld}uue2&J~hhCCUJDtNd=f3&N zWY;V`TKH_Ywhd_q#HanG(HM)OuzScLvNNq%>KCJ^*YW(MjqSO#HmYIZI9+{?4?W%R z*KkduQhK;)v1_${l;qPry4s5^`SW3$MkSshTs?3#piawKZuHDiqwNM!a(GK%Q*|4$ zXxFR`6QFEZwAi$_srsW)x9qjSVRIhSpkrURRiNYGF>L=n7l;m3S+ny~s_JSAJG_VA zdJ8Ain01hIG#iX+Qfs!rJQr?Z0xORKtV{R0mn!@B?bRcO74isb<)zVqS(`26m4C?O zZrC8IX269KGmYPgWR0^FL#B9OJD`ei%(?}Zw(7N+CC84Hr2LZx%xIh&3SsT>&&1PM zIWL9hfInz~7hg~O@t=DU;tmEfp_A#CvMS2x|%5 z$JNE<;$|nCq7lGyCHMNi?$2r()^%W`*c;zmCw_2ZXG^yCKAaVhbEe{TiWnDJ7jb-~ z?@ByW`SKc~PtEUXKYCsYQj{JrJp;F$KRX$ZZ?QDiuF_>QYiBL`S8nLN-ruQ zFX-YnuX;~yGjge_CRVRO@j9zf9&x+^tLh17VGvUwLK#l&en~}9+!*o+vog_6oGBba zv@+)wbS_{t-?7H2svM-ynfOC9wQj#GKtCI6sZ2KzI}rV%)^=qf$-G&JCR2dGh|--H zYEDT+a?*20rA|DJLffEL1(MI^9tQ8T$dYmvJQboy3d`nXVUbky zGVBWx8rv1FoXyL>m_pQ}D&dY(HV!L|(yU09px;lP(^X52^6INKz+&~=>uo>iMGi#i63 zkTXF`nFc@}(wLrt7B72dK2RgYE6^DR>H2kf>*<6>TlsJ@p< zgL!>&FAJ-JQ=gwo2FZcqPYj`@W-cfuB}}ko{HsB~1S5RCuK`^iHnXMqK&U89Clr-R z=A^{;7%`};nARLEgz~3CNzb_vIh!B;-qWt4T#nnlFBKUz2s&?caCRqWEmal>Z6GiD zy~?BBzKND-FRJ&)zlhnyDeGQ1M$_nekY&ZWb;vF2f@GG%GD4-;fmnVllF?9O&|`B8 z;Z=E0euW^C4{t{Hr{h!_4_@WNZntn;K+T%7VWY{0)8Mn=1DoNHi}b?Zf1b)_B3w9}GO%A?2>aHU?b=t1cuNdtnc1?HOvW3Go#lJK( zAs*(k_1)#%yK&>1{;)fEIg9$VQ+tXNH8i@%Hr@H1#|35uw4?`g+gBjwbk*|qByMI8 zbB~r3_Y#)ImFsUjkz5Ti9qJr)W5+DR_c15;cKr*k3~F$<9CCC1dbb?ae#N;~GS`G1BkR*; z?=&&vUqx}*d6>ukUyj=za)~)~{y>Ch4jwl)Y$-sd^kif&iy_r?MawAFDb!kv^A}-r zO0;$abp2NctBy^V&STxOG`>0;<_hT|D)d{cKz;{ zttW3WWvq=}4B>30?GO5!X87(2HG*Lo!bZQ{KRdT=Z4;1Bc>drMt7P`yJ`kc3b}3tE zGO56pxH{%h`VU$P;uka8l zkBZX#A?6`Ud6O#XS3WM52&m~kIOg_NbHsuvG|A~Z#Y?^f?QX#*(f^?oVqPC2{se~; zQfp{~AI(S5z)RYc8%prDMp#o%*usxWvyc`P4K4!On6i>;Ycd(BSy(!(HseahdRZan z{k5`R@Y^WY7-+&<`^44y@F|@Z(~=dXS>!g;+cF>;ZfjPrp=D1}E}4K2WDi^GEK#psJbIWDPf|A7kkqj<%+!^J5yCv)zQZ}?C?-mlDm)A<`Fj%UH(K#fq_6y ztlMRQxRZ!4N=YdJdqU=c=IKl3(`oxNz2`shc0uqg>(0VIe2b89PLb_icQGVbziXaC z1OBS;Nc1+n=DBg6NMREEZ)MJl!}(fy*P@Y`Ugb@-0q`qp`XHLuBrj%jR0k9s9^hA8 zv?8x^LXlWGhpSD99HQSJN_yLgNDEtN66-X+aU7`YxPWBD!4gyOY>^ zJkFgc&AZzH2P3BB{9Y-j!@R-T&D+@l8``d6AG~{OA@(`78wKdCCM`0g3^@sRz5b|1 zT;~$r<`LmyM$w{dN)cqBCDRNhloSrX>scD0+DVa|X){Oa`}}doO;@$?A7~i)u=_co zHaBNgc~F(`qYtjj3{!EUeA%Hxk>)KCmsg)1>-dkI&z4z(;a=E`U&^ar6EOV=wC-?&vYx}I%^Jrr9=;IPG`)s|rYQyo{*JG@M zq?Mv?i&)2T#$O~lXDoYZG{vU4Pn>k0;!Iqz49Hn=sabHmW4lhV&f3GkMH^wvqu705x>89%P#Awd?G|=qK3Vp$qoVoX zDd2#$0u+Tjn%9``^*K8OyHrlDNmM~b>DZYx?|6EpB)2nj{ja5-&~2cYn)JSscKc82E-NaK|Yt)p-v)9 zo)Scr=Xc01+gf$U_v=v`SU6l%_*Sh2HAn$fi6$jfL6sT}+-UANA4(^MY@gp#X&P`X zsjqx0>I~4dyzbXT)GAVd6J!>DEzp)lFL8ne0}kQ7c~o3E&nd~301uT|Rscb+wfXA2 zN)$dh>C{d7alecjt$tPDNPVzLi#8pUWP$Y~E2>E{Y4({XUV){2X)3gezF*J_R&c{} zUTb}+!){oqwHY2a1APpxbL+Q*X;(^MdfFk7g|d9s_h>8rNXfRFF=?GMs4yXd4k?8o_xqV0Lfw@eK zY76dliI=XR19fF(u!@>yspaMnH+7@SvC@2y?uhs@UOMVzGxpmBo zBl>k53DhEJ9qZY7oh9O3G#6H@39Fn7rb#7AXbgE{Sd1{nhdPG-K3z9(QEo3vn;9C9 z6HIlybCO4tEO8xe@lem*M`XCRseZjvwu8%8{ze%4bCkA#jVduLl4u^z-JoTL1diZ^b#v4`$brtyL{k^jVZtUnuy`sv7v8gWim*ftEBN z&t`v^cb9!;E%o_U+8D>4b%S=n7|UpI0l`>l2IJM|(c7?a_jUnD$q$Hm#O0T1mzL_bEq z*#4cf&HJo9>VJZSfLtNuc;7^;~@04 zuhCOX^X1$Uu1*^ix1#N=83^7KnMWt5l53WFF=Mha6R$php)2T^D`fW*3z%99B{616 z+%03)qyA6{GCm?IqT&TXK@3i^=3+|Ep}Fr?12*2NYPp8TR)=BOyhXAI9R$(Z=>}=i zZuPlx=mvi?*CMWaX(ZKzeyc<(Ni7L6S1$Enqt%=l*MIRIU$Iv)kOfkWWKTt=d8{v%*pAL2@ndCcZx=Wj70! zm&P4X+V1ycYH!$}9CUQkulJU3HJP8dPPoLPS{~J6{|!PTT!V^8tv>JdhkUlHcjG(= z5CnLno>hg+>qNzUt+Vt&_6m^;`DFn8Immngts)~)!^cI(uU&?bvg(F6+8zFv?Qik+ z%UlXk+4|YG6g$9b$vS054}A|$4amYdX04!2SS0wKgwh zY~i=Sq_wqVns>NsvvqK~&a0n|JzZ2Y+H!pIamAON_9>)F^>TNw_+n6cjX7}dZD>fZ z7PS16=Ob=)I*S&|q=@e9$b-D!+uXud(Y9%WZVWYo}J4VQd%#;Ky%X~Kf7 ziHt-e*MWiZ47|;w!FzX;Nt%gUO|7}vHLbStg$acI&WL=>9>hB9x}LY6_JBjftrvLz zDD8hf+hC#TJDMn^R;^`CCFYdhXO_uh+Afp?xJg#4jg9#ws=-I%*VC@0d6JU!U9ROD zWZfP@bX*F!6tk)^yG-a97)&i+=@U5&$0+j`Yi)ALXJ6Mk%(`Iq%g)lWYlqi6PGp?Y ztKA}PYCR0HN)sy9RdorbW&%#7D>*VqEX+GG)i5N1L|#p-#G zZECen(;_Ck;{ij$ptZlF-pACS>ECgn1vA<}_y65VntkjF{%@G{RQ!Q;>wLUJt-(Qb zC;D`=HUps~r1LBs^d-RI+pFb|Nc6U2 zj&>uXFsPy?SKUod)f=LzTKMA`Pg$oVwlq6A7{tI|!i%Srq|CMFF>qsb1Gw#OqaATH zz?vgW7#CDI(lh}xa?gJYhWaykbiXN+XhQ#TdN%N;Q&lTSlbi}iw-E#Nhnxn(2j|=Z z6rVS-pfE>q=kP1N7U^J29M_o8DPqw-acfVdM6!r^K5Qoau8anVa3_&fuW=Nc>9T8g zwDUs~g6SLx^lJKjke@BhEcpHVnK}+U=M_UVGaFlP4j*e9oWDZ1n2dnY=FdUuVuyXr zdkf3GiMh)(F^ht4Lue@_Us_vYLEJ3#*JQ<<uMMff@*9hh5*)|WD%SaI{MB3 zz>2SMIOV>+rm8@d7C2a`NoIZs#=xodW~%-4S_0M=0{Ki7ScBW00EVl95U+@ps5(*L zyx+a*p>8Yjm)O(aKu;ifDuK_6%dRT6=N3$rpT6=uhbE>O2B5wAaZC-Xiq;{=80|bxZ)i#jcYtUn9vvez@j3I5+WWTQMBdClGc! zRB?MUTRc*uK|Ul;vHI0vG(O z9NG32a0MwTpG2^9u1OFNtr7(ww0zVLD1&4>37wd=Y~N2j!^UcO_w?M9kwWi z`>hOR%g?cn4kOsBb9Z91OuXnKGq0G2;++E#9oCapCL$@51=FZn4gai;k)N?9koiDAu+Fw z#J8V);`cgA-5Gt8V~J=dZns@2m7lZnI%((eSOICMIgzvS>RIK05_wffO;)>{QGb4V zK^y8A!*q~`N~Fj9n=im7#gcdRewc*A9T#GrmLmKCd!=bKi_<{b!>}w?2-kh-k3amB zQ?F1aq0(0B7fN%#b%Y$X_zIsFi?z|3aZ!2xv(1TKz!TYj4|c^?Y4m|as$f9?!U~Q9 z)`T+>SphUShC2}t?s}qgg6`v6I6Reza2}2czeMuaJKR~vZzFeT%&?en>$u^@pp=fg zDIxt1+wlJ!l^0klxQvVz&A!^2e5H&wyFZlYet%TozUA&EL@g95m2uZCP72mg)0V^j zA~k#!lu1)5n+da;7<(n5OVn&0sb_a289aV{sYi3D1_--FIr#HuXpwt0gz|? zRo6f&)8Jnxafk+?V2!1FXBZ3SMDE)>iQI!%ceBH-QUcdlm=LtWfuF3UE+I1d`g-at zVa)um`yn9(XdoUNj?IHLRf9ptxEs(9tk#W@4`<*<3>&s)2@BP0Pg#ncc}{$2c2?oL zLt!oQVNqdEtEJmZi`SgKLxi|{OPbi0W8CIMPUuFKav9|d@x^4&SH!k@M_(ugh?D+A zno1{jSVg+GiF;pZ`(N#O4pDJwGsvI`JH==ekNL9+lL)PTRf072C9w;S%n_;LkfZ3y zQWh%x*Dz!?L>DW0zB7hE7zUUljRsBn)PaC6z#*$0w_OJ@#D9^8u?Id?0~ukr)(~RU zqeyB9R`ec7nNCT!DO@o4ryfWZB4FsNsxR!Rx-exvYWf(h*fH^+07BEyXIO3jm((zm zPP*Q)gX?b zGy=Q>(Ly6!tM%%_JQSb{cA)R0laGN;KlnCgq6a@?wsx=vS0aCzM^`{d8`Z}H0j2vm z@)A3JwxF?D#)(gCY~}cB5#qQ?mS7=gzr7gEid)e}gVxoKY6HE;#fxqgtw%B-3x+*x zt_#vcQ8C?-(G){pLIj57{b6ndvXXezBJ(pEorwqPXl{&6pqHpa3C}B?)FoKRl9i5j z4KPTbo8g1N5GMUjERPs3(P?`eBToDj$(VfMw381IDXl`MU{*B^P;_l3v;vq1*0@Co zj{jH^%dvW1=WKNM`=J>3^%Sx|xBgvhgV{u@;X6(qt++T zR0Sf>x((L6(>KNAJWOlQ&^TOWH&94@pfp=L zm?mhQw3WwrL7H0lTkA6+3Jd2jmuorGydI-nfamct3>LM7@4w zV%Z034`=eESb50S+m+k)u@8)6J0H47P%$|>pBZhFqom+3-~ISci02^Wv;2!@0*2db zGH~13hQHtES^*$OFR|XySj0L(XC+woxzSA8eB}ki#)I%}2>6^w(E4UOLvl)o5}0!T z_M%B?#_>usCuoeY&Al5$jMY)NZ*<}|pZBM`pPk^6Pt}CS9xmk%e!Sa%T#B{68rf^N z?6cGJudl5s8s)lE&ggbZ;}+IBfPXC0I>R_{Q$|yk2CIOkQ5Eg<_l_`aeBF;>kN&r| z%`I^dxFt*Hsjm|!y3aER|frIh=1)wmnNGuT>!Dk)g-HoyrrEK%$`{7+kl>a^9tg z$(~z`RL{d)i$^P)t+w@ob&A*rho{35hwI!P^)f|#KG`M#x1UQ5cNlF>N1_1MtO(Qb zRP9@L0?yH747~^!++eku=NKkIl(F$I)FG@M9nubhc|Z)2;vUtMuB$7J)1lSCcS{{` zn~u3$`m(SB(p?!8?5Q)8{O{JGBrQZv3|H@B@V1TVvCMu!);ICRCc}^Yp$ySUY4Yq@ z7Zq*y^+li=1^q3$RE5c^;7m*G>kD_Oz>)~>3NeL{vSaGUR(!b7j`u+92AZaYz zdSakzGEp38Hp4vOvlFKeiN_IW|a2#!BsU;Y3};~e?e$M_P0{sVxiN8=s+J$uS$xM8CAg&hpP;1uxYw^ zn3nH1?L^Pr`;ROBAnTRbC}zR^PJlS+Jm2G zdw_umAB%|t?jT(FMjRNufgYzzj$t$3D&@^w%WQqu;KgaQ4I%y z*M8dV>+ea9YbyW!FMCkmdNCy%_5His$BncHrX z{ETwaJjx_2?U`Qg5lS8toJkI&F!7suvzxWMs}YFz3OO%zs9Vd=iR~tVyNoi!6xm6N zrvPm0YUK3I@=>&uwUpPLsL#|iQCeJa=4&@bMO}w*P+2m{<|=+8>Mw2ie23m_;Za&C zXs4hW^A#M2K4nhE2|EIRj&LPXgez{-^duJa`Fi__=Xo5W! zct0Fw^>x6#BC6Zn4fJ`pT}eeg*#-xgwjch5ABN+TU1;u4~5KV`rytXr z)5QwY#WaC=OOC?KBf@}xcSH#L-+)I-7zj}dB)-ykeA_?AP+I0F<~^TrwMznPjbMT- z@+6HMhh3Q56dS|3{XMg}nfg4uw$5U7Qj#mS(vr z{RZ`jgTGNIhP=fx@7vU`UkU2PNw$KYQXV)F)UfHWU z?|sweM$(I3wzXIdE~nb0WLe9ILOxG@iy}gqX|cqI88m$e0-GniAhDgOHJdcqKVk%f ziwJ=}fEv=4`D&DGP!VPU4tVa{$Mu9E7aXu^(Ye6>3xc^|{SjJ-j@+|({?0FIkOK_% zWzp|7`j{8)tmvy^C>uE$ABd-D{DjhrTb-J(oM>HOCauKEpQ|XunYP=6cxs8vv z=W$2m4`z@XfqjNR)iF&>cy`-e{d-U$Uei|ee&#+1M@TYr>O4Z zh6eHeCvp&X8!Z#}k$Qz!pkZsdCe~5$`oz+X;nH>A)`tB#)olgbx9R^#7O)=p)q&m~ z%fX=$dT7Gg4h>Ei38Lfvw7Jns{6qX(d2S_h8i}%wjt-e*7FRIN4Q<}-dL-UopiwCV zm%9EZgkC9n6Yu6eD7Bzb$HF#Z=x-3~TQr=ig-}(X&W-gDZaKNd zlL_PwJr6H8DQf>-EXI%(t&!?r%|x}7FD^CjGEi(c;)dA_vJXMN=}(tQ7I%abkEWGG z_PFqQoV;Mq5cwGW8@gRDQ0__NiCb*d-}r}oqA;;2hP>S7XaVgOq?s@i6=V+N)$0uc zww*<! zp*8n^;X_zOmi#Q$kZ*wo__&5@l)`1`envUp$;iQBQ$UI6 zX_tmMA@OG?I}pA(5Vv%?;DO7wBqr005!q|B8=c8V?7uM;YXVQTtkb=$zXr))7Edu`kc2DDH zBRo4eGp+9oXA*(@!ybU7HQY!X;EQtx?9s%26PH0FFAg6sOYlA?PHBG5R*kQwL8y^K zr2EB=c25Dr!Rb+=uHdZex^*?^Lvz$#(kHrtI~pk>b7D+du_-qx)G`PQp1Pa5@5+n; zl$|!m=(41hD@ndgHa)h~kWrOr7@bV+T#}IwNf0Lv3n|cva*`N0HE{*3$|!CBy30rs zj46LA=~O-Spr(KSBy|txcd}n;4c#6|DKW<;v6)UwOcV0X`;1Rvp`cw;q=2x)EZ}*o z$mb-bE_E6mU24o_5Tt6-WI_$;mMI95s)?DBAwZp(|=OS(UgS zOUI+;>U{0NN=rli(wfWbYX;=ki2JDZ+-F6Rn~bc0Z7I>~Zd)JZ9tj&)cgX4Vfq|2J zV>0Lkp1ol7mRSpi^cE8!(^qKo#hDnO@yp%G_LpjF#&zS|#&)71rnJU$MC)J_A-hh$ zYjL>5@IN~xK?1_=mZMR&dyPaEbwZlxk}n0ptzM`Ib8mp&A(xAH3AbI0P)-wb`JObc zpToejV`DY`xL9cxx-CyuVeBv5#H>G2S2v=+1ucfY|3081C^_TNXBLI`G3!^fLX`R6KM zOQQeD2We4eYjEi14{jEvkOcO84?CiEP*+6E)4@5l`}pBYCV%>s;0xOej9FEd>A!J5 zwWaX6wo?n87uZ7DEg)a%qj$2eSxSA%htR|HloqX>Caq}EImdaAF~@;jW1(FJ9g(lu z@k&>3h`aU4kJ40kf86gz`$3&TkT^0iUp zy34AFBl#ox&CLz}5lmLp=K_j?iaJ}YNCPxt_r($fVj3lGJxkPTaL@+|wY~tqS9+TM z7c{CL=LXyr+(uivkQbdo)pi{L4+#kgW=r`_Yye!~^E%Q~M6T!f+mFbEyQ3Dxrluy6 zIcB!NcmF%~pfpbL;r+;Iw6NSE?VP&wJzCh|01CH*d+^P==+2o|qb#_in+G!#NYE;>g%gVc% zUVe{f6e-5(xyT!=DffbSG}U~__VHI?(jc}aEKcm-=V%hRvcz5#25er6`%Q|-iA)&R zffMG%UK!u8W{at=QI+U(T#J~H38y-TwXb{HxQFjw5i|3($9`k|40Y@<_Cc0tUK}(D zTr8hEHtp=Wx1HW%>ih)kz(Pt}N}b>wmmuRbQOn4aGVNxs7?$uGIdIqog@d(hB$lKG zcg7)vJpb&XgvH0M=Qcg}S6gWKcLXW_MQFFUZz?37<5&Mi7k~UC5JSzU3z$?$Cu`u;$FFNaE{1c1t5xmQRML8LQ)bunZRvEV zkoG)V`3VQ!KEx}W9NkIerQ5Me;yD*AOM5b3Wy(Kxyz?K->9h@|q(iM@G+z~1^E(%= z`{}(Fa0iR&c)Z=m$aDlEd+4VSbKslpivRUWQGv?8%%XeXH9~XaNEC) zXkveitwdAgN=rjYcj(sj|IOhbst1IpImN=6M}{0>EU|)a$pj7Y8~$t}5^ZWXfAGbD zT0zmdy71Dd#V8W-(xdHB-4)Eb8}xLIoOpcTNmU6BCZJ(%wh7XLV46q$K@#oD&GvQy zz;VtOkROC-E50#TBB{i0Cukm3<4UrPR8QGe8jr@bGP+x8j%}l({dQ=7JBQoM32xuv zHOMU^JKpTnD%TSd#PqC_b$zi#S{!>jR^PU)h@CxVe}s9Ovhv+rKOY{(&Io_H287T( zk*>1Y=}1IX|LYe}EuLFX;W@F@!o5^ceJr`)r(mBe<&JkNbsl>v!5ZBb;7S}YXQz7> z#Rjy_`_LvBq3XF(avwUJC~TH-)Ut03j1R)oL;{LRLq4S<$*EG;$AkxG#N{ZW^wei0 zmyI6&>>s-$B3szeUX3{vd_SCPs|avf>t8x zS?eqi*8fNoc+z&Z4NRv%UpnzU>Riv0_FxU-lWo_cMOB*??@5O%H)$Ch?bH!oP)d8H zk<0HTsaCiIS(t>LS*YVp(PpS}#lou{YS#PJj!7$>Gjj~slq14c3~!GTUYhcn&og0G zZt@OxF>He=k}4{n;T`Jmsou@86Y4N))#&%U&NnDxZs^)Voe`v0AKsDIcY8J+S8F*=?F+Z=1cj^7R(e%|_=c@LyFQtYq>vFC3h>pn+maSF zVHk5LsXu2Jr-Kt&E>QxsYFVe+quQsrmf2I=a)+D`pwek=lul}h{aET@+ zQphzKxt;IHRAWGp$VOzv9K5OD!&T~&Aw{#kP?4FmS0wbq{TiJBb!PcTWhskBYpqNY zp3-LvR9*hEfY|q*hljBYlT_CdncjcD3S-jvJT!R)@*IcLJQZ+sJWAeOtr;ynW6~U? za^*u0SF7rO-p1m(!>$5^b=VD>yXWryNF$s)dcGyPoYn?fY-#?W3#Ai}>-aY@ON(0x z@M*B1Jj`SvAt8)t!i2An4vV!V=X#_9zM#j4jvo|1P1Xj6uzGVkKs{bc2 z_%E+~dt2tH&-!FAnwn|3M5`n^#8Ralw00JRCzxkzvpur#T1%8Ox;c6ZixxHb0Ch>! z?gB)lrYVO3duSKhzx(l#*brV+Rm;|*)4d++FKV>gWX%S=l|*5$ z#{L*eTO*l+31))+vcO{l;@IcD8g?4azje3+gPJ{&dF9Py+pT<1Ps3mh;N}HJA;71L z_~VaRs{Qa8xl&ToRjOI#Sa-TmGhWun16&h%Nd>hX|6S2(vI-5m8lO$Q1DrUHfu%w` z#P0>mOgbY>DfVoX>qk>zE(Oi?#};G>&mKO}L-v<)lzFHGy*?cWoP-(#?yK^RIOMB5 z=9W?tSM2UKH*d{9_&l{8Uo5*G?+w;e>=#iSafatWzhqP+)3GA*uDikw_iDyFG@roq z%c4;(AoV4+-w_k!NzvI4zi?2F-MYnd!%VLuu@rxS55m9V8RI5IFeS2U>-aZ&st&)E zPastN=vt&OH~;6OJ{6oRINbW`UkSOWQ3}}Z2`*ae+$SSXA#M;;&ArS;&0F}q;x-JA zniH4KSW+PvXT^7zZpHHe;sMt$l_{*4f+(z=%rYg?)hk+$y2PH;*3*G#kiuJvs;)jk9znPDdj49D` z#Tj*DK6SqQru1Z(%IvgSxlPnizZrCCUgVOrLrHyFm$f;-GBL8WIHH!nRHY@cbk-g= zRF}qD)AORRf#PowpQ@Eiy$OZKL}C};;c?J(Qi)xRn{aI945gGst%j2dJyF@Oa#ogp z7Eb=@ep&Uht$HpA^HN0JR%xMt=WxB-<^qBitFsW*FREYFX~XEYY(o3UUkpC)4#OI&nf``H$(&KY6LaL482IpNqU zF}IHu0qcSXq5^)1mw!7-+c&QUPf!QKXoRECYd{F`he1q#391(uoMYMIYp+v)TaATE z<6wY$^8?eixbGL44=1H&S`R0&+mnN2OtJp8>=mVtbX}HJv{yU0*@-h7ppX&jXIajC zm6$-C>%fFJtOc}0k#GcnvnY72j4EY3MfXusnY!7IOZpW>PD9u+*SXhf9RKUH9t{t& zW~!6m-IPsYtGclq&*G!qqGY;W^{q&y_Sy*%Wka85l#KB_fDS`^x;Chuw)Fnz%?M>e zaodbn#wsMDMePNBZGKf{pKtr37>7mTx1X9qvn}`os6lP8+5-D|Wga~5bCtfKpGLMm z>y;~0j$Qg;j>cr>_?jH%7f$R>N{}kJ^LYfip0aUj*y!KI#Qn?dGRO278l%2b&<_xU z!8U|->9TdP&9t`{BvHtXcOOe3+O_fV6&1+pvv=Poi2H6D5Pwt{EU~uOj9LJBgn)qQ zR@0ty4xPK*>FYi|_in<`^hC>vD1FvQluBJ7{uis26;Je$vI4X)`O$T@#+0PSUZ2;u zeKs-rY;?OmYl$CE3jiY3H1`kQl8cKV>~z0A$F9w5MX8kC9%(Z=k5ZkguiLNnTYXI> z>eWW^ZgQ6{-~CA+e{Ys#ZE_>DOs$<#yU2>SR~zx}s^F77Xd`HzC0BjAyTJrt0uFl~B zukCj6Zmv$gK|q1u%puCnXbI}<8qKFWxx%yYJ4@vMqvo$vGezwi5DAJ~`iWxJpIy3XS`eWQ@2x_R7K z5$PNpuEuta!!AddD=$o2qU}x3Jm~#2Rwv!)n*ifx>t*QAHv>n61-|pc>gj_1(J?ER z{BFmVd@vnVd4vQs@Xn8gg-`Y;LJBM{X}+vr4r%XwZ|z|cpr)Kcr#2XWr%lZ@UD6pv44pZqPOLipLB%;= z)Tu}eyUz`PG;cHV>3?oz{h~?D**plD{DXFyX@ZoS)@~1>_mEYp%4D=^*Zq4ik${K{ zq|QL{LVh7ZnNGr0gk!4MLy-O&z3WOuDZhcgTFmh|bghzl+`s2ljjr!>A)j9P;=Q$~ zU-MkiocI`p?^uwlSLM^Wc8jz#Zmk(7?+JDY)7$F5<&xhDQByM7C5 zhZZy}!!bjz%8S|Kk3OGXqpG9!VySiCe4wG@HbQ;9G|MwP(>YJ}W^Z;PqooUB@VDb; z!uIG@35Pa4IG`5Yc{NpX7XAX#u$50pFiA%3bk~QvM=DM!a@;J!y2kzQ)N5v4sy=Je z3@1__@a5d^eWkm}mRt|MDkg{Z2K!sQiv1Gxaz)3QvkuL^B3=jJo1{k&X z>1GeCx@SobV%+iB`47O%$*?N_ch*n&P7{>7HOVB$zk&BdQ!pIpxKB%9>RJFA7)n|> ztg$kAAn&_ypk!Kx^^B=6bADDOS4Tm@SFs_s6`h!8Qti9W83GBA)z8i zqb?@Za93h7R-wKgxaDiTC5ln}R0|C)`{F(+)h+{4Q)sebwsvp6h14XNtcbHNTEsiuYeSmWaSD`-io_1? zKk*#+=)JnL?&fMJL)Zz)=Lj0XILx-{A1m5A+Q9jTa!c-r zB(;qY1klUWC50qTzuoSz4t&h+ZUp+0s6bLqKdtY*$taA&+l27r=RJqs+v- z2&qvkkX6V^FzZ$_*PK=5hnpdA`wv+sKiaiLyIelZ+wC)rB6#gi;tg7OJ$3yuuGzO_ zg=L#V;$|D(a!asXwsEo18P^aXu`G!1az;vDXY8Xx_eDymO{WP@Tky%mZ>qbAtZ}C9XH$7|>Z!*s$N9Cu1x1^mZ?%VuAj!M-g)7 z^i|3r|7DhM6+G<;+Vl2o$z-y|o*w?3S$aUb`2U{=us7Ig3;}1u7vrpGx4-G@w%p!J z%x8N%S^>Vq?>8kKAAy3EobgsMV?oU7SV1}t)-#L>Y^{;Spm#eSGYO;wwo)9}L^GWH zi0MiV3`NY*vAfv!k-gyqY&ZFyo5LL>95D)sC*uZ! z7+F_R>2j7aN~Rkydmk;>_`D=7O0dZeRG;(Q1?#ST3~^g`o!^Z*g@#JJHXNB$HsFH} zfjClm799*O_Ga_!R+u1XqyC!Lcz)og`rNp!gGsOW%Pb;dhM93qjOIMll z>mDXt3$fqcNgT0wqAO5lSP;vhZ#(+!r+zK_Vr$YCwCoA_P<8D=jkd{iwGI|!do7-?84ByE9BK`dnb5DhJA6{!=fk3%i-m8$4kxC&%@Zm64x{!aO zexZQIr#8puAH>9_nRK=9jQNy{Zq6&G z`*JBP+We_UNl#RNe6g(jy26t*4Q_^z-+=iDV8)MCqv#bX;OyoOd7r z1w9J*3_ZBEfV>pY&-|XbH@3i5w=_-dU6!Lvp#WGn(hoUbAwT}PPp+upq$E$lRd3&) zn&oYCGv;gi5_2W7Fs2RWVppbu+T8-E@Bj%(LScD3yBDpIMUGbaG5YHa|;bILQR}NJ(Ac^U3#ii&q5P4^%a@t9%X@ZxD-OXy;by!zaajHRuEm9wR zPix{T54C_3uZvX!w2WlQXSMq$k`virNUi!W;B-WOkAi?~aO*SBNAo}Ud|Y#g!ZN;= z{waf`C=uU5^GQYX{jogm>t9<{sx2cg;>7Hif?w|hzkG@N4YN`FDPff@Mi7i#2;|Z+ zNSdLYT%bsw^H%Fe8gAX5H~LzVZ5<>?@Ec)PrBEx5M6|Nwvzhi*LThPov*$w>fkyMM zQsip={KX5+o7Wo$QKULABY)c@2N^LLtvO^^Fsu@98M*Sas8?pPpi=Rke!zP=WD@U; z-paHvUhr2=6YSVE*ci$#`RjK9SsXMN&S(}=0L%6X$``c#Drrs=G&O@v)V6b_ zVZzl87HQc*lNe}U79mujknIR_wDgK9QZ#lnlDndX8*bynvUpXF0^ih6fv^#mPe;s z<=fe&&?Ub<>okhc%7c_brg}$dy+m`E2AgwivID?njn~<90lS&m{>#`Q%L0qn(*dE3 zTb&sywkOHx^+zPn*Mk;~=E@`6lAGPyqU}&yOMz&wo4s^lr_A7h+Ssgt68f_$4O^=T z=jmy5gPdo~r|2Kx+U(bCH>0K6%m#8VB8arC4HGeT)xDb3jpWa%^IZ|oe$0Id3h`c^ zADleIxErsL_EQW=SK}Fc?#QlR*Dm&pbO1S6)!?*_uvyGT^FqCt0xlwk+>dwPq}O@I z5D9muws`$D!!iEJSBdnN1a~b5zL@Gj7Uowi^pcD2{&`SM=PtngV z-fZdYPlY}QAvTPEtA=hqyop=DqB7^P>8}}fOx-1^FAP1C89vPa*WK{(;86?4Zr4RD zL)u@)S1T^sN?tKI_l%g2p9!UQ`o+9qJSn#*8a@0c5VUvH{JvehUPU3?FD2vK>MN~G ztnadlB#$6jiN5>#*04`^)(DKBd70tLXt6TqDf{d8V*FFCBISMY&6LGcHdk{3)OE%N zl$hcH66OKO_&H7%p}=fEiW>FzYK-gpN`T%{eQ=0Rmh|1DB~d&!!Pv29rg*m)C3MkE zN1fD#?wEc-oakFN?aRzjX6908J!v>PPKqnU_4H>yLTy;|%KwOCnZtQ2){%Uf z=>LP8a_R35#+xsG+l<3K@7)Ld&Vg?*ZiRO$T==4|*{L*M_j3gx z&8mFYw^G0YO%=hc=MAl@W!ZO}^Gr(?z!eLh;Bn2;^;_G^!qnEPcT|F^_DCm+8#yJu!5PLXHw!{B+yt+f`^>M2HHa`@p(&a>jLi9bpCTOMH=lD zaleq?3F8tUSpsK_y9`>x12;X;XNL)qo=ZxrSbx5my)cx>t6wEH${Y%6Bp+&Wu+#F1Z8FBp zwm8t^PawiYHlZ%~GF*HaydS)?ed2;9&z%C!J48M`nSQ~v&)eWK)E*%RB~}Y4PWCzf zzBydB2nx|&O2nVfyZql*S|liPW9~x$kfhz6tsGmw}I*B8cVPtLBqvkKUMY4 z{yR4dS!7Hda(bAlZih0=%~Cfpq$v4yl5;}%z}{VF^DNI++k($cGOb)VATO6B4L{m` z_=@RHTKYha{|Yr*ZRgfTcSf&QCl@3#cR{lB=Xm4)F=@;Qx;jjkRyNaR6I7#q?QW^p z!gYIVO<+?Y(c1v-*BH-o;)%)DF|@>Ir@vsPO0oepJGmfMY19dZap%=XUwY^9H{#js z5y#Rl9#K)g_gMYhM*=E3{-;}$xTfl#t{Rm4&Xe`N6ThWbY)yJa?{)BIn?=_@wU|a^ zyR?V`YYfCf@4IV&q3z(0;W7FH^H`E|BPL$yf(+6FBNexL`MxkbGMUw^kRWEh!h8&0 zbTmey(c}vj_`^G8N|8y7S@sZZlFq0$(#!eA&oRZNmP3%q@(PwJ`(*gLvEWV*o{2vg zWRD-02V@CbH-5xYEY-=Za~VEX!a<adCqv1_qqkmh;;;}j2v6LKb&1}o7(rCZQ5&%?Na$Qu&$2Fe| zxR4mWnr^M|FMdrWk)J}QN?FJ-77jW4V~4uy#t67vSM=RTBIoThN|}qJow}Vl(W>y5 z4be{AOWU8%7Cfm-<{H##$qpbi?JguCr9fV&`>! zM9Jw*E@!ZP;d=WvH=`Ca%?pH#?NKi2xswYm2JbGMe8A*CGI>a29@F{sk!dd`1!lP< z=MdldV(Qo-9q7BE^8yP(q9XjiX3qnvv96db%L+9N{qv51e?}*}{ggITD?u!*Y(v;8 z8PjxQNdvr8e3G!D&SL>W-N7u2wbZSVLx)Zw&et9;yC8|JP#%aCWnDaFOsC3cxG#*v zSb7J!J6dFNZ_21J^3!#_aSP)<|NGdk9=ZZePJW@`3P2exNN;}V^oH-N=KG)6wjHhn zXBQ9nn-6dPA1hDtNJlbUffr-EGB6-wYeYVKgkY%Uw}{Gu^Kh>`c^yM2nL^S9ch&9v zMiNac>C-b3T4aylHVcua|2NU3h%I*$%u3*q^ih5#@x8V9-115vuXrPKhJWhSuqN?2WJ23lLcQEmQWW}AsvNh@1Q_n zTb;B{W%@jpj&EU~{37fIkA!>GH@ETy^~K$VxHf>YYBl@&gaKrUySg&nf)O>js>`sj zuAAJ&@bagS8oMJcw5Kg#H#~H@J3iCVuWfk;g3* zsO3?nWqSSyX78@`g&xCsQ9N?g_hzWwmS7;>&C?5Hw19;$eC~ z#SD6VnDz}0apBXH_%x4E{e0GT>fF(H`M2ivS&1rNzPvn`*|P?MT4~K^?8Kn?@$o%2 zqL_~YT@{(zdqR+zs};|UzedWuDum;pN0gLw#U6DHIS2|-lZ?BFu}Qul;LEyrege8* zzbdNe46u4Q=WJ+c@*4B2^(p$kH(zQ;aB_%ai~(NoG4bU7^_rj^6Rt%SN5gdRx~p9T zx9(Uaw=SNg)V0Zh2Lr0c*lmNq8mRe|Rn~3?A$@%vVRAY^A2@RBb47+A1pitjj&%dP zg2xwJC5{GOm(QtgV{}Ku)=UgQN?e^g5~!utwHa*k+z7MH|^AMYwo_WM}K9>zm2Yrqx>>P8oiD4^f>rb{Hp^opjWMskTv>%mQpqo zKl~fY$!%y1!1E0QjlvhM(ngxU$Ud4fg}YaA;mSSMNAVz{J1}Fr^c~_$eM}3 z`{*Z5xuCZAw!@-`^SaN5>a98``NT|oL)dYa7YKwH#ff|B`*|I>46A{y6v)(jmIG1S z3KFDEv#R$D2(5&EUz{>Yrt^|^E!yF#A{IC^V!A;#-Z8tYRCpM?F+F=qgE!!e{I3`}y*Jf?6@l4E+$egU-_`m?!h9 ziIAM{rHY0IrjYgVneEZ~jF3Td7>SxjLiqV;XV^+j;5{CEfciJ(8)5ssOv3@n8T3RT zYNPvA)BP?FjPzH2ylhlGPKZ5oXt)sc?H}1XOob~0h+!|FrlXpEPF7;=5wEV5^kpR1 z+UZ@siSruKuJd_Ss@@|Mj;!~Z8o)ED6)b@!zQJJFC)PWNgj&1P!)NOh{5j4N3=D56 zmMV97RI?_^0Ln7>FAmF~l*3kJ5}3a@IGzaso{e_Icb=72MiHtpOx3*^4*Yo4J6mN{ zCPzfIzf@WX=*=hK^3Ib35f@t>Rr`8+4Kfh|TwWXVstmWc{Zj0l;xih!Cx%$*hEviv zWm7=TvakYS)_M}HA>=jbFOO5{pi!Wh$S0Ve5^PDE`fOM?@2K;5AfpDkk#-SjleLk2 zk)-C)%9eCj@g(UY=7(paNu%5Cz=^6VeoXbamPU7>9=podZmcRvwh8-k%+kgOD1w(v zNL))NC#j|Bsb{ObzJigak>)bZYWkk=fjgn&VB&H?3Q4yz-B834f zztoWSGy2}tLusN3;UNO%)F%K!L5%bthAKi6e+r8HTa_gj zJ?y>L#RXx0RM*vuh-0BQ8P^p@D&ewUeLJeK>Xwh^{J5(d3=VH4Tk+?mtn5E!soKRF zI;xOB5`>OS47gS}21UI(`Sgk)lbaCQI`XI}?96@&l7cm*Og)8igKp-Oe#2C_E|y*A zqnfVBg=l$#c3ShLi&JOv$GLjPF2N;!KLmZ(x3O#FeS`2i{Uy7Kc=vK>LLLJF2j`zZsK- zdu~Wp9+@D7t>GJg!p8ra^2o?pXS^)&U!Lf9ov6fFx3=iY%(s(U6*| zK8QEgwf*ZtLsyCdnakQm3D9WRSM$G|4LgCvZ4te&#nZ^jKe#b*=q#_y_eG`Wj(#w! zlR;rm02cY{)uLCbx_(lzEZq@7;Oro7>rQ=aCNt6IL`rPkk8^ohZp1nq`S`$QAoI)s!YF;xZB_^B9}yqUYJ5O>BtoxYg>EvQIh= zL_J)$347#35Fri_yR!`7_BMN!5Mjt9w3(`~$X+?HIhjK@=ZsAosyc? zOjId0)%pIeflMcq0sWBnJYCcmiUfivgnjE<{bEe+Cv9TB=Ogm&EBANlA|A>6f`J-L zPC|B5Q9A=?OU9;i!mqueF^HFX`ON92_W$A1PZaynRqv>#zH4l?QBBJSI9>a#YD0LM zklc<9z~c!?S377p4^WROi)iOEV;X7uvVir6>KgTDSvHCoKl{c8x#b5#h`^b-(PjF75x7KHJaS z*hUzf?{o)e`EHLyxbGJ;@doZvaHI-MHCDNf{vjegEYYfmfwNU}U-Q~dsy~YnW^=t| zEa;yu2rA{&_qya?t3JptK{Wr#6&1Z|#hPtqG~p7v5ArP2gVyKWFn>7)!G8%EvM~}* z5*nn~A44(lSxhRI5xbcktUj>Qw94}2GfogyOVSM!a&Me2YPAvyBoK63O0s+FBDX@Y@c)Yz0 z^MaVoz?}Qo)V`N>=jqix%?o&2Ux29z(745?8LXUvoIcS0|HZZTW>@rNfkF=#_rB&# z=Sv|)@C^D4K5^rqZe;i30ax-MLx#B-}!CS zP-Arl8K9BqdH;C?TZQv@dXvh!g_4dczjaiW*YVcHaj{&w-~*1;&H(-WxoSk z^981zXQK%l)jns|9406Yj9}7%=A_0`5Y3M`I}jlS)vIaHiwp7y@f?DxC#_}EU|Eh` z^1)98HcBHiH%?QX*qSw;x1Tzu@hF|hyKCR?{?zC9s*Hzd>4;7(PF!#46{Z7zVik0Q zr}hP>5r?SCcZ~uPJ+a=*5>Rt12z3|m4-R75r{(@;M}lD!Y=s3b_W$vr_lgas@d=)q zRl=dz3HjG zXnYa5NaB&-UPAhN#f1y0HO(4TxqIvncQ{!8m4-nT3VPGIeNYU4Olth$#VH`xAz{f) zzVRR((;pid-H$AT@+xq>j}6H=G)5QL7NoMh7FY_+z6=JeW-SM-0WWiLv6rO;na__S zrw0YMp7|w!4uMKO?I{ErjuG73D@s+tT+M4Kq|MqTLlP9TgG~Jn@@$~7fQQbKeTW|a zlS=TEjtwJ7xkt;pCVhLps;nH8nov8P&2&&3wD9uWs8shmK_TY`MUG)?|7&t z?x=O5W8f8&_~gdRuaI~VhtfjTtfE`1opA(M2LL?6QgUyI-(l~U z^OUM{{0VUA6QbBDPLAPOGudS&Z9#owF_C%p(u%d0?Pa8xfyM{g8@1e33@K2qhbrSu zAy$6$3C4LiyCU{SQ7b%`Kb^!I#Kii+nw?j=?`d7mxF}80h&x}xcOBn*Bj&Vtap4Ye z#LY!&u1_+l6;yv22b^tn{o33UFqwiS^=UP3k^+^Tx>dPUMd0CX#51ayHWTUe8#@OB ziJ0!Au}y6qJO2YnB>uUktAqq!|HmrBYk)q4?*v|b?XVUe9>SQ}lnUW$WwXY@{!NP3ymnjuF9kCZ*x;CO6J$!Xh8+0KfM)E7jf6EMSFkz)$FOFSoCD7 z@uyfdw{s>x=dYr=Z7`{cm>fnyubuL}KHR86u3j34wLv`@>9nv(^<-)bR)WxQ@XuU+ z@q&Hb%E3Ll&0Z;nxk?c`8vqWdxID6Je=M2uMBs7h818Juj3r~|)tEz^9raR6z+`_zBAP4=(@Yd_ z`ayJHSk|DD`OdWCQLg=l(|V#d(vq^lvz5)PGRQXDPRSeu9@ohs{Z???d<-a3)h92P zvyVivielE zfz1EI)4Ri}YX1&7d-lUYH&M7jP0e%zGh&Lq`KL+6|8^4rz+L2v>5=5mClrs=72Os zzXW4^_LDSCcasf3CG!jNU1tCVF49tEIhQQ8Q?aj_x;+h1b>HpG;C0(3!G-Ivv1H=$e-kww`|- z`mU>;*7P;yr#J?6%3`zF`(B*Gc{-oX_NMesRC&qTVH;A;UXB-An+JUYnJU(?w{IU^ExZs@^S&Z^Zv1xfnsM9N0Oss82E6c$JGX4>L8&Q;1f8q{hW zh@(BaXqmvZPPAA|iQ31xniW#m#+n-O^NZp?j#1@4INi~tT8QYceTK!PRdSGv(Z~8i z6}6Mf2Sson=^CFwN!+r#8t-)%wAaQnuP;<-92`GLbgGi$m$za5GrbUWW0MN{;s-;W zGXe1u93EufP)qKRdg(NuLKM94%&iMDF^++Q zP%L~hT)Fjz_sgh@*S_NE{F}HsuLA+GtL_)c)nC0>7&v>LKa&XsgTvkj!zjUH3-!Tw z;kQH@!7`G`;aRxFf+Iek1m6+7OUOPc$M3eFlVr7|a_Yx2ZCW4*BK;`ChpoSLJ~TLZ zltx^CLFA3C;X|K>I}VtoLOLBB&MYTX`qgr=?3Dy`5mqJZsB3%)+0bMieRE|naarlQ zQ--5{t)>Qi7QbYhXRmFNkBB4LjmJ=+QuBUJH+4$}#k zrok`2w!H^}8sI+k&}As3Lk8#WJjYXLnNJP8y)3t znugf=0ZaO(Jtt@WEO>EW76ul%$jde+9w7DOC}R$_=9_IrD*>pp3a6mzQ$sN!KJ$KteYseSYgVd7vtS|71j1r(91QkcXJrUzKskx=Oy~jsu&RVZX3{m1&rYBO?nQ`2# z&%f|k>WPmtfAarvb4r)P)pDsVA4^kvSpfa)E{j1g;mng?`Cn~PR z{pBxfx*e%|o%-LuU^v&s&WaMsTOKuJM6AUgd2EoaVbIzc0J~*H*}6VRuAOn@lCG4L z$oIWVs_Rv?QZz1JCo;A#%17-ONN4CEMChwLlK%5!R!B!sLNUuypMc6NTXRcjP0#wV zzhM(3zUNvL`zu2S;{84oX)fY<=~6q-TTp=7(SqfFWqYK@%z_#hfE&QGGNxh*mIhFDoXK&RoK3Fg2py;kscd0F^t0Z zRUg?p9Z-QW*1UrdV4w|qPRdaU*&O-)brN!B>2vE`ycM7(!^PSAzIGEG5=dsdGKXaP02JoAm_>;-q%MDFX%u&w-`pc!L3T7AeelpN9c)oU5MdncE-k{+T!NZ)lk>m{U#A!~BWH?U@()#Th<(P#Z_x`wuvvMh1 zxihDdR9t62Fv2ixx*()BFKhcK9duHtzLkdapZv>kH*&!8mGBI$eKZbW`$g>gAcrj~ zLKz!0sFRgP70)4+uQvn5DKjz|{CgUo z6_N|^_NVI`Mn`$TNW+|vN#3U0*%Hrz!0V0+<--o|`aDO&O9lllf+(TrB39f+vS-*ZwZB3@RLv2!&Z zeht9WBQup9@BxGZLqliq2z`Ij^xkeL&3w|O{zy#=^2@~Sg0}`}yEq_3?RC&9|M34Gz z$aT&X0@HbOB0V|3jowX7jAUixc}#V_MK>2Bkt(p!fFjy*;dK;MIb_6KaZcE}`ze<8=UpH_0fl4#Bei89 z+P%JAOLhR+qU+2H(x^;5TW@hZcK(wb0VZUJLB;koG0zo3)Wu-JY=s?sU&J**n=AD< zVU!Kzq;iHxpGojrR!L0XI%~P5I_}GVg>~{;j3L^M+Y`>a`!V*SGIAL`l9q{n{PFe~ z18hXzMfAR7or1|A(8K8`87VC-iMz`Tpa@g7qm0E7y_>%m9rp?B{SmDBylUHe+7+%_ zEh#`Ryp+SPZYC8BOIX_Xs>6DV%T2?EOeAI1QgbPI36A@&L3rWBShx60bk@hFi6jMD z_W1GR-oZi7R`6e{uEs8)28`7RRW0=ScYMpmF~MxTdGmT4VE@v*w%e<2*5_#|n;hIM zy0f<_0c&%B-KL5?hRxp1hrFSePh!cA)0Xf?qA4^NqYw5#fM5p+CXPtNPM?x1;f z7nwXlYIX$Sv(G9--{q1?99Ck|+&(vsl9M#_E}!H|%>hn|`tV)=0`XVFJ>MUpZ@w9P zEucgvAnQfbG8RPIFqA*7wIkkDl3i+O`6Kt4RHLr1Q2D=t(QcTUxK>h$j8L6@PR$Nd z{|(PH-=l7sj*}sgzan3SV-*G)wD?}H|7ln;Dg4?b(VzD@t|y-iEH>FB{k;&W<0aY0 z^Hf{tPomep*a@eg6$4}1wV3C)t=s0#bYYf8yb;!$!gz#{K*t@k1e|N3QT9OmOO?KW z%MJ0dPG0GgD2kuDZ=^=R=1+{(lU;f9a6@fMZ4T}sixmkWlOR5)_`EoYyLp7z@byVq zi}7*o{<6L>~*i4ID+`RSp-`@zwtgDj^0|gagLtH|te5P#g z|718CKVQoxW@ME7d?PUF zpiq{wNo6EvUH&y#Lkn4ut(lw7?N~I6?>$mZ*sHW6yP=?Ikj8z^U|j8PHc=DpEy195 zrdgsTv1dH5bs$=yU-k=KdK9t)>z@cD3c4FFkY=lKM9T@qxK#tB1eTg4Nrukx4t2T8 zd51T)KEWThLQFw#GgeT!lWy~$91kG;oLo@i*A>gEnHwtm^d;R^d7E_qpvyw3p6|cn zqC^45c$Gyr4PvxU6q)L;9ObK%>MuJ~a1+s~=Z~}q;HyCsHcZhWgptM&I0}ag3a6Vk zy%1*iszy4@6zZ7x7^zB}Wp+kqmzFPmOyZ*6mL%z-_M*3cOZlj_-|qKgqHdm@IzPjv z^xP6{Zb`=Gz25;h9OIqBsR=P?k<)@VBQC37N}aGg$dg-rXUQuU)@or)KIWpb!n z1sx4&$Z_lY0upj{bstT+&G{9ZYKs%bri;P3*-F<0U#~qo&!(tjvIhGk)8DzGw~6zR{TVl7GH%qRB<0Z1hZ}fSZ{5b|5v^14;$ay6H?8rlcsQeqKIL>l zq3_B5G&08UTscW zHL+Q!Buf#svk+9Yd;^T7zPYQDXJt??gkX?Bnssk*_ zr_E+88kSX`iBYh_q1YH*A`In&A$)ErzZ(nDZ z_>8P_UKH=!JOLQzZ5=PXpq*NTxzE`QQ0g13(`1(d!%k@cek_Escm7l5bJY+{WITkG z&}Y$$U)>8Fdp*^8B`gcSIn}A}ra}qlN8Zx3Ut$ZrbEoeZ4z;|B0FSrpS)6X$+ni2I z*c)MWd>YBS{&H>qCK;!%P4!_b&Nn$%DYe-t5>eLl?ajKrW22*Te+>ZqNel(mrhxwi_B zddi|jIBUg9_MIPKNBEJ&@F1wAfdETGmPR^I6snKBGvceMK;T8I^)0+{Utc3WyWIK3 zQfRDLyZ07brVzDPxSbx!eN3#X?K0rIe`yXDEk$kD?v%1AB&mN;fS#MoX?C5jZyt%D zb}C+oosFX{PM0l8c>QINSVj^_YzIY4k`l6YW=>Nw0awcy0jIli0q3*A@a_`lwhgxA zdi@ZbbFduRoo}$z1{66O*|Z(BFUFZlsN@;L@W)L3(@mt?3edL-`2h!ig#OgX(fc#J}Kni~yD`q!i6e7o%#btzILZm|U$t%R}XVVbSVn zcZR~Z)TPG;qX;A1okGS649_9ncNp4%CYQ9WmLL~GJUo{hY8dYPLC?P|k<*DA=k3e; zfnMqvy@<(vtp*$xPcGkTM+;Ziogx7>->mC(R|)G?K`+7&;6W+-^f|7Z&dCG_-8uNp zfR^cgrcYt#bJC?69pj14y(w7W&@0G0-{x(lMMN^eIn1y+q#MeN8$pV$f#z}SOm5;_ z++eIKyAdXE6W!ljY}+8=*#UrzR)(nc_fu-MQBsRa3_;8o5QEXf8~JFyo4NfgKh#Ry zs1lFM!k>K5T6{i@`--M|!VF`d3)f}F-th$xt~H3BelDw+T8~5e;+JkMy~Bv6VF(|K zcn_$_O#2P)1W_RR{q)}{>+}X(mQUZ$`@sk;<0Q=6YM(2$fYW)YfQMe??R0G=k@f1) zS}vM#@}ULjfk}&w5p_eSd0H;SkWIO1&O;|gVS+@nApAowSffdpaQwG2c>_7Eh}T5z z;@Fdmw(WwYQ|E~K3M>Al20RHsiDyXh5 z2x#`1G#k@wuAX1GS-3$Sh_SUK!K?QA7fyZwz)a?D*FM{W3RG+vsA!9yFNg=;N`W_t3K~oP>Bky0eC7C&-9zD+FFhI&Ug6lqu z5KvmXUw{8x|0#j-qp~vTFb%Km51I%r3X{yy0>wUY_Wa9NIh!{3AHwi^1bal8!jg6V zxP18V70T$KvU+`UaiD0{zA^?53as;g#>2zYu_sxz`kDG5IID%C>xY_hz25~Q|I5AM z)Tbb1P``m{#brAmyHJ4Q7A^azCZ|n7l*-~w1aC>T)}5OroPPAzHGG@iZ=u*g*Zo|4 zou(;FSzsaO{s&7rix!TRh`Y4^&;npxey-ib>EEX<<Bpraa-OrtYbVJMOL%tvbHsa%(`W7a(6r>E#dqW74Fo}$(_S&dS(x~7A42a z45ekpZKHA&2A0zeW{}CSC5tU)u_7%B(ACadK zrT-14i-W)z#6SN0cY>2Cy@R}SK>FkmJ#giHVM}x9$ypc+<QMS&(_jI)`N_RHGx3;FPX=`a6q7{Nec(4|^8Ri_V#GV}uhX{IqT2 z>rIzV+4t$(4(!BD8>NR&*P8rxqtEl?V>E*SVZ?-=d&GDO9(%S;**%)S~Kk=z0a zme6;}HVcM~?{y`&;tL+>>ac5rQWEpCrKKt)tL(C}wx==T#AAfqHiB!*zP_u;;&}IH zN`s*fPibr_@o&#@z#4z^$*sy$eW7-CBaLZ)bgjG>&0Gt)!Bp8FbYD@0`!?PZIX8n@e3yps<_J72&s{b&^#03IFOh$3Tw$XK(6|gZP@$bnHtc=DNUfJde>%58wt)OYFFjdU zq!lY(-TO+=tC4{jWl;P}1yd_r7SF`vi=z}rMKVrxkSI{AInhJ<(~RaftJ>(84nHI6 zTPWGd#j$iwZ42s`3%Iy4!N)1jq@v(Ec5f0p+kFjR+cYT(y2R!>qW(j+&(p@?MZz>Ib`ps*)dni(IliX(I3W?594CNP-O}Rr7iZl{4BUlO}xb zsoOz_hmb$fozXIz7VzjlR@N@frT*U^|BjC7>F>Fli5{}P!`NO~Y-t&ci~ghkihv2< zoyh=yj7{Oz**9?ssi~K)68g@MoBds9#=9+sQ)%vtSQ1C z2PfSep=vBNbl()5UF_8^_H`Y_j2=Gt1{!8V~@oOW2I}qTMP&IKlfE#zqNJ$^&aO=gQ=(5@z~`w ziw8@YG@rz7jLelMvHo2r3VqjK&k^sOxQylARl& z%cS<`pVAh+CbmKU>4Q)^VF2n690ISf09aY&6sv02W|i^y^h)6QTD-fTjBoF$5B-np z(5FK|m}FOwV3GrN7G~lHS*~~qiStVTRSr~8FFqbE8#R(;`mK%{k|-_%vr?ubWx`}} z8z9gUTnV{;t}ZaonH_%a?kKAuZs?!{EL*Zjdgpt%xd<#VsDG8R^ z9N}PN4R1$C+n`J9ebwP_iqQEtk=%ip9lZ^~&WKJz^yCpfHHM3uyTBvA9fU`MYt^dNWg5$<1!Z*BR=%UO#xkM+zX`>P#UUhL zfI4?q>`mW@{b?I9NELE{3i^tMN1S$HJ9-{MwB2V_*Vu_?>)7->dd~Vq(uRx>@ zSm`RDKjnyVgv2(@+oE;Tb`pAx&yAMt<*V0W%F^}dl(HP<$E<*9xi;uBY#J(5tSJ^{ z9U3#^=M1YXrw!*|JNFTEex9 zy`xOIUcgepZP{WaP_$rS@gZiYF=~){w&8)nurW19e1*!`x^9E)>uh5OM=Kk6I6A^S zPaakIu|}}3FTw%>WaKx_N2*E%=kw>wC({U3L1<9B239Uzh`55`aJSBbBEgQBJGL|4 zJ;=nmxt;LnbSm!cOTv?Vqwr|&FuXW2UV-dvyt}#{-{0PZmp9WsBcV6s=6>KI_-77k5JK8St9fw}i$e9-E@wXZ`y1KN__D+r$8_|AV5vCKb{kBg~wzEE()6p z>3hoK(u&Kbe+nZ9&`p6tfHpTbmnmz!yf$WhzI^fvNv{Y@|1*NQBaG8B}555JA z3ztF7K_fAI*%}N~AHYTXc46(YJy>^WD>fe4imhk%VByYnSh8mmHXPlBHT!pA_l46) zKfVuJPwYY3+5Omd{t#C0+l);|cVO?$lh~q`{VJ4(k%=XYT*F{w7Xl;C0`RHY3`PM( zkSBi`d=V6joZ$*uqARL>BGkSf$P-l#MsATXa#m@mDvgn&N^2ji_AiRB@|BP&HCsq= zS*BXXRD)4q9GuG3m-TkVYpL_7T>UV>YdjXZU6pZ|f zt9^^f{zf+b@UGqxt*0%ASzHwuS=yjPo7zY}zZolbreN2Fji}MNF^tS}z}PAqTL z#oP!9?aBfV)&h^``j4 zyvq@`2(XM4K-ioxT7m7LAs9MvkXXN()@^{a^&1i3=?SYmdEsDbE`Fo^diKPifdeEi z>DV!eVq&0WaaEVeJM2XU>ie3Xa^RH$QzmIZSJmg1S-)eoYiK60|rf zmKIitgGw-V=Fh5(YSOqh%*|}Y|FU(fPFOI18P1=%gqbO`B>Drbw1isvPj>0tL#&28 zhOMo=_>Pt@TUy}t*pWjD&Z5;dIEh7(o%h)JhaH0G<7lY>jqfPmMJ;R^d%iO$eZ_JW z1?>1;VFj0g@frS1LSrd7s9v)=A|iv)xOP>Pk1K+FzCj33K)rCrTs*&hA2rIB6AL&k zj@1>EfAvKUX+|epvU!}5FEn7)l*?2$#WVUw&(3{Nqk26FNkve+qP}DNhB)Lagn*VK zP&9EF)?9pzd+OIO*P;h(f{Nfvm8UGd)$gM6yjOHt^h%nEJg)g*>KOsY&=}-!@<*Kx z{a_nZ2=*Zbk1u3<6aT0_?u zyMX-SK10_Ty4o1K1&QlTE=OO~?a&AFHfD+|jeStGxa#C`@`jO>vpSENg!QuY358=w zv`p;+BgO5(Azw6HB4c135CK!~U^qv`z$j;4aVoM+iX%cq-qhx_*JE9DVEm@N%#spOPKA5B;`GCj*%T0*%@(ZH20j;!cu z;K}pwItZ>jHZ8lF@#xK)HvU4|uhAzS~;h8Rn?7u?c`Pfp+>-ldK1GxSh zgw{)juHlPEYbTrfXk}#v<;%(pOUno$Qmf%HBl6{>MU&}Rn_@<%@P#7a(jS$g0ddWm zHKoae8Jp*$djW;DR4x;EyLay{*PzvCH46=o%@>OM5QJHSWg*EIh3BV_5U-b=LbO^P zkIQ?}YOMS$@Cvy^C30)?f27>+AJMGRQnT7OE6pk`HLLxI;so)dS8ibOx{WxgK1fer zy~OiZ&v8}(X~xR2IJ#v#j-*e);k2nZwQ~-R?U;+qjkB<9)^MEPzZ@s`%)|Z+1$60? zuw&gA9NC$Q8IybB_~F&KdU+d4lnGM>n*(e;1K}H45GhNRp-SWCaPSX?s{#SP{BbaM z^@FjK7fhUeKF)t-=_J$a)~aw-1*>B~IGj|0%4uj^8TdyRg}rYm+(HVd z4JZgR#{d+sTo1!0PDgl*f>{Nf&6}0M-Yo;Mc6L3in%fkG!;D~WW&}r5Bb1La!puR@ zIKDg{w=)~!+v~l6cN0`b8H@cJ8zG@fEG)7c!P+OAzMhN%Q9{R0T^r1(a^$ zA4+AcUHXZ0R4gA)FE~0nO2Mc#httx_P-$$Ix3I86?%a6=MhUA7$HbvsX=$Y;lAztX zbz8B(CJY=bV52&-;88cvrRbi z0-hbm!@fx(%pr zn*{UPec;qI5v~fT^H%Q;mlnejtd7fhlN#M&TC)doR_=(eDs@oD>MF&|~9P4Be55QM>kF zaC#a>t7(trn_*S921f2UfZ-VjFl^6p3_EZht(I+pW$o4o>@ot;LsAhxKLg{g|E!+b zd(m;%fw9+qQTqO)CSUzgbj+0>M3XMR`;V(!*Tr|3bnZ0{Dsm;jzGsQRnw?StDO&>> zvXPcimN9f|p@D|wBg-(BcWkcLV3lPP%P_V!vYer?%%VYtu5V1kiW>WYQ0Py}GL*5> znV!et{`*84jXoy*~Xp!v4)=wIJC>rdtoMaiva+{s1HBe^x z$m`XtwFFs)tz_s!cDQC4$?}pNptbAeJrFc`Y$`3hdvP`CMJ+GhTF0Yx!EbW{u zqxr4SEUs*YWqHke{%;clxc(0bUn=cIVU3G5DJnBOx9JP_V{J^U`BAjAOv4va-6Y zf(}M_c6dJS?w*W`+ehQZo^iO4HXM%*&qSz|5q2ydg!`u#;>wXls9q`pwkA1|H%~VB z`gvmUl7+CcvXYQP3^Ak)QOQn0oYz_J+`zb#46aTKAUg`til>dc&SqZ5spQB`1T9So z7(5pDt6R5`0-GYz{LO7#&w%oTGIj=GoXi^4YRhn+IleT3k9!Eb+=3-;t(BQQO2(DI zq_N`_toXnxw-JW44p;XckNJZFk<`HvttuO%M?D8j?BaoxuGUzc=!gwtoblvXL-kN6 zkzL~Ug=FFZ8d2{7O(uibi zTDJu~yY)t|?tP@=4x6{>BRgooVBEfO7r&_N!)MIjl2A%;Wd|$*DdWuYT3ErP<%Up7 zIAtd&!YlXZJpDt>6ksy^5(l#=7FS#bbD&>m&u%?c-uy-GwQHwtc>3rCQl`z8AzB&k z$xcBu1Mc%!x?xE};py(73xTEbjIEiK1p9ZewwF=AINBPI%T8AWQ$Cab4_H4aV+6;= zmXN%~Siw}@CoRhiIaRE5b<9aWj&@5Aqv`7NXteAkq6W-Gc>fv5*LxZY44jXG35!r= z$~F`lv{>dN`pi-D3)OTMqWaB&Py6v|Kb5BU4ES}Kh>%{>5ZY%33JzHyT59YX)R7I;_swmTy7`*~f{bwmCo{qvQEvFHEXQE8<8g;K2@D(HlhbkMdu9)ROhTgxiKkdwr~X+&02`o zi)8Il2ZMACE1ng*7VR@yMm-?;(T&I61;g1rYA(RJfzSifCi>+-MUG15Oz!>Q1g5mXwss} zcb!m5;}yY|mR9=5vST)_#56)t3D-O}q51Ub({e4mZazD$tRgG${&{WxZDIh|{~=*! z(lS(5qJbc%T1M7{=`=XxJonLuT`p7g_o3+Tr|pxKWVQa&>-}^eUL&__FR-Ru)=&3; zO?cnGyjS<99tWqo=c4q77r1?715U0Oit8JP;bG=@+|QhV3mZma=ZwyHyf+0`HjTjf zO+#=sV>GU3Cgbw9(KxYcFm7f}#o2Aicyw+#9-rTg%5nZMRq$tPX9+iV7x@@lTiJ>d zLJ1oLR(AYhk9LAno;+p(tsG*Ky{qYa$?@2^Ob}(*9`0ADVC=_`K7><-*C|n=jLdVu zgYxAo3-}T|xQ-x5aAjwk9$k8&RIzf1j*Nqym5YoDL~soW2#1}et#q(qr=kE)JD3_7 zp?}L@Oz-1~#70IK+rk9X+E`*)A3H4TZH@)Ka%0VK8{FDj8jlaQMDt1}u*hKqdvhb0 zsD<>y;_Zs!zhP>*ETZ3RAWB_V5S;AY zCF~S^NsC6uz*AL*tc@-3l~Fe79L2~77N!>BJ4>rB!IkjNe5J4Y;7Vxa5Xj7bjB88l zGAmbv{gy4-BW?SBJpLY7z4s!jweAlSuL$II^@oXzKYXG~!yzaJwOaQ<;Ytl*;T45E z&LPO_k`LMKeI*h`%JQuUEnZC`XV5huk6R!t{UXFgz%jHiO4Vx#mxwr6_=dx~P-$5C zM8nYFlo zdnekpD2Dz$S|rz=fmpaqieMoV&0Sm+xG_gEz0G#fQ;Nc3-)NqmQ17 zivS~@Xf6X<^FQacCVK8qC9?ddmFHy(6|YHasbYynXjP?!C|m6aZ;WjykZ)HE8PZoTuxchWqK~t)sPlg1GpOGUl#3! z&@w(VnZ9uQ?+N$SGUcb~DEcoUMO)U+r=`)(!S&j_c5DjQbDl4acAXTi%jz83G4zl7 ze@V1w!{_mP_x8h&bc%R`I|rBJ?D|mxsW-Qd6n(sNJT9ynh>Poo;#THFJUB2NH!{ZJ zTH0tl-aj3;Gp8tU9fw`Z2jRw^R6IJp8Kq*wU}a?{qa?9bPDmlp(7H;1;_#JJhG60l zm4s1kR4q*j3=GG_DS?;UH7hLVxxQT4N*`gPpaK>ipS|H}c_pB6e;%uOlUBHN?g|nI zjYO4-HDGV;Dm~-FEML4%WhzwwK71{}Ov|pL zwF_oUnTeTGQ!!+~V4OO75_fOh6l)>|FTjF~Ef6Xeb<&4u*Y%>GqQdFFf;0p z_{?a@j;|Uo&GQ7;N#iGp_4nr=e-YOK8&%;TOgE_8P%OhwA3wvfXeN32Vk0Nm8+pigZfyz zY#BDLT92yb<6&*#j$XY+V8NpGc>OKZ{4iLVyUD-^uJ#@X@y~}KZ+}=SP|y8kPLwKI zQU(Kf`Rpb7^z17TP75^0-lq~!^}&@^do3?%&x`QNJjaSr>((8xD`PKeRE)>=P3hRU zW`p#UCpddJseASGK{PGeAraDxzF=51s+FsT$e>8kP?cvns@S%TTXFKxF^MW+md98+ z(J@vk{gXMU1AU#@`=3z_82F#_p+UhPJD0K37MHm%m)UtNPR+BE7CUBz1q6w*gBCk) zu|pT52r$9~E%|OvjuID`F>QIAAa8G&=gFmj-x~8K55W)jcH!~Sxj3dOrYlF+$Lo{o zz1}|_FON;bjUB`B?&3U5>|78tyT{_Y6I1bM=ODZ~GzvG<2jcje1blNVLw!zes*lfi z`~Zn{UMB<~8V!E>Sb>(YV5$1^A5<#W|6yf0z(@x_sBa}BA5gS!s0OYCM9n%$izUOg zvGtE(A!%vkzHFkW4=62)>>x~+09q9ZsBF?_r(n9cabOKLsq@>+ZzVyGu*USXViH8P z?>Em!a3yRqj27XU#~`%QLP;wrd*ss^%zhzMts^y??&&T-ODxmSQq1dPhbao94RA0a z?Oq9|tN;_f*&@n&qs5qmfDl@FAM`iZ%I3w37t1};LQHEct-@MbT4{M6ww$s9Gr*io5tYA zwh6ejeFC1HUx_$hBdkttjju0k!}W6q5gHn#KG62!tj|t2w4%|%O4WvS$uE)XuU04ssc8w-7L+; z=Em0W@d(gUKghW33K|J$CF6>rZL?s%X(5sM|ebH^_6=_HtNfB=F-Z2oWz?A!utXOF|QVZAVGWM9l4)gSZ54Z@6(eK3FOXdKAQ zK$lLP1X>BKni62GEGz^j35B#~(h{mczXoUoS54VuUQ)q6pAm;0ZQY`+Ky~G^6{VTo z%G6SN!gJV90xf0!ocRK@^j+=Qv$raI&S1laP2w)Vrhj&%(g2p$R{s7)KOc8=_(N7AB?t5TcL1dLD-r*VEU9fC|Rm1jEr(&{P^iO zeE1>~`X?beqJ%tWRzgAp^NHoPN2i_`otPx|vuyD)B#%y($^qlp^1idOxYD9e_Yx}e z8uJd76)5K0;loDD{a-nA8AJOIhJ{&PxVWeagQGhFRVAo!L=0jg6&NdMlCo-kno*ep%})2x|HLqAtS8ZD8ug3@o4mQlhWd-Btw z%kL)Pjn9Y2(u810R|T!vo%6JG5}fJ#$_gueO1X{h3WQZ2gTTw3Jv1HDdR4-*QBCkLV+Jm+9x32@b>~Ff zJGuaAb9>|1>Lh%9aVL_7_J+NKHA<8$Ce{dATj|@#c$x$NHs4b@uQlrvR?3vFAn?FK zmGDY%WwUPO3e{wpFhRg2SP)P(>nov$mR2g42_dwe@tCyc@;JJXP}Tw&oYz->pFjnD z9tz?L!Z^3FbY2=Was;eRzJ!yp5oYu+grSX1(7dz}I@kCDlX?cCPTZFWb1_1&doF?2 zisj2=-uz`)vo=j0>GUbHWNiO0jdG~#k5>R*Mtp2J?muCO!Tt#=>^#LzMGTJ55Jdxf zcEy@`laV^QFQ$*^iJ7B%%lz!*{#Z15D3;C`ho<%Fh(9Nl?g6y25?mQEpjcc{0YzF` z34w$|4a_v_G+|X=wF&|Q))V4seWse`G8VX^)sh{|#wLwJotkxElE+l6mu%K&+|%XD zR$|+>9pa}-w*mUP(sD`=B|uX(NM#IJPT9$-M2S)Yw}e@4=l(kA4wg_)A2NT@MTL1#v%YFmu4g`*JYg!XoW6O93a3nuZ2J-;ge|@Re`P&d``T6TBo^8_}88x zmrIu_EAw1W>$F5!P|MoD0<msqpGe(qS5 zngslK4Q=a(%cxjC+*pA}N2cJ#i5Yl(ayH(cS%~S~is9;(A^7I>bllEJ#Pux$@o@J@ zJlvCvt2@Tw<&`a}@_So>>9^|Zq61SgTk;bl;HvxX2)OFO>t9cF*GXjMRclp!-GAMj z_DvbtdWzP}uI;bCFM*Bw=^sOXJJ;*C8d5$zpLR?Q__S@G?nmMIG$_?Xf1coa z;=~D==XL8J>yPBq^JwyE`mBz_bsGFqn1&Eez-IrJ-#hmIWif#3-&B}c{}uhS@~@`< ztIKcij~|Z@;3}&3ah48S>O=X%Gu$|^2B%gH#g%mfaAT{2*lok`Xy0T!J3Iqd){n-c z%oMylItQ22l5lz37~DEI8_zCp!HE7%VQ-ro#Y@DB#g)C=#oFrXF75%ehSJ(fpd`Q% zQfM8e(*Kcuk1X`H5r$asGZtrDk>Vd+3TR=~(h_7fc;&GP8T8#Gd{DWK$0$|2j9A(T zz@LIEd(!iKv^>)4NO)t1BnF>%amWK-J0omc+7kO$SHs2KZPB=zGmNt-X!W&1&aaHn zv{5Y_J9Y#UCr_1fI%Qg_Ksm!u#aFF~X_IGQ;@HXP-mSM-?+EJjJEdik0O+kCkIlD? z9&luL2F51#!L(8RFe|Aa=8owrI&F9lteP_c4Qf_Y*X#-pHwD2?&hYi}7Jy|ePzL+w zaGh*+C$ti72(f%78oUa?Du~iLC{g)r`HTs#d~M zOUst7z_VvBz+qDf%JfwwOwpg2o$>g4@;bPVV9M(WQy@ifrTc(H90&*yYfhs^O=NHc z!aOa3rHWNRh<|XuMCA>1v@EH+eInODd zAGdR;*8Jgx#3i9>g(~W|vw^>=Y!E`jLJO!o94JGz2Ka}n--07zMSw%GYQwd1J;RKd z7+Z*sH}fuA8+d*Wxf>7^DnsxVC>SI23?Js@t@5kN+l30pAwLHnC|dI4I&UA{`#|OU z!|T@kz1fkB?+05UXl*Cd)9oR?W?lFN1;g3HL*7S@^cLXZgbmB5tM~pIy0t8%z_r!~ zaGfTD4SaKIj=*cIdJobjH^J9O$K&aN;ds1z2p;Vjh5LJ_IjPzeYS*USlLnp|G=3`FroW!^T&KCQ=>wZ~tgMcs?WccU z9z$~<(AMjx)viekFUfs1NaT7>^`V&S7#)ZfWNy>;rBbwWaXp3m>z^+x;dZ8@XvblC z?b6~rvIzU|9^k{K>P}>KWffgTrXBw z^|5*X3U?2!z>#GGacSc~v94U+&>z<~C*twmsaP?r4i*oof#*l(;r!-gyt%#=lSg%c zvwcp9vFRJ&3l9%B88VU`h6q%&3enO-%PZlPg{xmch!nyxaU}$@q$AG5a9*_(bU%Ce6sM1!LemCK1pcUO#%|iEDLBg9-o5+9*OgY* zu3fsT^M#AQEANdyudKAtLa12}Xt5F)n$$xQN6QD2k#* z%AkGQ-WWP~9P$N5AjcO*=+U7m4rDCH*3~IUUpE&qQ6b1_^d-7=>4#glpP|pdVW``n z8Pd1y!q6e3Fn!8QvE15N+Dr2|Eya93gZm}Ou&lIpGo~v+nqW$wR^~0{Ddrt2*Rvud zt^*22M*-{yXytpw z>)up@dl?E;GX~@7zF~N{dpNG7kH+iE+ktn4Rs~bvzf+$P0+YnI?D_on-fYOtmIrs}@4`ts>Ah5PHnSXTRJu&14aqD`{` zIc=N%vGlKtqNUTIQU5sl^ZK2kwDsClgI9ggmh~a{bE1D=`l79)i-C4d{d@Rt5d*jy z#2~*b{7C%&9}nF+_0jn0t@={E#Etzcad2S|T;0$cx3?tV#^ynIe|Z@OHV8qF>i&3k zVi}&CUXK|gI>Rix5lR-1MZU;zSUWgK7!-B}3H0@pk(}tqNibxb&;n60(o|{d=nntz z{O}IWCqseKl1CpucNcd7Sb{69ptO{7nU*&~D6OcpE>USoa&y!9MiOQT1T3(*jq{w+ z;>0Nf@6!TEkm9}s$O>gENuYYV5fJ1EDzu8x!dtd%d6X(GlwMEm`(ou}pK#MG)im_H( zHfaWbZ!gT8HW_ngq+oICEL=K%1QUk!$E0Dsv1rB^G^k!yfmWW6eys#v9-kqsXaObY zGwc(si?nJIS_!KHW9nH)MHUw2e6iTl;28b|BGj@{>8O=o=kH2@F-*xLS?Zm(|?)wNl4>!)G8Moor=xdw6=~K zr3(wRX4NuGojghA_w3wIkc9kF`%9E7jm{DcOFH+`K?OT8mJauTdcc$7d$;& zP%tVO`GQ@rW!)6~_;?p?ADW5BrSCIms%GzJ5-!O7p2I(Y}zsekp&Qqx^3{70;`$2Km1w25>cq zLH-F5E66XZcK!CX0@&xceQ*JeE$fXd>-*usw&A#)k&HWgQ*i&_d{wv+TD!vJ3nSF7 zR#{vE+`awa;^8Ar*rEQuurvmgFr{xLLoz*n@C<_oCVp(TrS;c1w;9}>+&*;9vcZxC^Ray1LhRbK z1*Z@0#=;pB#XZ0{hmm@oZqg}A3tvTlPeufYEnE~izse(k#%IQ80)#KZjSg}O39xEP zXpQE)f>urmW|{?-&zcnnf-5`z@O)e*yw<8wTYBh!`}$k-?$KKU^YdDGJ`NVJa^-65 z-n|zC*tx4x^^ak=*etGD%XNTOTm}RgFt8uCZQp_}o!VjR=8bs%Ni4Ah^jDpd#m@sL!Bo8e(sjozA_njdlCoNCLy1Nkpk9{c)Uvi z>){c2v451(WL)2tgdgtiQ(p@Pu=*3wO3??ztn_n|RT_Q$oMe?IEBzq92d)M&$iG7j z;A#+q{0l-KH2nNV&Ah3TBv9pWkJsZo`pK$m5`uWt!VwyV#g9(2?qoUS_G*~pUo({ z_;z;f)I;Ep`|>zECas3F5Yw7T|4!Z?;pgD~1K5+fO9lYw-l-dG%xvN1;)NieU};Jx ze6wQ=!H&(;9C>L#p9FDBpjDIBV*)4PmD|ltOkrhVCcdtzlO`i`<7T9-UyE)E>Vo{d z6)@Yv!OljSb{RduIFD{{ftuB8Nyjo?pB9NhtgTda9v!^WXOrQtXss(Kewu_i$qsU~mUe90 z8Rt%)$HZ~t)qEQ?Z`4pij}?h7pq`zrR5ExUd~O=BYRcb75J5k`3o=Ie?Ts!E<_ zdT!@A2*uo=tqocwg{}!9LD2{ei54IooG=hO(szgzox=c!1b8Dhzq$^0JH*8nlK7i) zUFzLp6o)`hSNJ;QM#kz%5*BNDQeANixR>4?4|ny)we16OEprmSyS+z!7j*6czoEQ; zL_P(?PxW(>RT_Q$oMe?IEBzn_a5cz(QVif~5QF>^@}41Vl;}Ruw7$Lret3$@J7?kK z>Y<`{_RYfLiQVB~Y9!%w*t^}{%0^;EvMHFIR^08a(Y<9&Jh`|Dht`k8rQI`d=foOR zDjW>cFN|PiY$^r6jTzz2Nt!VOLfDxlpMVtoE!i`hu*xZ|f&^Ku!xk-MEWl~KWD~Du z(bFtcgjPa=g@uBl4;C;gn`sFR1X=D+YuxDJV`NNzHdWIPm-`VCxDUaQuuK?bFn)$C z8Z({PB(#TOVv@6xmQx^}G&GmG3Ah^>?%VuiADesXGrGrCV6Ev-MghE>VEX+*c z>*;~Qq506cMN8DG7B9W-rDL0;qkt;`HgB%n3M_-=9BlrkC6LcY^HpW@G?i964P4ob zOr=Fma}m(MmDi*Xt{iTaz(!XA0xI1Fc<`Sfv^Gj0eDZ<&v?yOv|``Z>69Y9DG9Wr>hM2(Dl1F;-T3@i$>KhYqM^CN5M+5AEx$9bQ)z)^nvmc~1o}t8(^VZyRiH{0D~gIG z%OKa6j5TbEC3BMT=*A(`tWW^Xc6n9)D}pj5%fj8!3&Gy`5T%Zh&)XF~b~%y0cqDLl z3m)wqhWp!lwCxH<&8|mtAy6?72o|yYb)hbK>SocCt0P@*Uw2-X|mD}VgOfz z{3pc#t_Cs4pA>$U=@w7@^%MOwe)-`Q@a;WZ-M0c~)2HEd`b;U@LIXTyge+%gX9cQG z@KDNN>UL(i(7RPt+&r`rPfl(`?LrP1*Qp#{pId{6$JU@$v2eIr+rZt~Tda{B35vbq zHGj?WB`Y8@BnrMBeh3W=lUSI92D%H-vPhU^!A&a^r?i~1&?ks$zLkU}4O+R(^;8X7 zH7gh`yd0PQ)yp^7v?)!t5d^r6;6Q5>t!#8#Ah6Ikl~C8Jc`JzukmHLl(Y;d_tXaNN z0a1DB@lRltpsE8ytC324`}nZ!@!br9$socN3# zktbIU1o-(2w9>znK&%0)raHe!1;+}g2(47Q3uvkjuAI{POL*nA5L`b!UZwI?72K4U zd!R*>AfNrqT;k`+c(e%vhsy6jODmz3&zPD+gaEA9&h(qCjvM!hKv2=#UHhR*k`%bE$Z8cr@gMvPw%;l2sag70D_sRY_K9veFOoYf8Oi7{nm|CNY4kK@9RI zg`Z`8aQ*n1W-##|zQ+4kw{Z7tI(oFKg1p&{;OplNcP~!?HE%~3LV~OPX2?7tmmomEPUs1;xLBf!xwmQCgCTs4389Bf*<9*GHq#ezqxE4ORm zw+O8SLk$pr)fnk86crvJ;GQRYPSjBlRjqs_N$>2$ih&=jY#d;0W~!dGJDi-Hq(?lh zlWfxe6f|j7rLr@YKCo)4Sz0weS5_2g&87vI^Pe7%*USM5=(<6lPCkdawd&*Gz9W)R z_Ut|&&seh%(#Q4O*-Lo-{A&RzS{3;_5nTDZFmePTi~BQ7RE08C1n>#)Cb@EBc%Pm) zvUN3%teuN98|UEaw#CR?FaaCqOvd7=NjS1?9X2gWLE4g;SUoct+m}zrnVoBJe%B^E zzH$L2<4U1O;gSlNJ0iA7X=F3XDR54AhLn^UGDt%4;w2^CDXrHnn>4|R!-w$txvs;O zo1?1?70d0dTeQa6Q|INm=zecisZsaOJjhBEm9cs0CgAMgAsx#It-NpMFReMBP)dkp z-Xy$g%6v&B!16gUPcsiQA97#@&TGD}JRU)n$6)1z^E{8{n@eRr8#-_Z4(!~EYGukJ z%-dVNldcN(hXP-pLccaev1D2&;MGyQxRHt4Wg}si%LrwQ#G+F1N{9$h?}LN8O6QAU z7dupl_Qc&IbMWfYQoO#gQ+)?GIO`7|zYV{w;OdLE$EW&1vI0fwN69KJ^@C)Umike$ zN=yA9S*86{Kgh2sKRJd$4DxRf1GpN*ApfNB^Q-}^_7VT-d&UI(5#PPKi|t!iqHDMI zu(7jM1+R+&PH#l{_`^Quml)Bd0lvSv8@KkR;?kBexU_yG?xs(ap=3|49*i5iX5z`o zwYYI)E$URrkL*T9u(L5!a1adhye2Z*4=t^{nUTJA0z_0@j zJN>Y!m_wm%PfHhK-mW0{COK@Gie69Q*T5~r+txxX(QqSQS|9pM~wvHXTV*L1t z5~YEbM?zTfV&yS^?sD|#J^T^EuW7)%V&zE^~mz6IJgKOvD)Yc`qyn8FA4NF9oGL;b=SO8xb<%YGTGuUa0LI2sj z&fk{T%Dj;yJN>M?$zT)1hYZHy{rfO``b@F@vO>b&_U5&l(oC=22Z54#O#@QGCM!cc zHmBM$VUyeWY&hjT6D+x&u&L!kF0;}_<#B24C!{hBr%b0kFQ(UA1h_w!X>H|H1722= zrcX{mbXWw8vwex^U>B^MlYpmJHsIS^>F8899ODO8!@Gyu@#@+}e0wtk4a-Hs@+%`0 zD-?^GmFvRa#UF91A`=x9fE?=G9M!)CetLCTz51`zM}Xn-enq&fFiwBl@9FPJR{Lh9 zzb9Gko0a|<`8CZyliDB#`Ez0bSA!VjpOFuss)4HvdhxeCyF z$a&4*Ra3$&mG{r>bQ|D2?;+2J-tm04j1tkMa}QLlQbPcX6$w7;N)@Z2Ti0Ir{<|M= zVE+;I?1L1D1*2{2?)duUkC-)c5wd-m2Q6B(!pXz?uzS^9oZ2)GCpXT;o`vJEd%-xI z*f<|&cdW(Hv{hI=cM_JRj#1z`9Y;4U#)-{K@#yqEbZuA{UbYH=ql&=I)klHz5S4f0 zKIS7@zv)uKYb6vi62jYW-eUUHY3S0SBPJ$~Lriob@#p2JQ+<2)lTKZPNhA@bgda zr9wjaBYe~F?vM2MB&&V1(%+M;_Weio_vF{@pWD+Q2Km>;0Imix$iE=kXIdXzbx`}W z0@$C$C-lg{BdAreBntW4V9Drqc(8vSzPY##L)yflRXGO*t|>S=uPZLD9)N3`2IKb5 zBy5}A35`lvo3ELviX{@;p-DD)td@g%%@|R<&9+>j@-e|0=ia!O`}>1W9Z z1G_TzV%g#q0&eUqep=wS7%m6$|?}_RnH(6$B&*zV&X{YfHr-? zXzX7-6X&+f!Rkqaad7P{>{&4dr?xG}u}v#5x_d`#m^&TmOH*-i??xQjv9a7f&j7LB7gE4Z3qG%(KFXWcZNbHJ7m++V8G{psNCXAu16Bk$ zrK<;Fvr6T71(@ED_^1k437=d~Xk^8Q6&<>m3`$58h~)32RgO4i;D7!`1W&@U2Aj+` z+?Vjn<8fbtDVzP7UzwjZD=Viw4)Z#p)x+BhVJh!vBXse1n>2PjP98aig5i;fEf9q$ ze`jQ@oQUu4?8K(Iz3|}l5>TL?7n1b1lMJ!u?*I|O%k zIQ{N@&K>s$@PRQ_uQlhas;9brH^p_#o2G*_8ijE0$bpa~;Rk}u%elJ1{JDu?*|5qR zkHUMIuYx?M1vN@&Xwun za2<4cu#Lk2weVKGmq=m4#6>t5lE*>W!UR{QR>gk9tE6^e!?Axa0|Eh6yyQ(`xWe|@ zbsC?QNqEzzzZe*44V;v15f>-2im~ZPy~!gYE>-|%E|dmw?1GRb$=&;lz~Lp*E(jT zuVKjZj}L7tyVcWqz^YsrC9nNNWu1VGNTe3L5uz_-{PW*;q^YDt$LngqD8$b?sA`ScSHx!kKzb*cyZ`0EW3-R6@`;og}5GDNZ+0kH0u=h6s-Kdmj09+44%{-Z#5V~sc9Vc$Qn-bX)zBgCCnC4 zZ{cLU;aJ2W%}i=HaUxoB&_3;~=8b;sl@my-OLJe$7 z33(aCr}{gB*qMet6vusY`A-j-j665qWfC&aEE}s$uOQZ`lx?jtqg?$v{Z4aViD1f( zaC{oJ8QUd^H84W_45Qoo3H`OnKmgFS191yivi;?sq%0ujmv?3i_p`YBRAKbX`}{HY!f8$aBi|} z3Mq&HgDRkCGvb8`!Em(zxLUys2X52z8c z(Ukr;2KF8=xLV@#)n?k7pQ{_Cbtp@|1(kqWW@i-~xT6wjwNUB5@oL7xW^dp17L`daYr6Q|5^);6`IjI0*KPWL~;0 z=+pHReBYlH;+B0n!sKZTH%+>&r5#DAh^UdI{agPMkdOh zrL`&lL4PTMdH=kpRcumy{qL@KY00IhT6>h~E4{u6LUzj?XpINs2_hq<^z{06)O!qi1SRwr@uX~hn6uGw2TQ^_L=voLz!=Yp2kp;g*#jWuc~{l zPkyjIFVq@)+Hs`ITh2f<;k5X^PD8`1+adohp(faamiWQl!JEt1Ax9Ar5iGBJ`t9r{ zZdXAkSepmt1cVp)?cuW6&%8ts_Xf!WpHkl#nF)SYM@Akc0c~dG%NIBn#(e3z@RigQBsGe2h$B z3PUG)VD0S5*fg%G3$Py%z5Ywo%==psY5pAn6RV&nVpFH#e+^|WyR|NnO&Z<1!wGL} ztPiZrAE@lXmKl^5vlD}>QnZJ-)#i2#iw!0=gR9E37F*jOib>~MQf@P$Q}BYl6mwm+ zt7@Hb4`bQ_oEw1>A!p+0@C%`c9bp=)al~rtx#dw~b0yWlrJmUDyg}&h7aA}}9UeF> ztXP}vE6FlmI!5hCkB8fj1`)g{ewO~3nlV=zC&BZ4@$ii^1FH07Ed0r@vc*|f_2cH@ z{h}*oC*by_PHSGiI-}?){#xWN^v?o_e~RU(Auz09haX@9_bW`(e;7cF_rxwaLqorc zf0z1Ps)9m(iW_e3o>3644wH7w=y5a2Oo<_ep26zC@;utp02S_%FLjW6VNxIn)Obxu z+{M*<=?xla#2)CXNJt#M`Q{Awbu<8}b_LO}iw}L5xVkoXDt;8wd`H&daadHqOD-iM zx>d80dB#k)mF$2)zJ-LHSXYnBuHZrFv!YjbNwMq^5cg_32*PmDBfOn<4#W? z2$c2Cou-MFTBThT*%R;r78y2+c5UfEmC`mpqFwUV``!~61-hy+YO628I*FtK!cG)70Y1TwqplOSY%pC6Fs#(5rxGw?XiAC`t zUhOc;-%SPdIgLj-aAK^vAO&oy<%S4+o=`;A^7slfm9|^Z;)RW_CWtg5Jk{w8-@dh^l3yA^MP^OInP*1e9DNIPa1CE~OEj8m* zhh`Rr)a#n4us8sjwFWyc0{b#|>D3|0UZP*YqjbSHV%~4}_lXuBkUc!P7~>bb^fMS; z_qh_I@>$WYBm!6uwpM8$x0SXlse&1F!vY~?!|K#n;uh_I!`tWK1b5w4K`UemIxU5%N)~j=lGEX3#4j%;G;o z@{p5O>W}UwYDy{{#fv3St@9zijbTkP+0oKaL{I3EMuO3QlQ%1mf5&CKLQiqtvxXY~pu!-EwRE>j=W3gm zqXW98b{wS(ecyH;Ns2Xz#JC*s=V<(Y!Jql=bZIeF)9?;qDyLy@S+!9Pm#-+Ps8879 z>#NaKej__q$wY0vF35rHEvNxI#vC0Uh=C&cvDw-1Tf>vd-aQVu=f4vA=3v||U)T6v zFP{sa@!x4SWdo@N_X=o)v`;pIrt^b-YXm(WjfyWkT)gW+Mv}V!Bn`+<;ppKTdB7Ww z=taWIl?ekR3;UNzyHY{vPbeIUSQ^1{^%4jpedjTy<0w!epK( z^H?gqYTobbht0Wsz4XL|zl(LIan|W$UsaV@%S3D-F7X5d!#Kw3=xWiEj!0Ui#ZA}b|za?StDIumUPY}I~ z4}GwP+RgQ3NC=nxUsPQqQ9pPD9f}gG^3o>!6EhO6j1q94PJ)4=YnC@S8Mf_fuoXQC z6I49M$iAuPWKlEFazeaRh!y?<$v+THmeb10{A^tv%spS$wXQ!IXZ3 zZo(lE?^)QA62{r^)do1Ao_Ff4EIbew4gTVcg`(MBxq6rFb2YY(J?B23fnEiuCH796 zohf7isaoUdn1NUmIV7-fsrBWP3b}Y3R!lK%D&d>Cy^qu1a-{w7%qWONh+KWezkB!H zdm-+?W%qf0v|PO=vr^!8pkXjwtxC@6v0c#oBvxOb$w9Q1bh2-7tZcg4`7@En#O6B6 zg3k>iNJaHLCL+bpa(2rmgS!-g4&yBRbCqU8z#VkXT7Jk_St50zmkTbVnp*X7b-^@R z_?Du$#q;JYaizx(Dh6zWr)+~|0m`}tJVjtdu)n!_eSIU&7)0g?{<9gW{7UK`^7ONp zpfKGG9N=x_Il1HNBLd9;1%%vv9(GfovPO3sK$~e})ddZ3A;3l3z9ngAaL{VcuZ%u<@St2rkbX?`qyRN2;fNQJkDCC*QT#r|Kv z@Z0>HxY<6N#%Gu5Y!7S$+uXlphgR-B>U95hN8f7G(?aL%`(2X{34G;=eW0Ao1xd7T zT9$OBFDk~=5w~3jK>#~5h0+K-&TD!L^`s7)J)$ek4)oH8jbESkvt86$osDssb-rq6 zP|q}2$}gucERYI*FVHAagf6P6s9@?1|IP6I^q0@s3hx)w-oSw6s0HJR#xX@$kE@+w z1tq1yt^Tk*Z(Nf>aZP;Ue|7Z#eM@5D6FiRpK0RLFMEvtz;CgDjzt}WgxY^tH4X|E; zOkNfcK#B(Un{D{0fcqgPIE|H=JRJfa8uLXfMZ5MJNTL?s6H3WKH=e(Ecoz-C=3Y&D zyzlpc+z*He_|Zo9Ji1-^oj9D!&@=!m7^*7cGQj9AJjrJLb?Hx~pu)9>Sifebf~&+p8b@JccU@uzipwGK3-XD!re!vtjl-etx)3W+ zw};P+=-OsQgZrxLvi4dax%BUB21=0BovH4z1YE?+1F1~XdBAj+zQfa5HH&~*h&VEV z#)S!3P}Np@Xe&vILk6?$M-gSxWq&e7G;2(158DEZUm9{+RRi8)K^JT(Zk07xAt%)2)xOHa`c_UVhB;NN{3HFU>;nqk}Cum9P+rPZUEUWkh4(Fe~HMp z%e~j@G4`O{=}9^QYHI3=ns4lov^(CSEw}Yiujke zuGY3he4G26d;}VWpM6$t`2IXp4u0&?9TAs5-LG(4Xq^r63 zItIIl+#s=8jnt;D!^PK3*y~Ka@X-LSV_8!Udf~ zi^UM;V9KaJL)~)A(G~*%2Sx9I7Z{7Q&fqwKhwJ5($T+xS@pbb#gQpFy6x}(75lJ~& zsQNP<+PA279Qa~`Oo64$ef7R<<8?P4;)RO17S{xlF}EY>mn=XnLL;ujs9LXcAaSiaT935ivF1@n!pcCGIm@SlBy zp%C(lKKc(1n-8$y$pT|GUdW0@YyAiThs!QJ+h#h?JH_Y%m#^$qUA^KOVqs8z^G!=` z1aF?}L*tql!^cdU?HD!6)tBch%_#rH8M!PkHoEPW>I-=uZnC8cIm09Ir0B-VAuTJh zvT4>B#&80;ybft?pD~3Pz0TLLPFRGUXQ0R2)IeM+tEz59hqEPP@^Q@RyxzROHw{s@ zo(TvHgsXIFVj)|8kRD8h2>E($mjtI9p{9q#_Nv8kcY4-()Tc3_R)&f_n%F zr7?Fjhub#sbTI4u-=CC{`>|4j1y9DckE`8L0l-$@=pN*+3WKD?^-J?{#MLe~PyBNN z@d9ygA-creo7nt+CY;;!*_pa_QOYxL@h$JKQb8_u@+R0rGoei7KaUI7O}#efT6rE6`$K+ zfQOj~Dx^<>kTMu^W$91sje&^r^U`dGV)RU~jAkf?FcatVC(FF=m?31w&s*7x7i!Il ztV?>rh3*yC&{JtPX|p$Zqrb9YYAVCcCzD9UkZo1+`a`-AhN%?A_4r(HhLDnlPRiI$ z7sweYQ!8a*DZFPRLX;o7*lQPy$ftu^WoEFUJ-R&K+%5&9tAexWbGT|ejRH!7SdxZ+ zBi=d%yi7n6zH#rhrx4@z2oZd&Gu^|vm?S_g{F9So@=roxU*v__wfLX1V`FZe{_jG* zUKbb$%(jnyaD5|S9U)MON^Y>UFrS6pLum#_Jzgn&i+n8fqP}#NWn}15i6(rZbA+BN zeLW|?^maK%wUG$MK_dC+^gGhwatVnL$T`j*O7b^3eu!Bw#Suu>!_8Cu@|X(Wr=$G0 zops{*_jUIuOg-JF@F(RpX{|uYA6!Ws7?={gtuW`(3iExbVC(Zy%S)nJ-moW~DyxPY zGT;r`2|qRg{_|cVq*ln-jzNCmdY~l%CB%ij*d=>MFXJ!brm;cdOQ+`L^>2|bu}(sl zDRwzYX6n=IMWUp{sTA+pMclu6;yt8glV^PmWAv9A-3^ZKi&({sIjdJ?ILs%Bx@laKOY{&PHuj1AMtxl2=8UC zboVk*U!dKE6Wt{@L>K|z+~d0v3!yd!J3GrD#7ud4IPN=6x&dW^zpT#22VYqEqpW#i z3^)k(MFw!;rZsg!A`Hgn#VzgLkA0?ikEn(;W?Q@LKPsQNzD;a}iy4?T|As=Pm|}o| z7%Sl@L$?%Z9RZ3I=JHJUd5f`*~f3Y(PM+lo2Y<44A?xjbl)+z0NbGGLmH^#FBE?+0R= zMteTI0ths#9K5JkCMUWqcfwF+t)z{~%q?7srGiux&X^asUDsCKU-f>gNsD`96uwC` zr(xaeD7QRJJUR25c)@`x?cXg3)rXC3(ggXFbh3au51F`HyF8RrHvVTwycfGTDrqzk zBzpNUNe}$=9vMI53wS^$om`7Oq4$EUNRtYmYu)t_##J1n<~0$DJSKhuILF|HQ*xNd zeawfuj`W25n7CRUM;?wzxB~w&#D5_TAqG}b42fe#6d}jHMAk(Sh^&haA&;T^yDxKa z@}!vFpx;sz~jSS;TzN?v%E;Yc4iwY+m5a?{b7ix8hHDF#$vW<5) zVX0aID|kUox~zkzEio;X!{E`Z@~kawY;4kM9Uun>P#baI-A5W>-yJ)P|IFjST&SWc z<;ckHXz&EPyGYqy>dPf{gZ*47Mg_%>FL6w)r9C}8jfoOt>3J`je2z=OZEXTR$ww-H z>wkZe*m)mjQU~^l7UF%3pl?*ai6-CAo_LjuTjMd6ILk(48p<$FDoF1g*>k;Vw+0mD zJAa72@#L2N=hm{adDo4vx~a;u<4J>##_6S+Zw!y~xBQXvCJ3KLNWZ3R%$X!*$fbDHW>Tjmy-QSC zBohMjYZLPTAg`!i7cnBF@iA_R0bih|*|_D5hP<_iL0*&bs*2s;`b^X!2^8v@8r1cn zmx6ruLd~X*Z-8e%#gj7lS|b}bvAUQCS=~>ej3KF`Gyv>tB|P>BY}XPik~vHXq|4KP zBbHe80(CA=^SaJud%zbC1L*862*3(27{QBdd*M#_dk~1lL2L}tct7&!nv&dZnIAge zaCw7_eNx&S5%!g+p+G8=i3>l-v2Z}I*@|+3Ju`{>W%lZMQa}E59y zJZHjfV3>*k8BT!8T8ka^d=1-y;Fra4(UU+|5P46)J!vrln%pSgS-sUZc8H{uYjA!q z145q}EVO}oB<*RIn?mpgx!IVgmBrCJPnw%H3v#rTo0T5rG%}tc` z{PdS>u=Rn&NH%LuFQ&!3pud(FQ$gZfk)+#@48EkD1g?m&wuz<>^U@}Qy5yulv#p@X z=2~Q#ZQAbe6>S@ck;r9|Z72?h`|{Wu`TT-7B&rjsn%XsB(aK1;jZnO+t)R!<@>c2spKwMKi%fD2G+Hi2ZuMz@H$DaJ48?pSZ%$uXXtY*xWh_wYo6Hr41GJCp z^h1^+C4>970xUY_88BN1xtjP!y5zfR^nXVQ9J^YHuk6#C z(?s=Fao_yy~{wN`Nr0%+;Y9#6SJp`xt#cF&cHIABVNR{|OiO@g;6JUUZL$ zHTY6;%knpKXw~EeuU5Yk(v>BRj2(x1sXLtg2CcUpg;a2HFFj@07$|<0Nm0pA2Vd7< z9I+NwkM9nx=XF^z7afZ&76BcTD>ni6+}0=%S!fswmxr8)8R<$tOSd!8Hg{lNF`a0aIS z^ij&gYkh!8n3+nZoN4o&2)iT@^Tg_cX|B0yVT{2*ylRDVP@a`_Bx&^$ zD<0CXjr|Lc%(w}+gMZC)lh>+{G$P#xmjaC&zQ3b78a2U=K3t5%yThk`8 z1t^HFb!(X*ruq+9*QAgx&V2`OX7myT`LX8Pogg;B>h9A!TMkD8DMJ}0fj&{Ih|LgT zt34y_CfrEOrGtfI!I5TN${!lDM1n8K3^R01WV*rLK?Z>!G|BBp<r>g>Phvc~b3&sI!ir(_9+!tmQ8Eg@~Kwjk6df7cI<*URIMXK=T=(S5f> zl}*Cme&RBH#@3^%=e&24)R`~u3LhUQk2U{$cepWpJG(0n>ebelf8wZPt@_0^6Q*Eb z(fnP`Vb4-<=#Dt}d!+}Lje(OWEpuFzr~kS9UgNtU+VulIB&8k^!ER+|SFR_5K`zE3 zCQ4eD%X!AdBE9;AkeGdc6@9 z;i0Z?=JT9u;3(|cia5@u$!4UF;`TQ?RNF}ygi=X?9LMm+)IR1(;lnJELz zuA|HP53djySPBa-g|Hp6pfV5xPYw!oRTS6`JiVIO_aBIaugTie)`W&+=*_;A?ET0E z+1Zz1o5|uaXtpOx2>br^W-;x+_j2AyH+kF}OO5JI=ng&^a>b!_KImD0QLEAD3T8G} zYl_C!LrTyOse(@j5zpZTcfTVQgzF426#`d}9F&%RWq)Fw&%u6YPOD-tli$>>r8k<< z7z2U+emmG|Z$^ZD2Jbqs!8_>GrT{EN2!vN=Tv91pnSgb%aklLL`LB^FM2FJdFZ*Oz z47;G~@`9+R!WVz<`^uBhUr8rSm|{*GFG#O+@GgNYuuQ}|BC>!={XB~V^}pX}uU`Z$ z!PCx!b9F>?^q?WoyAx-j7Ygdx3?_;V>gY;|+tu|9_336a2A-m>R&Qqhr>Z(IN#OCu zo7Tn^I%0TsI=|zYAZk^E1fTH6)q_@aMl7^m;)gh8iNQ2{n_|v9k@Ae!07RKBQUuqT09qIlz@WfWrAKC;sFmZToDF`PfoH zo-A^GaTsC7Med^uP!?48zLD?zav&oPLp@~>Ekri zpCxuvrzy4%V=wuaV;Jn0$M@=1EMNPM?gm}$$LzWUx=ESo9-;!ssBzh=Pk!%g{i9l7 zbs@kA_j!rU-)ReR8v3|fifq^+@v}eB7>a=J?;nTvY1)&xIA2%mw$avG%AywNGZk8c zeSR$Rui#?%jTQA83fm|$qkUG!gcsM=Uh?&3csJI0Un;$sT_Kn0WV~uNx8$xVWY73htx^{r;T55DlD2q>T9{(1;GLj`hCs*NreZUw>Y?r!)MdNVDc-Rr-XZ48^XOxjb=o=5fLd8ExfoD%ua zXFGndFPW}430n;0y4qj3zxq2w3@Hb;abrDrqK||H-~fCMNM9fI0#G)C4u3sM@_tMu z=`2pgrd@9q=fAw<9A0G4ZyxNmF5cKiSdWn(m0kP298P^Czf!*t{=1<5PewsD;JLIVr|mPg+U5;ngoSeLPN zz#aCkt%%G`&kDKie?9so`=np<^4PuO+*oBW{qsZ>?Rk_5Be}dzlTT?jG2mm?#4#@= zn%j`hd~=q@n=mNE-y{z@g)}pI_ogZAYkib(7pog3Z6Vw_xp88d?P8%K6!X^;f+Ux^ zUr1ePiMJs>la9Yr_zAw^)o18sDJHp<(s#{X8&I{B^RVI=9X(W{ohdp%-oG6EbS6^a z3;ts&`lR-8gM%YOcwtHTz42BuTNKflMuPKOH~G+u7?qOW!5}T9m|+f02s!UNs)24g zt4So<2_LeEL8jps1lAOh(sI+XkYHNj)63&MbJ$Z^x%Sfen$AIPGV< zW%}dg>_^57MTh%oXiavD#Yf(of}$dRuZ@AZee$mpxb5UVJ({3+cZ0^}dZ|3pWk?%T zMeQ7co955tr7B?PU$zXsf@X=6e;WyZ{oUeEHBhqm>5EMdJURXVNtWY#BsxvPwoD2c z*RoKh8mjb0M$gt|Yw0oO{_-l$tkH#RO!bcVy6MK)66NJGZoI@F9+4-MZ z+H7!HY0qiGbqvfhrydQtP1T!YF<76fDXt#J#X*3maV)|t&zm-*)J#08|{xz zd)5^q#~Y)YvG;#oMsI^&*sC077a_Dwh!61NkiF_HsLG)I&hNS6bwlj=2L9;+LhE=R zhOlsuGM*(AXI?|vOjhN#?^PFFO;+=zDCSKUHq(ppO+E%GdK7kcf8m#}(5aw3A83VR zB%>v-z-Uk9UOwNnws~!1-q+=Zc=E;$F8xM)>RQ%Z(X7rQZ53Y{Lz^6t%MdAm%gfb^ zbju!5D6d`~B;M(3gf*JV2wm;8**#s*k4EwcsY-zp5i!~#$Bm{#BdM@#j~$-hTt!gd z#)1IQwW@0!4QNvvjhe=UGIR5-b7UB=SZp>YrC=C?LW&&1% zg`P{eL~ANxgP_HQjj)8;^VF33_B_w4Flvc;+`2tU4IpRt4#BUP8KD=wZ&;8qMb>}b z8wrhWR2Mv{G0p`MNF*kRo6T)(D5+gNj+W3?5RJ_#pWsZ0N`md5{Fl^i&MIjk#af)` zj;0aYqK46aeIO`SPHQu__>)z{F*>xqauX-BDkkCPZ;PV^NOS5g(*mgq8E_xY+*|8z z=*R4$F>O6=Grj|gs99Z@oU~Pa!}Gcl^Fw;tWaDS^qHS@j!TY=510`mbd^Bd(am_4R zARhI5&$uaZn+C5J-U$Br-wKqSszt5d5^hr5j1E29!I2Wn5Es>Ahh4;R)mntE@u9^< zZna`9!nLz_^*WudHdW4~YXLH6mEQ*k;fE9sIqSgKvICv%<9BPOb-cUxnIsMNp-qWtYaKSl@ z4#{`C?XsLAQLVe|*UQ|U`w?O>@;)-7>g}i z3+G>uHR!iB47k|Jl7=TfTe@1F5E`v>p|^Fz$nz;nY@4C9EoVa756P$_ldus1ULJA^ zYQgRcMHuc@J&3rv({lCGYtV>Uuowf>=GrGLI9cpQQuAuc6BA|-*lOV5zTFatb)3a` zi-53%LJ%TRQ{fFk%%V&Zcza!W*ob#P%uy9XcfqYEqU;u>G85=#&lWZdr(8~tme7Tp z|DeNk3HdY&3hWrF8QB?%8Krj)i{^9B%Ex-!zq6U^+$AjQ0?4w>${l(Z6TX!|;(!T^ zYPfLJgp!4bMa6>H>FAzBLh(I)AVs$!4v6QcKXoepWT`ztNB0@&M9B9@%C2D-|6#s* zT%;GimiYHKupLZSPzNjI**B6a1HWrKA5}NoZF3PBGc($gMxqm4^LE zne_BW+$`c=Mo}_x$+6_RHk8m1OAqw*W5Wmq+!&0jWClz7weDU`xG88%3;8H0#UIZh zGTSCdcvtOay2(A6@~VWr=wom56NJ7nbJE{H^X2%(Ofst!|LKw@%nd|u znoAlSrbb2QbH?t7gE0ZfaO;2$ouxkQxhOBu*Ux5EYTGR_#yy15Dyw(b2)5U5>lNIXp{(gs-EAf8cXSMJ>cvB@omls99OtQ>(N6OiB51R>iI+ z-``)g=;C^_Anks_rv_Eit7rTM?M}^Le-525#eAm;*c0LtbqkWiDc5K(4Q+1W;BS(( zlA*MR&lmUO>_%{VxPr!8IWIGL+CJn&p*krtI};=M z;o~1#*apYYwh*-dZ62W}Kqc4LY$gf!b4DF8fra9e3PDICvWk83!hjW)2+}Wq8_-ZA zQU2-?!q`%+JNK4YPFW{Zp*D;bnvr;ft`sYT+o7DV!=H8G?)J`c0y41j%P+)8W`k~jBpnu$aAw=Y z?U_4j!lh=iv`NyCeo@1IumDMX!VLvS2jV!@{1whY;nok?!$v#t+8&teJ@$l+!P3IP z+cQXW3iHsdQh&H{x_XN`!BTtW=3j9wD$MEY39N<3PR#qG+WxLSk>S_At|9-@rVRoe zjw+JdP`1yG3sVF`iP|O%m{^JJO*TqeDI)DXQtlZTv%1P~J!0|M@}=8HnfBg3He4oT zL}3V>k=q-2oZf-oC{0XMq?bcC0F9FnE!eQ2ywV$DhgS#+zP+vSzPu!Z@X%BY3f@(I z;yE6l{EzGTKfnqQl7R}sdBWuppBHET_~sk-YWr_}>i9u@4l+Ypc*zmV(Ys5hrX%sO z5k|k1;kFqs2eZw?a8$}lb_t27%B^%X`ozaKdVCzZlN#}T!h=ZwI4lybEpem!rDMoO z??Sdvdsty5hku-Z!iq{_DNXgl^@{EAiXA?gN7u{5F=x9h&t>00$XKKE6N4zrjR&cO zF|Mwh_4Pc`nHsck#1Jx21W9^bvF7SzeN#Pw-qjs#`SiL(NNQH&pR{L4(x8f_OoW^o z7vSiJE+;YOP#D@#uj-C>xXKK5_l-By-UJ0|&e^zQXY^vzeE-%Sf^XEB&XVp=Nf@8X z;FErpsnV{c>nUHMfHT19R>9+mU@}9COG^}0$1+D`SNl}xT7s#eCz(_wOuSGTR=HR8 z#n+Wx?ZhM9hH8}PU7yCGKu!h(Waxa+s7U=QpZ&~)C zF)}PsVaYpxMBlBdnh&H7*Lxy|MtJe8BpQZO3bPdq7kx%_+CUKu7%;bY!f-+GgJphP z13A|WrFt}arM;H$esHS-+r630L*?Zm-d>03*BSwu z`Q)A(|2)2*JI5dC1>zakz<)on}Vz+v4xeM>Izx)yuq; zHmg@^A^ok^#SriLz`Xww!w11upc-{(5`-KW)zdH`6ER%WRf3*<&o z(O>*N=cIyopwg`sU{!{&Lv5&%XX&gyEYV~vMFmCzX$)hK0xYu3a36OUhX@K#W?08q zz2u89+?2LjkwVU?Gy#l(zJpF3?H1S)Vy>^$GB9ZWS_LT_U>7#wby(97qQe3pl^N9q z1y;iU6+sV4@0E|+cLLmx%if-Gs|5pLa5xqig#|oLHb@@M#YgJ5|1g*okxC5~yI#$* zuJzpDMxp1+4Qycn9xe$sE!lg`+OC(Y{A@>?pSW$d4|@Xi1pMfX9Gyz2H39wDzuWGy zyZLh@{|uEpa+RYFDDq3_g%_Bl6%g|(G4bK>9p zJo`2$@P<)j1~zA)SJS@stG05xIvwD`W|M4RxAc2=xG=g{t} zeAo0C6F0jkl~u^+M=e`KA8x-312~OZt!)5fneBI70|)Jl*2IuT7m@~Qx{*!1R0i&D zt&Enrux%I7`iiAB8*D6?jV3cfxD7Scrbl5tbxMC*Tg0LpclHVQk+*m*AR=41IsbV4 zjLmS!M)4knY;<;-o4hy#y`QGT!Q1)+-~g%K1l03H<=T@y3M?0>Me}Qn(wL1ERg`PD zV0N@Z&SozBdioh(ZaAP6t0VG|P3B#Zm~+ase?qLKthG7xOZLiVrx|ie%zhPR&CnoMhrs$1JKzi7oa(toDMeHX^bl6kH_eads3q4L*cB;}R6v^>M*H@m8g!Dd!_eXFZK7}yI-TETwd(^TWak@!*Cgp$ z4{A*s9(qLCl?Uet2L*_Pa6pMal5Xman_mgrNBh?5K9P254Uf>1Iv*~yK4N#XQ;fvWBVz|fB2M){yqUzJSean}v`0#!7Q`4?V|1WOvf z4|Vmu+-u{d7s6mSxIB>E8HH{i*(D&VGM}1qBek`{w6@Uho(yVwU_srZj;5@KT{Vl|qVSCW_keVUycK9e(EL>8t~|;N^5_*yMOmNf%#S z7yS$jX`lKlx3eV!R{#emXYb@u-_-xu@Mo#RhdPVz8_V>!Z;n*Ct=^ww!lDWwaIr>~ zG+nq_uJT~$&fvqJ05$`d85j*Lek-vYO9v{7A_1xa6e=zT4VGF|H`y^pzZV>n%(Nen zZi%w4zz*2yA|<=|PdPWYUM1g6Rv(i3fN5XQbHSS-_3|fft+m~k`w3tirYZoTULuoR z{tRVU6g8s{be`x3vF)S@mbfK~55m=N~(XLcu>KdM2mQQ6oZ z3xCt72m$v{46R37xX822oWtv0Ho7Bk`iC9ti){bO03^NIBAeMZ3uxexY+#Tl-RMR1 zOLFeJ4ltZHThjyO@!@o`nMnKr@6n=Wrzg?JPkhB|>xgA%zQM0KdVTXT)#^avFl`g| zp^(uwu_!{Jd?1j!^a3XsSB-2h$Ivc`_oC#Te;Ein3%g`+Bg{J`iahX(+CFP&c-()K zA!@vPD*WQ@>P>ZSi#jp~Gw90c^vRhtBXQN%bL)h@^@)p-_kX}QUXW%~2sAZ_V7or% zcJ$?nx0ZAx+UW+z)d1@F=q{$M!!lcmA<^11#?)wSUQd`)iTp{PI(rCyCt3SoUtBV5+JTWV`t2IGVL zPciBaPWB<@(s&?|z|fL7d}^T}s1O}`1iybM=tE(h4>V*~AV$q$=o34aq#qLZCP|^H zAp-xRt74W4o7Af>WR`}tB3!(YWMqdZgS@d^u_)ZX1EB7o4?M8Bmb+9Tk2Jyu zf?#T}y^zf51i;N#E=F{Rb@rWPHQRf?e6BZ_j?|Jk9CLJVV8_E2GepQ&Xw$I|n~k|q zXLTiuH$o|rn%igtyzu&>DTXE#w?dCmU0x%~zI9B%-5XactFz30)bA; z2!b$QR9vL%h*H#Cc34;hf^Z_3(nEm(&fZT#)PCoVJ6wGyw2-c7UVbRK$_znEd~jM_ zL0Z7Joqg=5D3PV6Z@7US-AMM_LR2d&h*S3oBi*14?;bynyi>)YqytUPBK=R;$3ErA zD=b8MTY0npflK9{F|{kQV^5-Vp*O`eFEFb@pQpe54+i9d=6~b9@B@f2RPlu`D7gqd zkp0^*na>MRrCMp=iSmFuvQ;Uili$v9@&TzEWdVSAJ2to{0vo~DmM zV5@g95%v>qK)pvzER}UD49GZmc|Pegu6ms0`j%~>^$~fvT+1cIQx)F5%HOv+C~Z;M zA?!Cem{9ES6h{kjUO_-I6aPfkVGd6q4Q8|{lx1zNB{RAikQg5X@fHWc$TR$4VH&l% zxWkr>+rIs?E8y`8YXkXNXOw6I-)mtPv##bFzW?DuJx{0jq`ax5q{+RsBG}I>AbuLF zCAHmO5q&BQhabUAS)fJ)2O7papL(n!wKe6B{$vb;n4d!*|2?n4m|LJ?zp-k_0iD3 zQx>tIB)1iEyD`(*Hld>Y$hl~U8f29e_rfP`$Ts@x?@_~S|8y|$Tf~HSab3qo7|PgZ zEWZ?bL%+OZd8IOI;?x*;O7!%7f+UM~toAKLL>fL3%tr1m_s6uQiXqc` zP7Iyz8qQd682!!UK#N1akk*P2$Pm=)n;%3P@ll4$K&rp>NQ_pS;^2W+N@M9Sq>fT& zV8c(|mW)QOA8ny6zC7D2X=|}$a6ThWh$m7WqTPDRgY8=4#>L>qzTAxv)DvhEq4P=@ ziId(1*q%^yt%&1$am!aJuEUB5v`cn#B|TF8VXzeXU%c1tYo1M$R_sM-9Pzs;K{vx{W-yKff1S{^4r^m6>Tj6u(hRVIDP*`Y+|2C%>5UO zy!|{rx3DRPCRGWJvwj`M>zkO69?7N0<;15i!^dx_Z~2ZZuIRZ{s6Dqr!@ff$tyUw$ zQ#k~0X|!qM?PJY9yPq_2&G^Py>LPu*%mb59DPOGnA_Q@{3ehEz(=TX{FcWy7+IsuB zPKWqo7xRj+5SJ)wVHS9Nzr}Q55vIfXyL6NDo(e%NNe9RMAHLo)CaypH_Ql=ZwYU~{ zcXxLR#Tkk_4DL|8xVzinR@~j)-K9Y3ncq1#H|L+5T;5FP1<7PGd++bFp0z$JAjg3* zk39fMDR!!OFd-@`3V3bD5$Yl#0sIX^6T}(Lw1oiocoFi-s6E%?O$@HB8vCP72KG%5 zUq7oLM8<|Cd6Gmw=7jHekMvi{S%G9zCG@o9aS)h*r+yvNTA|DaN{9spuD!<-mBE#8 zjiIV4h?UtVK0wx*1{lKuHc1;y4_j_Lazl5thQ{zazsF!JFXpWjBF%b&^Cc&W5f={t zc3;^=U+xzCmp~Fx52Av-KjxMf2)r#d(pf4QBK~;bc_6M~EE#te4@a>&-7{a|29k4x zVl~x?c9v+vmns$*O>O%rkllHQ(21TSGhR)@=l==W^9gsl=E@g6{DVE*V*aewf?^<(SRi`r}Cj;Y4~&kQ{m?yb`f>CeK6Kcy;!lbJe}-J;4+{fd2?r-VkxV1{(2owvjiX!}f zNHRO(kNK(h$+32&hAy_Ia2}I{;n)+{F5U;=0uXN8^fs_7dyoHAZ4G{8g=QbfI66~? zI{a7o0N^r#@E4s^rZ2jPC;^os3BM6b26KG@A(%P6lEp~jojMbMn z^~Cxd4^{Ig#80hCf`mwiIrfp};Pzv{gE?yzTbLMkaMY>gE69>tiEJ721kLgHXy|n0 z8G=@Djg~xwT!Hm=>h54P^?8u{Ll;P|$k-i~H3BP*jEapxY z@jj?o2ftH0^#Wcw6i~CnfW~xv%#Ao7Na^BYdf6SdRP;D_Awcsm5k2w1FhwA}G4AO_ zrM?nkrQ3H3Jq<9HE>)Yk%#M7^FCgk=JgK#u6HSy{3ZD0&lR6}!`e`$Rh<88#h~IKr)` zjTPOuA*vU^>+#dIxg|Iq%0Q5qNn8C5i>$U)PvkpFfZxwxv?T}j0!j8B!IJpiCU~-| zvk-jvi2aMfqPe0%hUuEKSi1M{z2nxNdCZv4I;fhBvc2u3xW3M^^RPec`+1NC|4psk z|A#uTF*Z~AVU^F^fl~hSHKL8L#a@^r9UK*Pmj^YP^IbdU1qlk$?#}h#Y;JJMOPFs> zl7#vC($V*2(Bm~k$R6(_|U!KFse)m*=%WqszJ%EcFk{DHQ zvv|Ola-ycjL3x&GB05rI;lar|jvEZYw#~>~#S=cq*W5LL>i(4`eY1=^SL01HnJ1uO zeC}DU-_BvceEst&Iu z+c)@m3RK3Mga+}**E6V*k)3bf>TyT%WiZV$BtZl4Q$ zjQK(vkIBq1z`(Z~R?gaX$HNWPac9i;UGQSg(tLYt>w^lJrzmCE{2ea}(sjSpe!XqV=1U)X6_=qy^iY>6(m^G-X^D!UqffW5 zv%5M?^LBlTuVB{=p}aV>UhRSrdPex|IGUjw{;Uy0rB)5)9DQr`PV6;l2L)@Ox)y_> zWNuxuFMI43aMz#SDgp9`BEnnDeQ*GS#v9_*=sxgQ}okGjsW77ZnshgayLs?M*zz7^j|!_C+X9gNvY zKzZ@$5hDjC!(u|Bg|38NP0i^1{%k+&v1^=F2?om`icZ==HAGO}w-B zy#v7yC*TETN94aB9WxwYO5&3^|9WP-h(|5B6z8{BL6cQIds_>Vl_loft3)ox{@ISu*u;`LyyKuf!CW_TA5chCG6sXFB6t;fSG z_mE&mH23u2gzCN%kKLk_0H3!2fBzR>o>jsVnXz&|8!}U@I40bIt~>v`TO-;urOO1K zrI>uzEv(apYAT}i1gWc^!KZ7bLg%_nkxMb(3;d$yPv=U|!DTUY!M718q+znECS!nN z+F>1zY$ku3vz_r-rBtS+pd#U#9;8;Bd^p(fn15BNVIkEo0OZ75C8HUCFh(s}2GwxX zgDfTq17W{JFGi6ruRS%-WX1fihbSw zW1wIB&@U=Z>Nf)`f{t5z5rAyFc*CqffKkXZ_;N|s}3yY`dRD}B{ z>0B@lKIffjk)AZfZis3wUxG_#hA6zVY`z{KLEc=Wje?8pQ{Z&Q-du|rQTbKGMyDI% z&Al4<*uqe5+%AL#k2aY9Nj=+p0{}xO6~oD_=%_q;?6x{WViBb683e!m2S5?mBk0=v zyLXd?F0w5S)j|@Hx2*csJFg+=IjvD#W>x6b(Aa1ie>vRfd_MVSp0Yx_iibl2uOM|V z>(Y?~Q?r?w=TbPjWTdWO;MEG@k^@Qx={R<>=Bv#qMpxjAu!)F2P-p7b{zP44|9U^9 zxjGUDGA?fZ7n=a2S{QZ5)8$`F7m+a#kf~~8j#?eq7}or%W-J+^&(ziTUZI+fmHLKY zkYtg*A-@%ofhS_^uN&sz%-iuj_p@*S*m<+r<6;>8+r7bcq)!C;(9>N@&EZ!s7h{}h z%;{&-*Oysi6nT9_O~F)nAxX7PYuCxFUL?b|tNtVVmtqSuM++cQgE+{=jnE{=IOrh@ ze*Zf6?)CV?z^&30i>B~HtyK=Ex`#_*r?dg8k_~-k_yM}<_IcAT_Cg=uyO(1C_$MZ@ z$DJ)&$1d2xoLepMoaZ;XAxcDs0K02~R3@XlT9u09>bm~GcE8S6AOcbZOhJ7e3(xc= zn$TvXcL-B{Y#S!o6?yPPme2WqJBP+_>)yQhsGAO&1bRT`)|IWH0$jkmE2hozN3KJ~v>b=+7y@^t;Hw2*n{I}+6d-j>x4EHAw zE7f_Cyx?gBU6Ubxr$J0d?0rG-`aagtjq*kV0vWa%_HmLY{nDtK|uSWOE17( zsW%x=!=_vne{WAMiF=(^A>mc8{kNU-KED<)x$AIN<4?*;}&!T*;b%7rmz_t&;Y$Z_U{Vdcy1=+t0(s5 zrQf16DWvF%7--d}Q17m>T(b; zI3RHN&@7X53&B@8uD0>Ym%W)0U6na8+i8yKmGP@ky2u*jb%%C&1+{l=jF36vbWkqf znOe}KX8Q^SzE2}i)0yHh>mw~y>7-!jFYC09g1e2>nFfUJEv6pHynguM=_J$yZwSKg zy)E~6HS)^)*|S|`6y6_Lr-p3HiTsS$BTxOTA!;W2-x#z`Fb78z!CWas$AIBq*r5tO0)1X)8G~;kz0JjiKWmIsB+02C2ZTcFd1W5*V;+ z!*B2Wnlc1Yt#>?0R@{)fTCWE#SY-Qkd=x?Y0lvWfFJrl8EBpE)W7raB#KCbxO-9xx zF)s3Zp?(X2R{T`Natl+w`Otp30TjP+z0ekiJuCg!cnu&siI1-)8VmbPP7;DAoa4N>ZmF@zTgKym#qMkHDMjyE4 zZ$;uYGW6<=P|VEC82Hy=Oup&+*FCnNMjA-4X7YRMF<@Tm9{_9zS?4j>ZSj3TLI5;~ zDcMkT)l4PLjG+`vry;mMNac3|&FMs$4U^)x{ePO}xU+@EAZwiWC^(FlzJ_<;JOYpyV+aToQnCeXTHjM4Ej2 z^rZBpAvB17)2n?G^d@pwg0Tdz>;J!f2cEdlpa5`82aNL5F2D(s2tz8+Yp}pFDAO!c zfwCnsv+EnFfB^nv(yf)-bx`KQSem!Z2cw@vUteD-XlP)$?Uz#=4~F9g!5zj{|89ET zRZ8`IJoCe^{NFli}mjZGiLBA>jW~6xeDP5rP+|0j6{ut7@kb z!u@@zuoj(9`x7(jGhNQG-8&TQ7?afg1EuyV8%S+0)4%eS_`~mV@9YT0*;y5m0+LcS z@Y{?%ke0=uQm6%m^?4eLKi@%#U4XkP$RerMrVzq?V&I#QNE_)yDVofL-OwyZ1GBl# z5OQd+d#*xWIfW4e*nt~e2<}f(zV~O|Wb+#xN|F;BIRc2498l)XB9l-RswV0FDc6;>uUl~y|%mo>Pof<825HQ*% z$s%2Lq;;noyX2T9Dti$eG_G;wr*oqHn08{21pYbg$lx?^{8B4#Ab2m2N3h@H4C`Euz2 zeqFq<&UFqFdB;ads@jnj1A~b(8>B8t<_OP^!4XYmZmo*)`a$-*d4;k&d;6k-`ohkx zbgs;69Yn+`IZ_w$3v+=_JTQwkK?qM<6*?7Ee%)Yfy3}`-40cFvyT!yOqvhwa#Y%1DI3n(Wg)-HnkC6oOh?p2;>zQ1ZcUF@w zf-q$KVX)_HsL?cb#`z>xR5O<_%} z>}(@Y?CE7j;s4^j*@O8R++d{V{|sk7@LRP+EI2RCJg6w|e7ur52YSU_olO9IcCaQ% zc1V|7+jj{s;a9{=`TlqfZjT|?nozQjJI4QLIk#LY<>G7a99-mM8^=kIxhTa|FZf15 zw89$9jSSww_oM1@xg!wiL`n8z=%z3d#QqGER4)YZ{o*c%QH zeDvt`+ChTZdlFHnh2;i~LU3;O5j{Cs2Y_RpSmM-39+qE0k#yTIwkS$T(JIhO19<%nI&u6@@&R&K~-OJMmRR+)m32MoD?f zihe_bMqw9>ELm;&&daD>K?}{nuEV^S`q}94t1Jt;4BW&FnVP2Efu@F7Llgv-EGpg< z)Jm*UYaz3L1eTWl$Q?hZFYKRoMT;i`c-;L|u}8s_(TxO$H7{hIkYZ$t43yQ{RFGlt zs}bscOsTufR3b z+t~#xlA%_fK$#*?3D2=VY2V;G;U`A56F4LG<&SM(>ke)o0gTtAhEX2@wUHG2}Uu(>Rs|{6kD#8fz4p8Cb*@J|@dbkd)Y&PBC=TrG?A+MD z?XCT##CJ%x+UHV-?fxt zR{IU^;bn%BKTYMUOAzna6Ym=;3v1agVv&Mn-?$D`4Bbw`0F-j1tnj~cK5sr!+?UbL zibQ?G{kWbt!UN&T#DCUH$@7LwkF%j$4N@89B4cE`1>DV@oZ|BW7zaWK{r*j%&o0e} z#h1oIaOl2z{i%EcVFBh-mN5bI9zcDh5Q;=2`M%g~WIbdj!n8tnhbju-<@bCgmk*DVvNiY3~3a#!E>7_@IQL&9r35O9l32 zLo)HuoHFC_+g_rGH#NKbT9ERp9`%F;TJQi>@)UTWlA?P16^uJl3dx zB_;-eaZQ{sU}Ezx;WRE)fMTxxy~Fe`?ikamWZhJuN-&p0uhoIjmvPKe{#K4miI|w! zDLIHsSU5*K(Zr=zuL0_0I_Ka(PFeYg1Ey;6Gme;-Z&Ivw1I$Pa4G-U+qaKizcN2n! zM?0Jmdw|JtGx`EF1~;IgIZ~*VU_eFNS8G?{Nxlq5ptqwr7WtEj_+^|}QJA#JX?bt&Oj&s4BAi zA8#M*d0tLYbEgITP+fm}O7Q&qt^Bn+s6tw1{WaEx12iQ6^hC+nvBWUT=?~nFNp03sk_g0pI^jTO)(bP{js@Ph; zo!kdOS}COMEoySrv1$c1qKt0qoF__OSYaFy=;Bg)l~fe59DPq6fGHPVQ)CKZ@2@JU zU{QK>%&)T_Gbe*-f~g50`_x#5+EK$SSNgG~3v>nN8DsmMF(IaIG@%jcAvu}C zMvggVj^$C8B?m)WvL8~u|8zd?@tSZJ$7MX}q@!{E2BtyP{-H9XMz3sW_}UAc86USu zpd0d>x4#D;$vC~xh`11JZEd@h4Gpup%Q(MJe;lU%?e=})qXmOJD~uw{(sq-Ccwr)7 ze&H~RQHhap+u=Yn1vfCSqYw4}97R^VRdm!mVMY3$e^BD1U8%L#YODW@vv7xrk!(Y} zlzcLltT3X)t}xNw-cE9%KxQF88=X~he~3v7NS#PJC7^c*-lsQ3OrtR(>taQBFJqP6 zBD@H7#Aro)Dou8LEtIzsb=Dxx<8^n}QZ^>l*3^|F}{q69W^USwO)mV z)`noLQKHV}EbJ{5Q}1`6N_f5ZM4qL@k3M%}?r@VvZNV2>th0xn`|#GR5U2#KDHN0j z*U_caE&|GvzT%oY!c!JbL4Yg1SSHl~^3j9Gt?^SileK;6c3>KUg4i2%k#Y033n_U0hylReIgt>m0VwIj*;< zGK#WS5F8=%n2iaK0qyIT`czlYya1sd0}Wnq4onp}rA{r~U_DCL4|rxnCc0I9zT4R< zk_pD$%z#K4S()7|4WIg|B~%7#oxw^S@@C>*v`!V_{=P}V?6RldYgv4O2mAt0B+=dv z%X_=m)b#HQFSkuAL-P#6_0EoX;U3HhHoV56zU$&`k#Il#AHChGeLH0jki7LD!1#># zV7{hW;sAbr_`!{p@HtgcfEPqufCpg5o6B}JN>;Kc#lS7zD4WFG$vU*)?CNg!@JIFz z7X*IO0-qp6|3yyCUl(p?glDVoW;;oLMvb`8#w16I^t4zOu~ukNA@W))}SR?FkRhS`?i=JLV$-+(PWLqu=Uo5A17!4d-Pr5>GJC8 zkKd?c;wY!m2BMKEGPURL@=jT5w zn5w21muNI~b#f}I-f4<%f=eHTNoMkLNAt!Vb8*rHzF~1SE2}fI6KQ(n1WOw!+u+Pe z>f@Uhdt5}9!@2KeCx(h>mYI(Q|FseHfjNIXgHJ$OGQ+?DHi`tij!hE^^iZ-RCWIN5 z7|h-$NV!0&iFUvaaMfaU+3|{hy)pAU*$ts`5~sf)N6p#QGoNFRSCEi*o>LL~GHJoo zPa#C;ab#!t6z0pv7GF06T8p&ZfyXA8bO;_c;ERQMMQs9$dsuXG0)xU@r@q zrX%uG|NY>5n~fd~cW8K21pPs5oda~f`5E*KQH|L(F?w8G%-!poqy5UjP)I~#8znJr z^7!D?60&qm`p~?U{oVeWeJmkAnY;ax^q9qvIb*d{F*2)g&B9_v42$Y&Ev$jpDx%Lth(@3*MWS=vnZso+q?;hbTA%3a;tvTrUWmb#x zp%7XSVmXVgHEQ1Cu^eF!PU+KIQLHn~CEpXl5o6mxf+#U1Lj&!!u~$$F@e7sbhPqM? zAF<3YEB10l%}s$uEcE#4{y1am+w(&sC1u61l?i-Qs@?>H^{ac-uAFHoN3!M<-n4r_bZYZ`g;AN;9UIgsnFu zJg4e5_TS`dMNM!v!qttPg^zZgg4aFMDVIws{8y&Yr!5U*_b3q4rxM=s`S+cgpFeXi zK|mL?Z{8zXl_rrI6Qn_i^<;6q-7T125U+aZQnLMV-j^y=d`LJoI%-Byvhobp5l%dS zAtC&wsZxZHi@{9ZMu-_!a~}FIox;A)lcrD+tZFurVCtuLyJ4GC7rFpzrL0Ut3r?OQ z)o$qnWsC&rX@=+JYQI&*iNMuW)GPUrn#N1yfDULd$>IO!LQpKNtrpPKeNm+K{8@Ap zvLDYdoN8e_#;NkGNAT2MYP<63U%)~!V9=L1th+O?Hir_juu&*JCG}t!m!ufN)Z&m)lnwtZNbM@& z@EbSL)mFXeg|0P9-?!_QCiGNAV~IqF5(kJOC}gbmQc^d@+o z(9Ta!dh$!eA}UkLwHcDOXSU(02m9N@MaD;4eZt|AKwxqWwOt91xW~1L!)h0Dav96; z_14H-p)@{OV|sj6xa$(5I+Qz;?7`ZQJE)l(8lUH-uN^f9w(EH)t_B)l|1M^xg+EsXy%x3T~IA;NRNw+*OW5~x(e^~Z}z zt5|OCA1A|ZB~`Rb2_@N?J6}m85;C%-O$ubZfVw(8WcNH>WR+nXYaLxiQM@irpaPjL zl$MX9Y~5W&G7hAZIiO_a9;OW}2g~M(_X=}p=mhLeGYhgef>ZNVLe`Nw4qDK z;2qV&uFKRbYhqbR<)eMWffBpIOwJjJoJ5@hFH;@uMsl+0w>3MP@iude61m+7 zrX$}6@;^h=SSv^(@Dj^XyK>>5Nq=7vd$PNYvilX?kt)Sa63%{`VVuHlp4Wm?_a;XD zLIGL%Ef07xk_c^Zvv-K9>+9(y@Gf`OB=mQ8{~C@CpH~VA!SfzL3e(?S@As0-?>_I@ znl)4+s~Yp`UGy3ba06lucYF>g3MrMSe}_%~1ED*3j=HR9^+lA5vJdk`wR&jp=uD`* z@9D`OVC9Hzw6kf*97EoNpT^$x7IVWXGK;$0AeHaWNOwM@qocwHa9cCAncxgcE?0MIz7l(!+wJ3x;D!=1n_B462v} zlhKjp<>%gF@Y(Q!5KA_x)Ztn0Crx_%GEI*(NwJ>Z%7m)FFe*YLstH5sc=ti9^9~iv z-{Ik<(qOu2;z2>_GqR2JkB^9tC=|dh##f%|9X*JRl$_?3e8}=`oIKvo2^Y86N9qrD z7T8LgY9VnCJr9N4-mWq-ldcg;ZfMKID2T|#xl8@M50<;p!}sXeq3Ubp(tvVI?DV3N zd31tZ&@e61XlCoWirc%fj$${3f9*gZz+orabqWEP>hkFmAVkJVwWP?YrDkj2jqT$MQPCWQoQ3gfD`Wz@UN3Mq7AG@Nt1)_}jCOsJ1Hnc=v|X+{1I&vH@n z!Ex<1^mTFTOZIpCh4FfeluRPDxx!VC1iy@?t zDW2C$^XnUX>%-}~(}q-5dbhU^PAp-I)I#36poO*tsjx z=xvW-t`1voulVutT6_j-41Bd5XK~{_!~qTH;U@ZqT+Z{_AAKUM0hhUhPgMzPoepY+ z2xv7qu~~w&d;1-3n`5M-+sjNBzW4U;f*bD#_s4ERf+ENV3wHfemGr=_p+DRU*ok$} zQyS8nm}gH6EBS zf@^*CzjbXi))JbKgw}bX5Un`NsUjan)n?9>Q$a-d=R=zJ z%~)M;2oz85tx`&f@OChW;{T&9`(lz(<@#^LF;ZdgT z*%)v#u8cy?MKwV})LmOe{3yBf5eC0}A5=b*%Xe z_D{z=6b#dr_89~@VqzN-j4Vq@4gatyD=qS?Yv6l9(Ce|opN!jt2{r5+WP$M!z;jS0 z@(^oLXjxkzxi|@LOK;t?n?^9&StM_3df!_g=Hh``AvS#5rwsn)1h>7d7xNrf_}iNW z+FsBwg;5hu^g|D4?hY65=bV~E#0R$Y*a;zqKH}lTxo>GHQ?M2FN}IT@u6Cq*aN%y^ z&rwFoHVPRn&EAa-T+I#lEc+TJ8+f2Ki3>WPgED9`Gb%%d zs~bI5%UIdp_n)|{4y-+$DcZee{MUVZ^)uWcZQ#c!{bjgo2hN9b#iAzofRRT9YlJKx zE<}iA1uClOGQqt){1GOcSy@k?u1?p^Oo*x?MhHpY93<4+c-SicB4Ghn`co7-uilKh(%&0W>bw z{l~g&V^jqN%?!!pt;zHo4l$8?uRbW8dz_MIHJOr!QLHaVPnVw(1@}NA5o14WF~w%i zn*U3fujN7`;l4yb&{)xY5_dV>z{h414r$z)W~pRbb$rkm7QKEma|D8(!Rp}nIGXiv z+Q)iscti_F+kRJZum~hOFPD{bm30(HxpochFK!#)@Dovi!BFKUaV|5B2;rT&3;nYs zre2nQ!S}Y@OL-Rk>MtmdC=GsNNDfnL(d!l5{MtGVRMG|drOX4s!Nkn3ILIe#`y_RZ zC#k!sLUre6+DqSTj%Fduaqz^BuMXiw+bFyQVEZ;$P^RO1A|n-ovfA(ixEg>aN6V2D z29U{&SNWtym=R7Ql2gNu>eZo`9qy#DNkydt!{gE!*dz`{d^iRAA;c(8seJ6H_w@$z?JI7V|u z`c4fw{i#C#9s*Y>y}G~EE)9;=a{=to&<<51WT&*kbuJde37Xw-2lv<>?WK)=-!O#q znHB?kDSnNa=6hXa4e0DZ8`SW@`Rvei(m1WJiYo-n{<3HUJ>@aA?2b>Q@SM`r<_HIcrxvME&y!-m zbC3MBw6C`^5fE5;maU_mD<{4QopwLiv(dt#bi%XI5kw?gUawzbL1MZhH!FI8{wbLa z_~Ohj0rMK}W!OKm27`vz0chd0LU3>6w)UbiE3vIF6PC2AiFT1gc(9&fs-do9PL+>; zlugM)c0ipl(=*Urtos#29|-TDFN|DAZu~p6pgU=~1ogw1Wbfo0h1XXW1-qWl%Zzq% zs(S6g4$P|pJHhA;q4dV##QNlq%AqlXFJ^ZBh9VY?99+fl%3Z9b3s(>Iyb~TB{B*fE zR|ZD|AhgGItyh&U24lzvxnUvr?$aQ&-(+_Y{rTCNfNq*oZoAjC+sep zU&4(DO~xJ+?&>QO8HZ}YKFM!bT?$|8`g;nX^q_a0*p~SuH3 zEU-rZ6s3anRzKzbW;!yx-CzoH(Y)ik;ZmtCF>SW{AaN&4?m5>){h=1ze=U{Q6K#R_ zSw@y@d&5L%Wr=R+CeBxVh!*OyA7uQB;MQ{Z?J-_v2=mwpMfQL^sp-ehAZ1>?Q~aZP z2z1$oZ3SeLX={YrX53vXV~9Eib;!s^Px1B)u|<0PsS8rrLydBX8oC5#Z|frrpdDh8 zjT$#0Vt*}E_7uS3#IDO50C@oaBI9!cKGri3Hc*OZ2)IC*bbCb!wvqRVvg7!`Sqpt* z@HTO*CS5&H*d^L0kFCV51dKws_fREX%-3QkjDNGWfF#CNS6a5I2A8}y?73vi z<>jYBJnpy0jBaO4nM22W#BY9`RO)L8&K3Fa_v81YXz@{=zEId0RRoK!qIW%G2a1I7 z^hFR>r1@wDFm+*ZyWsVR-{x-*S#&SKKYc60LBb`6VW`M4z>0Pju7G)@xU z_QpOuvT8>Adr@=HeE~Jy{{E9Ml*tBliwE*%#~sX-p@&(<<#s7gZH`d_G2OC-kpa_} zx7B`=UcRo$m;=9QuP#0w)Rk7WzNO7iP+As)m@C3`4S7%-{)&aej5YmdD%|l*UcwO5 ziul1ro_epkp^*O@S&@vA_)zh9xn>Jo!2GOOXE=jbpuaFHGDJ`AM!Kbyv$On2i?Tn! z-IZ;7q!U^3D_aw67c&>;^%=y}4VRgd)oe91b&Z*@li+CuB}ws1aX{l`a&lEBI2R`TchwW?7o@O z!ZPFjB^#SDs7P<&QhmFPKi=L=A6ZdvvfvY%R4_Z3><15!Z*S4yI_I2&IPAdL6+9m*TuSh8ww&ow108ghjD`WeCRu&j8B6-ON%Q z?knbX7s>erjC~QurE&?M?tLRxxrUdR-5&zb8o}3DTIp9@uWt<7spH{30+a(Ih!ygb z>ZULTv7Mt z;2xYbY;i!HbaS6=@kSMDPl=g$FWbAXMf7s<5av-L4yAynUbXud1o1!)@VjE~;uFTk zZ-n1no^Igl7Qyb#)(_h=wv$i{Ix1E_Xz)0|V>a!@brdYwyQotvlx||>YrcVDq)iE_ zi09K?mu|4SlM~|S!A^KVvotFKKoc1Sm8R6};!Qb^^>scleHE<|+`M8jv%87Ls@;wUx-@i7I)q&{lW*JZK-TGp;kR`=+}^_5gO){Gk8N9R}~<1t*1)8L}sP{iF79 zVu0TBM-HqvO5LHil^1R)SV$F>MFRb|WKhB?RLGG-@)J!7R}xautQsDet0rh=C5*Bp zrYrFMi@>D<5Zm$TCs=31G=HXeY2FGYve73|q6gNinTZw|A|lOn^@!4Bj6l2*u%iVKFy#f?@%4*rLu4zZ zEfv)1+>%T~oy!$J`zYZKgHb)&BC=8`iL~OyvwKN34*W4LY~x!vWuabJEtP!GQO@Tu zlY)CJ^0@g^vwDMMS)eru5X@+7xOp3ZC7C#^Vw%+c)GEf(WLgUL(sg$X2^YDfoi11V z+A!~M3U!Oh%(F$3o@6qqeaVe*zh!>k@|+h-gFjI%7?s`M%F_Nva?rr#gawI(qR-#$ z-`DHyo(Q|tsy*U3XOPfRs?3@OdL2y7VQPu@`Qp*(>7-(k14+Jr<+V zWSDrE&g`sfP-z%7GqYnmHBrfZV?*;nvsr@+ZX!k=@TYW-bVO;Y%grPl$rd{f?{jQ_ zi{qe+_XI+hKqt`x9M=Ie<};k=z{34^5`DVqn^bpD5-*ynDyyW<%P>3hC-m^QIH?(M z$MT)B%cMy&SwbE(1A{xe`K1tZW+#!(+wpz}M?{H^yb{qY){P3=ZoH0XoAs`BZN@c0 zs9_2Vg)ham)6DOju01dto}>20C@6ANEG51cHBY3;OuGoXLq(tQ=xe}(g3%DTOB59r zNiJ6hxZDe8bd=|(;RWGspo>I>I+Ky0E=zvLaimCF^lC`NSG2aNT>jOQ={d$5sQced ziyti1gZ29Fg|bfO2~{w)&h@SrM3-BQ1f4o@{e8>wx14{`+>0D$OMc<6r+G@((cbBC z)iTL=)IybU5JkGq$%b}|03DjmOeCOCC+${5O5C_5M}ci+%IAC=jcyrC!P3`ewF9$K6sSFBSPY)Ln5w*RNh}Cy(eg8<CM8zxeT_+=$2U)k_>!ZQB1{E#^|El1}?Z1HM5ADY@QIf6q_@Eq3 z_H{Rmi|MW5j-{*u?P8qC@wBkI8k%fnceAo5+}4?!INq}F2Qt@Yn^?C#fpp67`#RSc zn;V&7f}M@GZ{tMO23&Bg`yX`idPp?_wl;$1n37EYPJLd8>R_9HY85=q!0R%M%1o1q zeXW_e_7hv&K8WYDawmTVIs_jG3NSVJQd~*WzyDkk{a}E$rj}|*YNLb zqz){IJA(yr@QdWwT@CE+IJ%-i;k5otz4sh_3Oc(~R~8=85PzX(j@h?Xc`VfpNpKX0 zX4@Fd5;Lx%9KD2>T1^S+T}vn@a0q6JY1*|nC1O1;3ALr7oh4+L6M<5j+OsP{R)x1* ztiT$fgk1c?IJyCesxi?&u?BUA*#l^vmuv@7a8+pH)_M#hJT^*C$Y}4~I7L99`~D8~ z;@Fk(>ZBN$ND{=Lc@v~soWoce*qr;qk7InHEwNqc-FHF92jV9F+u?pBj@aRL9c<{C zXYoX7suWscZ!JU{U$<*CHagXm z&vuy08kTxtPihsiZFFBn&J;$2Z1MC)6OY+}&=wXEXJ7xvq zOxpG)r3=KEMecC_7geQVGeJ2B<9yaU|8D!#0@+*}xuH}aL!RYm_fIin))p@mE+<;w zL8GsO_ZX?p1aVA-cKD9cBrCr_7oKxiqhwGnbQWVwp6WRbUJ4U)PbYVOXR|%4*`y}9 zFzTN*S0$gET|727&M);t+uAoPN_`tE6qiOiSb@9VO*1TT-V~@NET^&Nk|p)w50{U< zP#S|S_BhP;pqSxdYQuk%_zt*2P`h)~z4VQ!8Syz2(=WIE;qglsB#h7YyGf5ikl$b0 zJ;y5kWJ>Sh)s?tj>!1kvL<>~8#K4rZw}i8AkHW*L+}6#4M<)*Lzh(2h3a`|ZF`_Q^ zp^oxRk|2ufshCG$(Yct$0E^?9@K# zyf|bwbE!H9WFy0H|H3Nzj#0YAh*RC7xd#;s<6sxBHmFeR*&WB%n)q`cMFLh5f(){@ zN_ke4fOmYp?^+J6>JLz=#9`LUNN+D<@!=x4);TD&6*U|!q2%Xn(a*G$+xDLr8jmNN zp!^R*+K;&@1eEK6oNOLEHcBD^-lovjL^d=F;b$F0H9D$Av@PFwVSoQD0bjVUB~$1Z zTDMJKilo^(9EcB!UKEm@{Y=sH5f#MJ;VVDInCACpsKG+?yzC#BB|J6zX0PEjtgN@E z%YSt6aFDp)hDD88QQBP+M8TIFk(PJOn}T)~xP@F1;_;fT4?#9aA0 z$5vo1@C$oEI5-)?#Y*E7Gc{EL7Ja~6CHv}p%|O5Z5Nr#1&j{fN6eEN9i=oujBf?F? zx7d9L7u$^lV^xaab)LnA;f1K95d@Qp)M)VsB(?}7$Kd!(*wMkTo*&)p{6tJGNvUOK z82467A!|)D%t6V*>Mi)G;zj7{f3?nx43-W(oc74+X((^4-?bLb$i9#h56UEq_!xbW z%i<2rP_3XKV@IdfDl#-Sg@p#-OR1l-=%e|o?|HL%wJ~}=gX?e?hXVQR6o(nTA)5ir zITQOBj%12cBp#O$_i+DD_aq~=5d@q}4$H}#>SR|^X5P3p3Ii$+Dzx(<*E85_rhUcY z(t2Ex8bVIt+DfdaQ{rJw9f#c> z({Vx}qHkS`J>V|ao6AQDopmVE?bsc^_ zc7hgGTyN)+oUmd;rrCODfwwI+1sov}vcL>*GXm(PyvD z=O>L-!H)h{8d+1sKtkc7;mUn)R$$NAM0}MABGdgz5@ef-*F9d0=T~(Dk8Z}dO0v90 zZ(II$FrhhOfb*P#s|-n&_7>4p+>hSggJ2A^ieLwGkcY-`-^evQBWMn8>2YeHK=TBl z3O%$%kit-_9#iWRs6RVb&o|HSFHE5Q-B*LR(4W1kKag)5kX}&6eueJPTsjUj1gYIN zI3Y}Wv-#3QMf1Kb=I#v-QVMlfqJZ~ptG-(EDVf{RS%^J$I5o2T`oAwsU!|)V!G5st zWsu26n=O#fj3dHTbd6p_>V`|Qp_%PG)-NDaSM#rT1}XJ?Iy^xHveOPLWRN;R+t=~_ z)Yw#pA();)QQ_#^ujfA+U{v57EFgNzxk7O~_
V)k?`1t1wcO)S}&2p$)dx>2lD ze*{!CvJsBEpr0B~T@;0Q_HS(>TppTYfVKmk8m(XvKDuR$v0~GF-NIGc_qlk7M&|@05!ljE>XLEtD>_Kh^scz&wE6&Bb@$_w z6E-ZRBc>o3uN1v9Bho4S23MA9u5~*ZKgVLPk-Hf#D&Pw>OJQ z%?t$ERaZ|G?AT3Vz+!JU!S?e>N=sWx9W+YsM3rSrGX;@*(_?=u)BDZtG76z)TByR& zm+K}>A*g{Ti!xo9#ZPL}NSH!ya53Sw6RD-yIfG)wpV6gjm!Qu6#L_u#=hAdNs{V+8 zNLJEIEJ=|Vh$5(iDU=s9muK*l(T|XJV%C(?q#XtF3Rw0z=}d$Pf&v5+3GY^Y^gdZl zO$?H;P35RVwlu7<{6FPOA4|X@^hWIVouR|m17o;(T=J>Su@u`fUTr~iy3z~pv#8C^ zMQJROqh16GIJhR7ts^@IFQI%0wy+LjL5nUCB^6QRG6Ky_(x{Z?$mn242ewj83gKXR zAwrl-d=FYZp z6{xOUl6ldHsgnee_2JF^qr%8U8JwaukG9)pws6{eb$HYD*ns6RMq~rjyCni&rL4rlddA8vdVM4!Hac!f$QLRX znDdo>si_!aG3APdp`7eju)(E~i`7=-oP7$to`kR~zZ#=%tgW`&_McvgEYPCV7DBRU z^sIXdQz5iBpE-yKx@XrFH#Lwi-^3dyRVN(;)T4j`TAOziGpq|t{xnA7dbuC zUgodD#0J}!O&=}UnL}g1D)+MiAIN(NMGRbz(Xl?@S??yIn1(Q5G9K(VacS|z2dP`h z|K=kWf(OzYrize7da2OG_QTTX&znU^=Duao-}#52-^StN{Sg%LE5_2pf29eRtRX8u zw@BYqqEr-I(rk~mNNb}1W~{CW*}#yft&PRKkeI;NZjmJ*R_j}v%KU$-7q)o+7a8cgfmSzUglhyR7d_}Q z5TKK@2m})N#}+j}e$?HL>aD^+6YA{4VETzPg38{?sD;J-&#eQiIXCJ}6XwNQo?oL= zsU{s{Tq@joXcamLf&?BjF8iTwA-uhay5Q}?;ZcEEZ8DQIZjA7g1XUvXb_^_#>HeL= zk&t-E!~F^dM;<@O0nIrX4cvP|RIy`cjbx39`IuJ@tuCGZExVbreowK5k@3RNlFVSK zPb8p-;hbpQz{&>Mm;$6yqk~HZ3EYvHfU>38U@?od#Jn}owgB>^)w(TJ(qS+~{WD4! zd715PbQeZ=f4Ks`<@dle+@j=Tn?Aeh;NoIBRZ&zSy}<{03Y{}sXy3Q#?kEEV0}XX4uQ)% zGO!JT1E{q>0>0Bq7ob3yI5CY<^t8epSAFvY2vq+P8hEHRUe)q(!Xuf>Jpj8MUiJ*OkI+0W{A9bQNj`9&yG+V2GgQ zQV6ua+?tN?j0Br0vj!M>VXr&|Vs~1sOH7aq!FA`3Kz_>L_UVO1pV;J28ZNqJvGXya z3j+1vLQOi9^HnU0S-!mQ3mQK_t6~97BthBto_KSUv7?YI_Qq2~&k+x-B2#9nV2dH{ zUj(O!22>7>rb)dic`20!^Gwz>oKWgv8eg^HG`=c>*j%yB2)7OP!mhV9;MA4HWIWnl zjNUV3f3dl80(v$cSTzqR?pd#*LdAD#i@7>rvOF8_@0%4w)GA9-d-saPAi_qIg-oD6 zY?^L#+e!Q#9Lq=uG!bF9ox3R`NfySbm0u+bI7X_8pA*eYPsYCcDj zwY4@u$&LcK>qi{KUEf{@)F*Ke+A_ghuk|kUp}-BYvo>gBcXT$uxVxeD_rDhouwyp6 ze@cXKYfiq6GSbi0)d`36em}O}IjfW&T7cGVmJLvAZx%19r6g6S5uc?QJf3 zoC?+Xew@ZWwyx8efKk}wa4DvIi!nB^hKXHRdx9yP-G(oJYK;ek{YKBiWsI@6RL{z$ zSBw{ukH?(44QOR^P1r7v^yi+cz?r;826E}&XT^2Q-m|l%-Jy~%iyRYkO zC`@z7lwvjXZ=-iAamM8#iAc>X(W4a^ydw`5(x%5|%->4N*602Ah%}fVd0sgHx#qIJ z-Oquik4N0~Za+BfRQYeg$)vwwxJlO+#32$m%7GKNs>zaR!%ln5*0D^Q^s4$Nck9S;a=<^!X7jXe1@03QEmx*0!| zdiI|<3$6|5(?>_ZXRdXOv&XH4^zFLttEg40)MX1c<}s4FG85zs^SWg;M7wD$xA?0D zIITs#f_FE5ThK0RJ+d58q{aCTWwptAGW+*=Wj4N4m4yitB-n&~%51O4%yth2#E1LX zpk%|)Ia;!G@`;l zECNSGd#7zLerR$xdcsWF{j7sS@7UbrBtZK#-j^a!kG@w#LD~(&7#r2E^AFy|Ruy?; zjYB-$NT|U0=yJLC4B_!oAU2NZb!Ybg-eRRVnw$8B;#)vPmzkpmo^_u_JEf1#`SyWH zaGj8afv6T!2RE>iaF6W^))jMPk?*-}@@r}LrnTEg?Y~Q!tF^r|Syq?&rt?n|T)GMw z`_;Ve>E?N@*=H)@0+aT)cD&8Mz>kLvoR{BBh*~2c>0u{ryrPb%Nv*ibLNt74`{>cr zfZGS{6XLhaDxci(aJ9N1Ibb0qD z&5>`&YxXH^ZBg&$kCB^Q0~N1J4nAvE4OP0Idga0pT&4}LbVD7u{_-A^^UPx(6!2r< z9{;&XZX69QFwMr&%f;HICS?l|gQU$AzM%hJibe8C-`rYp6L}^u2c?AF3rEEIS3G8X zwQ9W)I~p2j_n;?7ZIn@gP7uqMKqXvrC3ks^VBZYd`d#VTxo+Rn-dlO{S(+__eH16Q zQ$8UZ?-)YJTX+6D(m-6w*8%gka9y6U>&FLOLV+d{f%bQw4S9OW=@C=uGZFbQjh-?@`H7e+d>y*10E5&pJ=9yY!LAK>R@Yq@n~{~c zFx1Qf@tZG%W93B;GYyTd`6V*8XT3c=5l5(~-`0k3{wgjJ5)@xvU-Et;zL4zg*3y2{ zSciaH)zaYgM93l3pQJFzUdxI^&V=8)Erx7qa}0nOspanWL#VbR3C#>YBwL;OT>XhX ztBN_sr9ol$s6eB`g363pC-f8WH-I-=ZeXgk+;>%vuCd=wVOXh<1qDQ@i>ERR=%uv zdZ#txhOLgJvD`fZJQc8_K)HND9Zd5rTPbmL`M&R{o?crb?k`&A3&jYteb80f`Oh*8hH zn%GNwR$Sjh9*)i-x!mM?n@smsf-g*LBZYGzH1Jl*jkjsDx}DI{s)dFcEM*j$-JET7 zGLiXYkdKq6dlHDtJiM$hE-$hpN+iv;eJ=4RVWO@EHefcJBv@IB15Nw2w);m~0l+AN zoy|!&?r<@g`-BCzij>6dHX^uu_A}~N>MvO{*?SM|xVuy8r~CJs4)4(S-@RSB6*NV5 zAhG78J+*@2r}`s|;~nG~$F8L$o;W-Oy9rWR^y2_?-JQUl{$*PE6ZIDkFQ&yg9#VOh zP>P0Mt=Jsq7d;|u@~>%unn1nN2kfu@g`#3&wN?xC9bOMnWJ#64TeMhfV%j1EvQ-fo z7#QZOv~f4uT!RY>DOQ{9r`F;~gyIUmMHc|P1>m{D?e6XE93F-N-dNU%QC4YF@25*9 z;+U}i6v*Z3HIuIoH#dgUDFSu>oG6%or?KeYIa@nRK$c5}jTpWRItH|0k#fC#UxakKq-+ z;7reP283pRy(fHEoToxUd_U|hveUOno)w85W%F<_s)AThgd+Ir=sad%80_IiWzNbR zdD6IU*ivs!9e2ctB?J>=Xl{pS9}mI3;uX2qERl8@e68{pW;^>Ec_`*r)X83nL(XFD ziR|_1Expd_uduUB@4eF@Vvi1gcIJz$2ory?zpDhK(~}5pgB+|3oy>aKnn6dn>SX2% z+#xD4k_KCf(-m7F*)UmS7K%`KDQ?9b z9p(?6>k!*U&zfT_kG=vb-$XA!UBne>XCfjZ0tALpO^rc(H(0GRm0`vtB8mmrA=vBp zb{lQ5>gwtMS1rQ6fL*?zjS^}TaR1!!H&QjPG+L`~N{rPFCkwkTgAMuRFG%=3&@0qy z4x7HKJia`fomXu%*@A#z>tTVI`ucjIR>UzbH=dGwtr4y}d86JBG3;{r;oGZa5+>Kz zzdzq+l$zsNR_rlSj2+&uajx_Qhw9sL!KTk9lyDjpt7BLPK|~2y+aVV6+LTBTRm7M* z{dLr^ExKg1|=P9K!@4=ShDml zW$*Vjge0ad&?6i&^vvU7=*6MbHslx?_xtMN>x?kSoV1iee~vB3KDCJWrs)d|Da^Cl zs*+hXJauXE->gCr{N9Ohj$uK_&dH2wKj9(r62Usz9o%*)9mT~%iwUL{GS_HMxr>iTxj+Km! zvgt4u>ATux#(0A*vk-`C)J+aeuE9wuOfDQ_x7%=DhjO$#IH5=fFB zJv_aL><(jhX28S;u|2`r6b{-y=nfWQFZOO;&f(7W1VA~Di?q6xF@J3~r*QylHod{> z^ruGa#=-2&8aA(Ek2i5ot@io8dQ2I-FqWFLQ18}v2fh-POIwndaPOhr-VdJAefuzU zcxV{D%wF&>IIDrze7AQ3uvBH>uU=<^1wYF2c>P|YT)l3LC8BPnl3xmeVI&CJLZS?v zxIeEb{3DLPq=Clm?c735 z&4Bl}yD7Z%6jfFQD0$1=@?y1yz{>@aYn3d_+d8FX;ldSABCorQNRIj``hR++DPY>^ z{_cXQ0;>)++P5vOEF>gE$n6jykn@{HKF7fmN){d-p5Nzhg8ojo#|_j(Cf5-d>U00F zwwIKTfjyILp((xOD;dj00-0C~qo=2?j!weQpM9)8f3FRh_bx6buGbqZl?79C{az3O zL{5wE6|<1daYSi2t0&U&Lz+!US6x{(i%mne9vKej!b@nCgYUw@mQm=Ma`QhH&7GIi z#~UgJ9sLc#E|bu+inZaiN{9D8>a;?5T7l`4*Mo;EJ;Td7o@*4RVE4R$scQrA;UREn zNGLfo8)W{DVFb2NL|;Mw4(2{$ys-N~vV4HL6e<6^50J(~ss_Pqik`<`lk6H$hn(=t ztHs(dYoQ5Kfz>ZvTM1LN?;88y99)x4=dDxrLrEOsCk3=&zWUFxSp+>hvkYMV9b9g3 z^Y9@@tN+?YJ~)N5mMSl1rG)NIZ>2;*d`E*iSf{ziD)==P^EC6+s&8g7%(*=bCbYmM zvW}mf(RHXm{k2Ol5T$aT&eiqC1i`hz)l|4hLp^Be_InCXNrfA}FU;Q%hjE5bbl`e2 znIQ9ksDP+~s5cTVla7pFW+_e7@EP;x&d$yth1YY-bI*?@VINLwAlM2HbR^psREB9_ zU<+^CZJ{!%g_4<(ov+wH`Ql;|ab&)nDUAx@N2Ji=d))ihdIOW#_U$+ev|@Gn|c4YHgD@g zscTV7UCb6CGcqyZD7Bxq}dq@Gu1R8_*aq#ua7d*9*Ju86SjLo3t0BW}1Is}KlK3&yI20RL* z6}|U4gdAT+%66(~ zXe6I7NF9nE*3a}Hm|UC4^H5PEB{CPY^QufEg#S6<5&S~tZtUrS6k7>CyF5gN_r^t3 zg6)~i;6WRX%Mo2D=g2Ry9#~8IJXU|SFf&PJsF zC&9zRyUwI_qMYtbyWILmUry%#MHQo3nv9$MSKxml)FN!+}-;xDLP7D&d8RQ-s5xn8$W zs`X|Re)~!Tu^I!Z+(u>KgXg&-DS~H5K{9JZ`LYh1$ijg~|9+LTpM$X)w=6h(w|6*P z((@zDLe~HOd*cfidopS*U2VRAooDHvPW$)Ww`q6mY%0xphntN!ortKy!@ReINQAR5 z2#Nw`GNc;#LUC^fO<_!ZtcuqIGVg2J>9HM1LK3fZMxnPmKq8Q2Pz6Q zde=52;7Cj-3}%#cs&TZ<7ilnhH|VU2-#6rSc)bUV2tNEq9GKqk*JcE-uy;v6PJGWB=ljc zZKm;8!Biy+Y**(=@K|Dhzx|NjG>~&vosM$x0Z>NMOG`(uxr|{Bz_>UhbH8d1xi~!ZbxU-|f;d~#l3w5i*7x$CgWXsbw8B3CY-zy|;ZfAe3q`kx2 z&6b{vRl7$RT5eKI)9meDeRo{I> zhQj+d#t>bt)V34rY0a%0lO2AYVF#83Cy$P9ZAKUy4WnE_0yeAZ0xf>8<}z3iWVst} z26%SXqzBcBE4acIpHi~jnVykg)b%`Ivc-`RS2t5l_*XmIqm5pSges<@xEM4CrkKOg zv4l-}ZfNUXxWVw@0(YG~eCiZ&ys9$1;qY6&hp#7ycR@a&u~sk~V)~B;RWzt)eE|Eg zc#>982gJKtJiW*sUYk#J66xt$cYYdNVBw8n|taY5BJlFh+{K~~VaCcU6^KyyJ-|j|W z-c;2$Ba2*Xy~p?~(%CFS2X!R4q^CgC*Qdxn?C-Vkyiit25R~!8MXYt zMMPh?#eG?fFBdwG4H;UIG%GbT)uWSiL3;$_Nj3SFw#jRj;K~Q$xFSd?M}rq9$Rcc! zOosLJ7!%II@jI?dkWyn`!7EiHZ?lz^m6H!cLLBxYD#nV6Vz zhiZ-0dd87H_o1U-NqoByVc^{Vg4;3jjf}rOM)>B=l?~~v?N(`9J8+nVb zEdILUiDcPi3(6DTBb-xVsH$h}-_qNrUND0qhCEAIls3)$pB^FP9Z zi#WYi5k&>g5q|*}O$8Wiigh+;AKt8q=>BbZR7!7<@x*-~-f|Z+ir)*)<)N8TCMW+z z1ICW|Q0w>ibCj71Pl0uzP7uW_r({AsbKGIoZWh?9$UiJn&2gM0H<042WcN?lN{iAWhZX%KfG$a zu4p-;7vYLZ#C4sw7UIyO5IB!*sY}swT`pb1-@={lSXA_rZ|&;4G9FRZ@SNK=msmDh zJaA2hWV9H`AuW)~25R|iQTQ5wjzP%h9hEvZH%eL+WHhk6;=$A`4_66Vy|$^f0#{5brs zT%XWs%FjOa;MW!9tsysPgj25h-RMU5ASrQR(nc|fSJwcrQNW1Ou`+P^wRT)rG z@XzqSCja}RACM)N8aTJKgbSqcE!UgNL%IN+P)$R2M;bN|6ob^2Q)oDud7leLX%+4)R+e0eg(16RxphE}_}>t(os5 zk1w4a{dM^F<&iNv%3G4tc(Rn;rzAh{7Q1}!rE$&U{u-B2zYRl|@2UU8H+&FnXxQWJ z81`^nFR05B`tL=5PfYLM$5#>zJi<6Q;MQVsGkblDh%R*d!@$NWQqcEROmYh0tNFO( zWAVju^ASQE314&)&E#(1GXuBVJqoAoI@zjFl=YHbp4UUURK(+O>&BR)l$mj2-WdI#Gj6?WMhgBmVZgt?FJ(6Z%! zw^wR;JR0n=pwC0kUHF9rVOv2%J@hqgOoje4a=(4 z)x#Fc2re>XfCIIaKr5lG@&@y8U}Vvo>ul}lBS~cWJD=*oZRka_^nVQs17nJ9`BveZ zZn@l6XQ5#*BAVXrWs%r2*aPZK2L)rtIv9zq3y?M+c9bjTJW8QBh@~7uG*qa=V)y$d zZeK>Ye%sGzx?NecBoc%xXrBt@o&l0V~jxZLOj z6<3oxX}Tp?)OE0%;V&ZfKp;O!B6^vn*wSE4r8Y$vNYed+q*^gQ)DJJu1LwLBWz%52 zhI%xq*SEmH<@j$?nNbH!DBxAJ^U*(iyjV!X&fX=VAO&-}Xdjasof^_?PdaLGDyqJP z*ZK0hf3p`BmqlmzLL1HT;*_Wfb9icdyi5klfMxgcqNF2s(znygb^F37QU+da=YBHO zXagEDpgW?Q{nl6c>fy-4$q-G>7B4i-T+P5DZ583(Sxk|ECK-_~yuAOYz{CR;tM zNR`j=eUpJvzY$j7603IxdKj?Ofqq%~h3{#X?9N2;a5omyFx#H?pVVIxWrYqM`0f~1 zO%NR-=w%kSY_E)b^YC=T@M~=#0I8XffpsX2=7vR@CCtOrUg)kh0zez6``#m&%~&s# z8#RA0Wm=WsZMuVyDAEkmG-Mr1U@TR5NrwO4;V##dIqvv-|bm4SQm!fP8BY-^xw^WL}Hj*s#x}HYJg#~;s8OaL@x$7m84kx$^foLQ6!|}|g z?`xrJ<|D%_nNc~>`cd~h2u+~zt=Rc=?T>}K{~SeNtpD=pHfRq(rM#~KFH@@wJ`5l3 z7tJ!dwyuvn|IrSy%F^1LRhKFMWq8DN`A3GU%Nu_z_exzmZ*RV{I|!GSVA4y5=V|G{ zkn?9Na&Qu+6a?*9ng;EYvM^?{V>RyjOgHI4#kZLPESRG11>sU>{Ci8nXlcKpQrv?W z3B=7m>3nd#P$B(<6EOF@J!5THR%v&=H$>4h?XFYSPv?RnTu_ahi0mF7L~A&4hj>dgC0qsO^+;g$={=bD zDs4CMC1zg?Y(?VB>Od&H_B`cqVvDUN8qpx5gaj30AcQcqwFp}}nLajQT8iCfJxidv z%TI(>S1r7=x<4#FC^8+J*X1}UN8qJEdr5Dd?Cd&!uEp&DvX1LgWNGp}ag#=Q*#I&> z5X`waG;>k!pwe>?{knfaK|&ac%-?^fJ?!A|4x_W29LliL?_hfbleNNwT9FnTDEV7x zbSPEwpjJk4z8h{_)XM1Kupb~$@I7AeM`ol{^iA%YGy7jnW9ckUM}LJ|Us=U%Zh9OB zRMIzZ_dX4kyCXZGM3KvBdh!E{Y@s$xxK9?S(ZA^tE_gnN9e@fI4=EoTJ_n3uXKsFH zgV=3DcXAIOHhg9%SMN`Z*I6rAOFu$QV9PxXH#_owxArz=j` zwUQ+C?zxsUU~)w&OjiF{k{qXsGchNSKnPujDU!WdtvmMq`M3(xRj0@@@-r1TiZy_= z{Ik)7y=13jUYgRY@h~w@^D|x-=jx~0G+OeL2eTYeAib-Tbt@?@hxrkfhu#4RJTN2H z05jr0r83bX-q+5Tr?sT3hJRs-_1!lL3-dT!{ty3)7fk!1t2y|wFrUr$WtG};Z@KmX&?(Y@NF*$b4Bfaf1|5_sglyjuAZPVA$hUKI0+BqhyE5>tmG zV6Hcu!_`5Ii@g{%)qYliLJltux_G3($6w1e(4YBj6=hB8O?%8r-30 zy71j>vSLFNxW@640)1P7lptHxtTjO*^(M@1)V;)_$r=z4#0GDCwClLsWL?PCs$MIGPm~p(I2=62(ztrvUm*AMmWswEUYAf#geZ}NkUgi;zk;GkW zdZbmAND`>Vq8H9llehQJu{y&ua4^FON18T(#=4U(tEUw@Pd(T5xIGq-Fr5&d$-OtQ z+J?}TH754ynbbkMIF;NUilkbuHza2!-UyhJW8T#gaU58MA1s?!f z^z;+GJ1~@hs_jmLygi{Et-axhiLyi8T*A18l}-nmgW6{K$&3kC508BJIFqu1@*zn!5~K^y7_{_S7%fBHlq+`b_6;^{Qr?n>sT{b~9C9+~}Q|09bRu*hui zB*l`2{u^l#NmA!-^#?UoXGNKD6zrJghtji=IdCon=62%mLapzxY^ONYQir!u6naDR zcei1pCK2tJe=xapE%fa7cCr@BdynJK;L4Uu7~f7`mZBfRs_%V?cxv2B%*aqj9PWDf z%37dqtP?&Xq0RB_cQ_G%vlD85yLZwbDDkoj2LuT0d0> zd)#kR70YJ9``RLVw8P&B!zS*`9_wL~k2~BQ>tt=R>GhOD+#bBw+JD#2+5&X^~rie~|)0@s&lOy*VH#*13q_ZLIeob#F zrX1@o@5+m(`eQAFk8B}cc^&hN=Xx$8^1{SRO=n-3#is@U8urXtvWAy$_E-)3U?!*N zWx7~y&Hvzf@*+AMfFTJK6L_b7mZS!xEE4nkAQ)m`SS%LsK#2tb8&8Oe8+L}jo>ZfW&&Kw{)_x5r{3gHR7(=(V!(`BGr~Ij^h;-W`o3Of|~Z zcB$*Dbjr*je|2(y%B;x@|6qq;+rO-SXp0agc`keI)nzjJ0bG$wYVKBFUgoQekfhA8 z-GQ*c7O*GlWHnJlbf)C?dRYGM*H68z6aCADKE|&aHiTP*>dun8&h39ta@iTI|es+6)2ROZfvJhwC?ojw!orf*zUaoS1 zXjty6#$(@A2wNjWV)TwMf6vI1L8+_G@oz;;+&SCjqOcJ>DD& zJX4*}3Wg#48I~kqH9#M=uq?28IOXRhHC0UKawoP|cDGN?PvI?}^&*JNf?E17r1N013@4+eisIP37YqA{46jD9esJOOfdz2n@F2{C za}$n@!|~i1Tq;vypwA8sjJz0Bkm`HesEntpRb}@p^#kA677GDyp3as4Dvesn-f1cs z)ICf@)N`=RSFr6Q1fd2SBGB;-Ho*dxk`)yjeRdqcBI;;zLYjp!?IjXG8q4jCfG%fh9c2l(3vYi8ZOgd|X&yqj61HR}Nb^#PKoSH7gjVn7u8vDOGSZb!I17 z;@-xgz+SEm{T4TQ%?69h$R^#02IT7B~CQEFL7ioKlBzm(_89+(1WA``h>5SXBZIm@d`fvs1}Nx)$>aF<-207nUg^#Djn4c#8rl){6oEJEhHviV%L zmymxi@}fF`iTq>Q$c)o!VtInC2Ij41ONtDw66%Y3)xVm5K((Whf&3q;2K-OrxN>?A zFtSIdmlaoCnw)s3g1U!hvd9>LqlE?;%E(7ki@O!y=B7XtXn4_Z|pbA*CUrSkN4%L z^gHPyS0HU8X;m$$7Y#>VLLCIj!-_s z+w+O0(+_t+*6(h#TlP>WP|6A_g!14Lw(6_gsPI?G?T^d+mS$gcAUFeK4zeXZGY)>( zjMRKik78@XHw>FAmXHDK#Uy)gN!c)<^M{gW`s2VPtM`UdYjyJqjGv28ZCt;V*~*iIU!u^Tov zo5pI~SdEQ4wr%6P`aJJB>;2X`e?hM7J@?G)nI9&9WO2LTSmwKwAnD(9NJO`S|0!zd z>foFKvO6^0hh@|KUxx>CWlT?ZMvl3o<`#e(!@ga zAMhJ{+dr##&qLa=u2UVBw_a%W{&+()wgG?(Szj$g zgjvvvkX+-@jf10>2euZwFPmFAAyKZO5j+(Jmbck!d}coKXqH3|u2C3kw4mvt42MY^h)qDKG<7&1m5uI;O*4V>mhkws!SMHgzNS-?_x0^yk5M z;-jt2hfU7EvWQ4>#V&1S^AAFZJ-e@9FJKfLu9jcEI0h z%An|&9im6gm9Oc-VHX`^WNiV@&(Ciyt;vnDu(S|m4pVOn0zaO2=*nKchwqa1BYHiW zBhYVlf~&I_6YYoB;B^gXua~5n1kD9Eq<;YPw2d6Cp?%cs2`BWZ?gSxmniS09j`JHR zK3e%IXn!)Igbe5DJns_{e};0eXcD)dxY&DR&01tl?!LWh?DllE!*8_DfgeeOcd}nV z*?m$BQ!#=Vwn`OgZp9AQ5)kG>xc7+du1iFyv3>m*LM1`oIH8?3e-yaaOSO^nAiz;F zNJ7@ZRl>;Uz;^ka<|SZDUyo@y{0Rf(G_J*K3NA{2e~SK2bCn3D`_0-nE<&^pkgoWd zY}B}M^L11EkpFO{l-@_9MJ>5m$c%>)&5l^W^FpgTS$uhi7AaGq5G9A-0~w1>UBuPZ zRn(G+_x+B9y!JS?fS1n_s@iQ2z(7`Aq1Yd6|qjAtaEwTR2(fQ_*#&{IiG9)A`(6{S*a zLNi%~b1kzD22f8QSfY$_-W`>Acn;luuI`Z3^p?w7<|UF!Md>T$OkZGWfypskWEP2S ztJuP&;faqXlVR}pq{w+??xXvq)kE{`D%o>uy|*%vm#3Le?i=1JF9A*?bJ&`aVYjLl z3G)0MA^FBOQJXaCWhEgB{+`NkZo1=Syxd61Z^ zHtr2)RH00arvPs!R;q_WcX}46Q4z$6Mq30!7x+h}K`Z^~%?%!Cdy4o_ z;aAD1%N`#q$~dH!S?eC>T)PddKqlOsnLf=#mv{%y`Muatz*Z*6s`CiUMqxdA#w16e zy1H+C{d>4pL|(E$`3SM^Kl*>p7sM!Ja>qrv3RmEM20$3bMUn_6A#DJ7a~n~04GtG< zq+*4H5mjC<11^YpXe4}6GBQ#7l5T$nzK@SJCFw6eOM0;b>5x#Ct?s;kjE^x5UeoQy zzFz(JMQ0eap@Kc0;Ser%U?Wf?eww3Ef?7T#~S$y#B^L=Eso!q{LUxl@uByUtx(1Q{L9XJl#7ECn=D;nRBrd^ zzCy7twYF2ZP|uIO9~;3>j#0!z4KR$bvjRwlv4dNRn7+QQ7-L|D0qe*-wFW_aOT`{B zAZcEmuwCpoP3(WayXFV>sO#25{P$3`>E!7@D>F$u+N`G)lyh@F?1@=SbvI zqurCe9!~NMYD6-aAldzg5g6+C2wXNZSWC3Q;o(n!72Nlflsh;pVnJ_Ax8wO;fy%wT zy$@?@8l@@Jg{Qx;*6v8;g!X@3Wfo|-n#VKeY&5LBoC4TDgx=1R$`mq<)&IWK=7T93 zK~gwH18_&fjhi=nZ600>+WhgF`4{})Ru0Ks8pnsl!`}WMm=hEDi#Vw$_97!0WF^@r zf4qz_dRLsEE(}JqI6eS$T|q?G7-M@oa2z!;!gU@<>Up!xm81Lx-r`PAn;8W4rQ+Gz zeGG~S)Bw8fax;J#65uQIx*{y_=hj!w$!1qMOHUYLpG%=T+4oqPQ3!DtD9~pokys-j zC%uodmmd$C0^z)#r5z1AK815J8k^)HI4Yr}9i{Z-kJa(KpER^h@ifw6oadnTwD*K- z&AuB%lwqGp2Gv7=J(}H{Yz9BnUK~LA#FYkvUSHXreJ50#^$sW)8p-uXIKzEs^8a$6 zioTLx1ZPuotYCOLfk)Y#PI}J@+?o7>)g9`i-CZ5J^AR7Av%iQ;;``i=3W61-38VwJ z-7fM`@$XhV`zp>_gNa;oB7`bn#l?oQnqs0GI%O8>lT!0uS(h zn?XU%`1$i^58y70L9J+3=&7xv9yg2?riNaby06hRbo@pnvtG$kMi-qTAC1ELxdNnzSX>^l-u*<4*op*!s9L5_ zdVH&dEYhUX4*gVn!hk77xv*OMv+F1r2s<|DwrPWSSDU{QE+Hm zmMA9zIcH-LAn|k3BNb~Rb+^Q9*P34PaFh^+vltqVX0Txd;lP942)fA+Xc=2!{3 zqXnb7^_g4_VW`qj+U{=tjz*|5N8W8A|fI{GLu7uRJOKUE``BZnKF?QveeFH zpQ%ND^YlIE$8`^NWEp&+<{^gcg{+)OZb5XHr2vjF!%iCL>DnF6bBun+>(#343ow#b zD+(wF*k^BMLnyL``ChK??&DnXm{tRYW)0QZ(L#)>&MwQc(Z}n^n+Di~I6gO%OzQHH z!HLH6~3^%1iR&KnjWs3C+zW91{tk zG{bA^OyP)rMx+y_O~T&1lu;P{Q;6?oNL=S0x4CIpeEL9xrD_VCk(y}-Fjv|xqAJ?{ zkuIz{`-|lb0=D}A1FK@!{1aDDRbmf*HE&c%%K$2;H9;7OU*9H#i#&ZYGXoysP?YRp ziS#dz`kEb7ly4fyaB$setfroykLN3=O4X?CR)1ryt*z-xVpr7`Km()B8SDE2B?^#etqxcaBq^O%}vPdq4*~TG74?i8iN0eAkX3w z1sOTu3Ukst~ ze5nCJ7#PE%=sUf?y+T+eFF&e@E8y7V#7aVFJ^Cl?qyZTJFa(ssvx-+j6VbK9xIE^! zY5>jR-~3k%4>*3Rpn!W!u8TW7F-3i!p+ox9F5a0p~OM^9_SScTK#P( zk@^6zHWs7DbF(VIRF&yAaGIU%3eBPw_=FupNBM|wZTu;A;)kaeGD2QAN745*p`h{w zMez~u@csRJqlvb_<}7x2Jqy>r-YIE(1=T!1UbNNng?mQs?vkPQisJ|aqgudKUn-qV z?*-PFy`*TVwA&A~i?)m6x|GMiKv5)cr*FRYD(J6vhHUE@X6c6!z@(C`%wS6XE<(d5 z{FA*r%J4bgayzn~Rqe4t5a;%ARBoObNX z%{Qk;u0Mx`HxWgk2lUzR>SW);7R)BftB6k+88*xcVpd0};hnO>#G+s}`~J`d?GQ)8 zGzXw~Ct$=+f5{L7hmAj&VniYtKE~56a&c@vp%)NL4t~9U+S-eS)6Sa1MN(aHGP%cB z30wMM`fe)GVs5J?8&>RPO}NN{w$B~c6S`7rVrbK)!RMB+s{~s&C?+d+-tSe2Y)MG@ z^zzYxST~@-RL`itB&FHgh!SE|9_`>1+7d_tfVgg7yWy1=y4{S@EM-rh?VRrV*c z!R||CS;3Q8eFtDyB`q(%bDLzGr(J6TsHpMk0*td3#0Hgx!e`6ePKYUoontcp)UW9X zf;i#gdEOG*y%IhuwgyZ-#u}yufZEyr%-PJzTSiA;G+FNK=uN&y)&C@s4dpnAn8$2X~y5349 zBi|me((EzrI`!VkZVs1FZ-s=rQK@f(>+)ch6uFvMAN>?=2TMYT_?_hA)a(zH-u&x2 z=oF=+-pdl0RFpsA&$I1&f@^KwmuPF|$|{S3Ui#MG$ER97m@kid<=T9GV3extyMwo{ zry8@6bW^_c1=o2wHE@OGXyT=1>hy|CKmc0i2}`8sjvXEu>*VG2?^+S=QjbJ~YMx>M z2~b3R48b1T<`oXA@aSqj?+2L0xE&b;2dfg9x8Hnm5xvt;I! zwMZCt>dE48u6BX92PN#lFhr+BYQ><^e6;9cY^ifi&WnQwn=AusSIPjBrQb167FU%ymhs|>lU~z1agnX_M zqH!jlX_K*#I+t2K97l5mGfg#RTouiw)r$@N9z%~)8TC?*zn9ntX`zE3C()`cK$hp{ zcgH`sG`~?U11v|NedqV;YQ4X)cb+&=7*k6 zt}UKyGYI=2fr{gHz^*A#Hj0+MW~U2p9BbIP5<-7y`}yh7S6{f6$VV%>JG%|9`8z)x zx5t=RFpozx(d6fP%0LkzcE8PLzgBg@Og%1#0EhH~gHCN6+sUyy8R$0q`fYLE82$U$*Eip?op;6{+nQTYp0(}=rsmo&Ho6eykJMlsEX+4d zEaBKO)Z{aGLgm1gTc|!KENOh_YH909@K$Y0tkVqk{6T%q?r2^6dwYY~aoapEpL-Zes%%~psg+!^91104SZwDjf=;jExDOFw3+d=u zlVN`5<%T7h$cJflyjj|B2vl=8LB1ln5L z3RAE6%TRy7nR(yCf|O3XfFUg}%ExH1| zD?PNlX1_UET&rZ!>x@WG&#!n)yJnkbYj`|$=4=M5=-N-Qe0nmQ80tCW=-twHF{w1% z#=OOXTM-LQC>KY6zzNp{z{9nQ;jD<_8n!d?T;j=Ih!pZZmtp=?N+0ifk?rE~X**@sS@l%re8YqP1TDFJQpQ20q{y*OgQ zPwn2fo`$nw`gg*~HlKq|(J5u~0Dd#B&{rNYHazfVz}PLH%awA68Ged4p9Vm0NRv@) z5$xW&+D~#S1#@xe{3EdA{6gPd?z%%)Ku3Zi0SKJS{`-3CRAJj1yjvDm7E6bVJ=2Y= zib+se)WT`CxbK+>u3I?vHd$4+OP~3>Z!uLO@Vd!>bNcMQQvfAVeYQE4O~F&=OLfP9 z7jd0AP}?+D8v^alOcchhhf^rgAdaYT9BG&%ut!1BM)rIv^;oU?nsfpv$=6t&=^v!f z1P@P%dU~0{xa{4EB=WGYEO0^&a7F(S#DBZxl<-H_hMz=tqv@aeV>_YjH~PsBOI~cD zqwO~W$YZQ$YWMZhYTc}YNC$^;1dpQ7mu-d7jn(!_9rajQT{7?uN;!WIA(uWwR?>(P z>6aWN(qyr&yOPLpe9<7^RZ{N<*kACFa|2HaSlEFiyQW1`HR_ZD5$Ju>FClOk8%Iaq zCMT6S9M`h)6B_}yHtJwTFE!dsk>|Tp-o4~Tl?X7v#oO%SwS7Z&fc49sJhD<=1$4b) zn8_8oTGpAA3~Np3?WGj>Yi_L6lbzD~*9~<^&z$69SdkeU#6eH`$z zI{_&E`4|4%c?v7uXz%gN-^V#`?{MAN>kucu+}4^Zk_ZTLpipZSZFd!{EpUAy)nrTy z>kl6-5>gZwE10!fVqyTEJMYl9La(XbU{26iE@Ri>Ia92|0kDCnOM zYR=*?miIU2TZlZbH-hqJsXb}w9NNDU%}I`T-4!!CT`gc|t??kk;N1705}DRmhzr&; zTLuojmQhqHc-d*Q>G65yuYY;zln9+jE<>wN043!m`^i`M$}U1;oAhlK3+xGbfeWV= z-+obri7r#7_AwYjkjokMeZF%h3Yz*(A$8TLWFmbnF~TOG>T~5j%q22OCsxaM@v0<# zs;8sltPLR}M78t|xJL7i22Ot|JyR2sd|Z&8_M$4}T@?BWcq~=2Tao~~NdN>?AKU0m zYZGQ+^+c)m58I}P-Zr_@ z)?eh3xaz7R2!uSA+J5LLN^3M@vq2v3Dxi1+@i&FTxruybZko+ z-A|7gP?QK9WEqc9d17x_Y+b_zZZ4i(-lC-{Vkt&9wZ$i1luFH`5+oB-j;Uq)iFpa) zld>b2KnAFU)s=w?zBzh5S*%OraVAeqY|s3tfvS#W&Ik(+zx5~#uPrk>zu6nk%cLc= zcMPg#FB#sD6`RW85%q%jSjsQ?*f#R>$+y${JrMjhhhjpny|9oSv%_Hci;Xli**RotdVbU&;ZChv=LlNw;ua%!1PB5jvw%k2zZ6diC zxlYC9bU_4!&mz6u2ri^Gf2rq3Z^VEz`F~baME-`u919p`U;IMMQV*+l-j;lLc(`b5 zi~Yg(t|c92A-g`;?sFgXsy15H*ys-4HmzLe?(Y6@Se)yb^HHqnCH;}348NhD=*&v= z=t7dUddD0XkP290ps0$lR%7yyoho1cm2&;x#I8h#G8GigUhPSdc7aA^=`PZb%HG$S z`e!`rk>_c|v_4Y+nLSmpJ9#G4>G{G$fVYFt1BF>C7n|0Jn;D^3Rk(M46e^4lx`yRf zSez}Gx7$g02G((*&g;DAqj)UTkJp#ygn&aLgX=*hk{X*^Hf`PXp4DEg6pNIa#+uNW zA|eQZwoMCbI1e%VdU}#?*#N5GuG+&8c1!TQC8 z$|Q?Zg?1(^*+xC>3!(1}hX zmf1gB0DboMnEOKoZ`TAf7_iLjZg$4lI5`;w#%4FG0I8&6Tv>mP2D~Z2OC3mOx4gL8m3w%8j=J8^Lah=> z5UxJ)GFSNmp(zZmHGVC}3r+JmC22p|j|a7FJ~KBQn5te*{#KnwBBQ(E{jXfVFXI=$ zb{;WsvfSkPt|<_|SSaIM9mi^}j&Fw;)w8rlh{m{7sQbQoz+puCROBXg44tgZ)C0MO z{KPWDjEuwo#j}OCcVGmAGAcPFIUPwJkwIA~A6}RHC?F~A+u%WJcqATo;97;Yw`YMcOawnQvuA`Nd64OPdAXGnN zd<<2e6s8pj5UfNAs3EIk-CBSQ(}wtn@0NNqq@%_w1i>~8A<}-dYd*a_5Qk?_N}*=V zOsBBxmC&Z(Ml?rVQk3(AsU>@=W<&4c;X(XEq~XMnOyl4O11`r71JY+X(1%c-cq`Hm zvi%J%yRt%>e3FlKBL!YVCEK{KL=h9BU?aJ?zyGuw`7pi>t;Yb8#xCw$N8@YV!Zd&` zdv?(O*WM_-Twul-xYGiC08S!k2gUkPv%)_z(0Wx_Uke5QsS(y;4yKAVS-GN~n0l+J zmL)X1l5*v979PBvJy4!30ktkLYjX=2Eq*0+W-S6F8xB!BD}g^2F^TS~q`JzMp&vH_ zMO6<*OVwa+?!!xKSqV?=jm;gv)zs9|GSYh2#_`I8Pa(c2 z5G@c`^-PKDi8L_Tz4oB4ne%W&x93??9KpqB)_KyNXJ=Pz5&EJZOFsp7ZL{a9N<(YX z`UI??*$%CGL=0wy0!~$1N!nCa$r1yy3!0NTJVFqR5H)!078m7T@y4y%Uv#s7K>;4+ zSV_qvg9)JTD(Qff7HdgZNXSJO_)f!*S+%6xWXW#w2?j6TQVPuEcYcZI;;EKFntKK! zM?higv5v!b9`SUkVVlj2gEWY4;mezzY=p#ytR*LjJ}t_HUK{#40+NErqCt@p);BN8 zb9yhm;kDB~2hR_IvVGnz2@Rba$Ml4O_eP%y&iz=ha7k5c(j zeBn)N@W&>KD1#`Bkf}TffaLxmrymg6+g=mALX)M?PG;81*_UCn8#bbcEN^=|TW!T< zw?Le)HjJa!8iZj$+Lq1Ed$TM3lQ#?rH_6AA@HP5lMk;6~DX&4bNcO`%DHj(upu)H1 z733i(D0nwK{VPi$ut!DckD5Q`XPBF~H{Bn$pZI?6n|NTZ%jSUgu3h5!EPX^915;gT zTvVLXRFQzuh0uRsm+?E)C1zKhJ*55K*BRgmBBe7ygbxiQ(96vkPRNP@KXX0+ngzy= z`*dA%vF%y0ja32-91Wr0^B1Zdk=4WqniqX2`nb_qjV~i$|L&r}woJEJ9mfe@KB1Dc z!+_gtda<$kUoAMh+JVr#m%Le6IRdl6l$E$AzA88Djq7OcX|}Bmt-(3ORv}hF)euAI zTd#puQSMTZo!oE3lJ&q==t1FzaVig7ZEO~n`@di+Nny&`9P{HWWz3h)Q5y=pJ2VuA zXP!F1bhQNYPQdHFyKOKjMgiLtUU!W!O}B*Zm@RGVBzp8fJTHR6f&$OCjqczN=@76R zJKZoln_3z%;%a5o$3U}FQ(LaoT5#CQNsG6EiSc{FK;mMY(h!-*|Eur+7&WUWw_^qB5@!K zcbz#qd&6dFa=@n`Z869%ca5si^r97&$rxhx0gkA2Khz~#e!yScT?8gpQlJ-Zvzm1o z*{xFRDj~aHI$YEOf82B<@SuWp}t_y;~u8Nrg36S zo(!&OUcDtu31y$GY-}9>|EZ9O5fOnFc)#nI5oSinMm^j?_Ln3zymrs$D~jfXD;)_w zu^l*##XEk=?AJIj`lxvoPcX4#F;c4y#Av>|fN+A{=Ao~?aJn*VlR&ol0El}*+}y!G zB;2VN*--Wk3|tEUf-uvQlSbzZkzgue4Ly@ojugAQyS3bj^RJ8K&C!vOn+qD>R49$8 zl&TS@L*q1Zrrr5)psqNSC~T&>;1a16wlED{8lkSb@bU3~!7PD5sq3)HUM<-@bUd&1 zI%)c`@u>pUm~@jaci6KTb;)%|%KLm};MN`o{={_6bJD&sCP{JrP{iyJY%( z{aYl|M-DdBBKzWerp%Z$aEes01AH|p8vX+-f9HjY(X9SIOq#9+LmL$b;w8Uo-Y`cSROXmcZ;#B!SNYs2is!hK|C`e64T~4IzLp z28f-L&60*vxuL;jqqH`#6in3;TI-bUxBk2cC~f4}8n5m!%9M2)BR<2Cu!EGeu{j^> z2Es(ep_&C054_b_fQ2dZ6xOcDAtU6}MODz0K$>k+^+`J62P#O!!Fn3XK44K3K*_&i)A*SMW~Ba?tzjfZKWFCV`* z;O89K#LL$l#g}B<6?spV>=sy;Xf-jV!NC9R)%&`wC7rV#X>0=%H4+(PFK<5jHcx1O z$Jv*Dyo+Cy43U&hq`>><8^d?*oBRcm?(tvGB&f+Pu-i%k=1TP0{t#qBT+XmZz+}O6 zkPIp}h}uhf-FUr2utc|#&Bsu$(Pn%%g+T|x)YLRfz$>9W{Ytsi#Xt@3Zq|#~I-Sp0 zWwfI0^PFGx4i`;MO52ZmdDh0+sc62e?+0$eyOxv}>Z?uqO*IER`=jZ-y!xeuc*zt> z$8o}MgQW5WEa19I`@x?OrGKTSFBhR=9|pzC|K-BP7e6!Rw0jK*Ka3;Ta@iu-j1F!d zM|a2#ujK;=Py0Uyf25}MhxK-YuDUqQp~}?bVaXA*-vvVHwUH$h zMrrdy*Y!d)AK{T9{H$}mp{Z0`Q&cnSnF;u*aWi#$=J>%{q{fZ*S3xB#?sy&r`4fE$ zbdd0Yu)TxDmPZq)*``Oy<2m!;z@CpHR)Ap;PByzAR@dCAXuIH$09>k!RBi-H=cr2q z|6x-wN055`6y{Ff#@hN4wMsol)%0`6*A}CL`EOYCY%AZ*oah-KM3?R?1Lz}{^0O-b zYAkv!O|-RKH-AY+ocsLSRdjbaS$L6K$9U+L)^1}<;>sA(7F4y{jrFUp?tPaX&|t)g z!ROra@*;4wbi&f~#A%b?PxCX0FV@2+zN=yxzy58;Z8J8q`6yLT;d%osWCZ`y?vSGG ze&u*15tJShs(Qo(=J~Q4eES!aD`?lueZBWr{h8X0W=NXVOCfHyb&K;m%S*Ss0-tLw zFf^+%j{C04<}z#ida(^sK+J~i;3Jxq`{s0FjV`Aa3^?{odM)1-atvFI%NKI!hra=1 z(%}Z)f*3{trR911l`sWf{`gi?=6T1pu#-yuTKj$C+BO1PZVS`rs`iDJdoZSTudeK@ z#?_Y(SObifH1Flz8V+%~fVkr@cFi6wY8GpvngQ_O3exe4`w$>IAg*SdgmJ&RjMD7A z%g5(&^sUw7Q0?mtzARNBeN3B#b4RJ0b|&f}Qn_7q z%HYC^xaSdJ|4y}8=u-+lz6?`qbCn3Ou?$Wxez)d=SWV30vfqxsdJ5dG_Vc{1wo+(R zf&_nmq^II){2e!#;Do7^>8)tl<2ba#>H7m3n?K7*m-?_Bxc;>X#La zd(_dRm>#eLXp;UH^&gz1BuGaEnRKLT>_pitm)(XxbC+W}=%YvgMKUNtnK>KwF{1<9 z{3;4tV9ziT%LQ*q^0<_+vTzpygPw;VC2ik+%b$&Ts*ORn_;&^0yg;R&*z$F%45p=Y zF75LXMiNO~QvMdGJ6YbG`n`51W$jwd90E5;omijL6#G}~T56k%x~vE`$!;OLA5qI~RYWX~Q1=>rDb{E?m=yhNL$OVsojzJeBFoTpbGy6F4KL1)y z>?*jm}G%%hAe8cs(avvEph~W z9vFn`j>jK`*}&kS;Xe~$rJFnruMRmH2^8ZYp|?cRqvjfKc5c)8O?txCfjEnnm>#N| zTFP6h-rZFB*ky)*Mqz2FDyZnpY5~d6%MoYoQMrvW2tkgaTn)i9!^EXukEhb)N#EO? zuUM+&&LO^wrJ5d)S&K6qB`faVQ@F}jVu7Xfh!$c+q{`c@1ts;-@oC4M`Fk0A_>mST4uH-rhboyXf?4Kbg|M ziR7Ix#_~m5~&Sc(&X#wbHXN@ z#h@z}y_L0P2&WDvyBMC9?|9d&M}zF+GqT5&0V#PJb7m^VG~X;&YkjH1P)K6?`ov>3 zC<6#MZ7@6es2vZhBlDu8O~gB&&-i0)DW{HIzIj!u7Qr*m1bhGnMgnKTkw=5;W4X6P z-_1x<47X?KeIC0^ZBoL#iYBgY3;1S{BY)AN{zz28g>ZW+IECtE zLmf%z)UpN(`Z`4a$RX{|%Yk|B>%4G7RNeXvPS%@Bu|0?prrpvEgiGrGgv$p~N*V8! z;ka2PlFE1bji({!(yUzn`(~Nkq+)k<&B=}-N9jp?Av0D?xFZx5SL@yII0Ngm+ z!cd{Z&~wV^MEr>iCB@(m;BTdbITlUG7?>XAQHoK6zc`{bFp9B63N;;dL0-M>Ofbv6 z;hWPxIP|L<41hq(_baTn9S^a=QVf5ZgF(EzOYaRHd!o7;pfyF8@&tdA{v;XsQW;;? zKXk?4W-Oy2k)5SwG1|E$zYr-SdUA#-6{d)_A_x>49Lyuf z7l}rT7Zry_v--Wb?l;eS+}65&)?}SW@YHo~t(9w?>wC9YTzPGp-2gI>d%QbjBGZit zDMu~%s@^W5hhF6gUe~R|AMRw&q~2vBTZr}XwXW#Y0pfOt+UE|e2U78nbx{2HrMZ2H zsH~O&vg(&lb%Z9g#v@oc`}l+3_X$j&%}|_^FHJK5Dl9W&&bkU^##es*h_$fnct#*n}=e*@7>C3|WH0xZelzo~Mn{**GBy9qTI93wP7OZK9$6iu! zpu3*XV+2?b%m4>g)f#t;y>lz?gp!e9(1FBXTc)S;H1YMT@=n6Ps+$q)yqsi zK2)*~3>-`s#kY+NVgC-KJaS(QQjl++7eZk?TgBAAj6m69UOPX^aEKqpKfv6! z`wWB#chrvdeE5cl=9h!Yj|!(nCjMCB9Vpwp=h^wOvHx^WK$xtG!cJ&q!6^6JJAU#} zsmEH~xRqx}ec5zCWlm59%{<$z{`R?fV!gwd}Ne>&BJSQ_241Zkn?r*>IH~eqBUa-Q=9^wa_J~2qH6ygC-0&`j_{w}LF`YgX(FX7GtKYpG? z;$AW8ah$Kv;R-n12u4BH`s|im zaXKBe%XF%&n4>x#@UDX%L3_ULlt-`>5@2e>2E7y6Yt)hdbSWD9-2Wk$;ILX6rQZxf zo-|;;L95zeFS!y6zow8hE06)qGs-%1V9dK!`kvGEV3G>L?YTkt?&ashJDA1sW5-LR z`urzt94!VV+pmKmFgHGKrIFffQl5BZeE8^9pCYEWn2n({Q!-V1+?GS>DSy3*d#i8< zHC%5qhn@u+!jC3R2-z%Zt4rk0l&7byKtDOd4o%si1(>>ZF1! zyIb=)H@U!lUR{n-HqZY0EBE!p(%xI^Le#vpfw@*NVjjA$TsU(09b@sFL5Y47Oo_P? zW#As4_$*V)afXb&JS!EgfP(yQj4{6HrZ|l`cOPM23Y85G$*$WWhtT`>@0&p#Q!2^B zuZGDt3_-(^$U1hs*^q^|Uyt*r%nutI;zPtQ-G#Y3t(uRd=sbWYe)w^^ z$@2%ZqHo)UWHdVT9(Vee_Ve~cI(5=(Z~>`7j&&5{PfquHXWy_eziLLVDOugR#+*Zi zh(^i37pD7i%dnZT9W=+7aI12sc33+WpNo*RSI!OE(f$0?iTSoZiNiRb%n}r5I^h^0 zobF`5a^Fyb?Q&Mx*P5|KUj6$ewrlxrN{U3Mq-%_OeMMS3am(g@)q~p^VFlw8_T_KW zC8gyDxph>~!#nwMuNt`k7!W+S;~*e*_N;de>1rqMYztBKV*jS;`iBwi9!{9{@46q4 z3mGx1;%9sDZtx-xFWcOSIau}CPRy^{emUM!;bc`-w0r9*x zVGw)!Mw&-UU)K+B)A8~B6Er>i*ojVKq8LTkLr+$6p|%FdSc#zEuf2mbEEG%q!G?(M z?4J5$26}3?jH*+=eM3Hv)Jqzv{^^Cp)oug^>dXGGx1jJuMZVIA8Hp}chr5%-m}&n8 z=ErNfd0eMZ=7*MDmHM@7^=3=O>`)lgEER!P&k^*hg2I3DJ>#1y5FVnofB$%iTTg>( z3h}THZ8gjb?5EpRt23``0+67DrrhjrZz+tbSf9`3#+?YtKhtjoYWo_e{h%$fea>3k z2@Sjti!NFwe8-_38v0-7jt2Jf2!X_MY*^4JRCJ$qaWPs%rK@E=z98w({K?hzqkbrA z(I3OD^o=d49!@NB>-7gsMmqDzD0%NvR8AeZwwMS|`V=2Z25J={2NTP(5M<+#t`p7t zZ*Mx?)}m~Y@fawK{i!}H#Fw(ST&8VaBAf4epwj3?Wi zmSaY;%yJG(4ylerr%{*0d_s*Te~m=n$_l;Mq9eobFB>MHqQ=lP^u4E@5N@ zbrd==9}#)1pxrImGRsZeE||t)J==O2f(I@EH5}t-K!8Njcp59k*UKnF#5jSgh*Oxh zDqx!2^wf4XuX@;eGLYw}!+EO{X}OD55f^6VOa8`JwO?~_Q63c~P^mws7EThY%vRNv-(_U&2Fo}C%a3mQ`3roMl7 z!upgHC!Qv{8@haROTYQ8NVRU7ds*B-18B2A?^^Y8PupJEb_Uue258D0Kgb$0e(2b{ zpSpuhJsm3f^R2kfC{TSuOJ?qTap8Hn=(Xorf4xV!-Ww~|F)Sa-6)n=MD~>M4n&PukfTe!-Q-A0!M^LD*a=77ESq?cElx~J6 z8R-}sR`pO_{ds#k5B&>CpJ$`r>9OmQ%c$Hr2c+M;cX}j!LF?bN z>W(n;QvrcG$Fl&b>XX@cE+DP%)CF!lMQ(9EVI^br6s?>3*PE(E|1g@x)cW5lghjJ1dWZh>+w2UXXLdx606br&#z`13j|>&KPU^nE&e*8;YEEUt((gnwqn8EgO=Il4LF{+m{ z_8Tglm8iFpwbg}I<4A-%Q0o9*5XXe=k+u0nGQ!lDs37cI6w~j)zVpu>t5|*yy(GF1 zUCqwhSE_oEg3E1n6bz`9^hd`E^+H7c*-rNdPV37$IrADSwGNS1{r~61Nj6(pUS$$T z&qq7$!sdV;r%CnYWZxwxjPD7!F#%bMowZa6r>9{xW+75B~yh` z!h3;APhGT1kM_o46MayhRIpVgHM8bRwW`u~XUPA?&Mfd1Z;4T*gm56)^@sUJwN|D( zmMA>uWVwQ|NcYXW$o!E>+Rb(6Y%*B_6EebvfM&LevB$u+Q~SWEvDseu4&hZPJZLMl z{bBD^rq4a4#W^+uUpKHwWruJl0aEFwA3uM%72h@?^M!P7GBjw+3%-occY)^nu||k% z$l*^ql)`}4TcC}k38?o5?#ETk;sgIF@ouroJsi8X$r8VWT;O)*{gnA9g51gX1@@8; zjs01jvLdwr9E}!t?-HR$W3AH%oYc2R;xY-M<0Qx)Na@hfd$+kV4R@wL&PPTfAe@ei z5A=}4Ge@4Qb090CdNQo4j_ii9=e^(usgp%WzFR!Jv-G;Px5n?FQmfUgV}z;Ne=-oZ z!ERcJEiyi3gY>)K0usQhn+j+VwZj{%hIM<6$c^?#lbHrGnQbZUC2h(G4T; z8odWav^67GE-$dLrWsNiHD8?LJ#5jN!D1Xl)O)-HyjQs}t8N0`FYZTgS{c5WxSd%O zVP|@et_CwI(XZK?=o;%)GmA_8dk*@0(#?B$DymUtzDcj@-gf*O_7SPJ5kcR$bQ=R{ z3|di!O$;voR7Hi-+1rx*lutJSL{=-GrlfQn=g>W1l^ZYX{f_n4;Q`$2a2%B0z>KT~ z*!>#Y$b2^pi5&*cLr491{n>oNEwr%C+w#)`cMMg3{M?zfME%>|9OY(qv%($NKy_}T zSVZ=RzvaT(xrJggBUn;~Q58*eO)t5_TDYtV3#XnS-zEn{O%*~P{!Y<`1G4tXj?~K0 zTi(pQi`1d?IJ(&EWn`Qag&~@iZqsB|%MTYZhhI3ZYGragUE(}x+0WTbx6G+E9gW`w z%$??;onP;oI_*CiG!Z{BKI=)=J4C;VRrXb(_wrep!w%dL6BB1W8feF#OEu{_I*yo! z(t!WlHcv|fjo4Je-$v||R=+gYas#{R`i`_J!VzfMVcKx3zTTvNYTNR%rx*B{T&g8} zojwt={(9yi@p5zvG9(%2J7&@19;E!8}p zBe?tt*6+655bK$?)lJ#|uFvYjL{>DSr*5vn_ef0>-9-l`rE*k$_WyM9HgKRUeNybd zP1!R%h=D25pbA#2>RZ>A8uuxsdRO0Z1npgEW||fow^wTumPPT?kyfWo&~=(=EG@KZ z`~8~F=JNWRd!i@EMy|iq$8p{7`SfB^3?)6j{b4JrSB5&jm{49u{#{?PQ}?-T}^deyA;7t zlNc$AgeD*c5JZshSO05SE5i_K2m17t z#pEKRu#=f~)=U7hjC|csVk+1#)&8e+5f>{rS1o&*OHS#Uq#Hi7$J(oK?zdBzWrM$& z%Wq)I3uY1;aP=wnZx8ZV>(yVCu9goPl+6sK8{)E303o(fDK&6!(YpWh&C0LxIrf~@ zB8%l~>(g-zUH*#CsGW_FUq3cbEX`Iq?i1~Itj&<@ufRVD^jQbprKkDrET(wWmyrJn z4xS}ow+IOyt~N1C>GeUr2fSWB;AOS00pGcQYZtT3+W*6&3S2H3#L$z2?JWxl(bZnwYD#2+#bE}iM;Ppj- zl$%$`Y_;2EB5p)OtDAZ`<6yT3yuxN11}fkzl)MeiDSoneFTzo)KC46CuPvOzdS$#O ze*RCGXgVlk?|ZiT_R2)Tg-oB8_Df!m%@kWQ?w7k*iI~?glW1CqFFn=|g<9wbk6cM~ zagR<3_&z+2?Ppu8cH}v%MM$Gx1c8Q~qbKhaKVo&gAw@eXR~A$Skn$cclw~%gZi$(g zfQY7YO-1oKs@+2Ty0%)W2*R6cqgw#uK`>bBGCl`NV9vha0Q$pf(ZWFp&wLcEujXppuL6TU<>$S}`oL8rf9W^ea3O)QorjsE0i`9;SR-$gTY^jd#-APs6S@t)T{k_#{<(_=rnF5wq zcx6YXt#CNm#|A4Z#uAeIjPaHPw zZ_R_$NgW%Wb#wSHx{0|5 zUKX*S#~54x`VvE`n>s9Hx?M_B{84fkEccT}&znJ?y!Y$P-DEYN80NP=H-D2^TT#!r z=n3_&W^B)g{e0;#4$3QG-G1e8Sp0sHK${-kRdGLKfHaBWS#qz?)p!2nFW{?tGNr)@ ze(Q8aAQ>j&EzZuB&i!nmaRG_u;N$>9NAR8SWv$kdgq`6aEe*g*1Dvs@Lm^y4JcU^^ zdw2qqn~T|)8~L0Ibf|Ht$DS+32R9t7cNehki`-4Wur*?zA?3fhfXWC4-DyLNWjtNi zH4J5$m_-=lc8>%*O?(5}uI7Xfz+6axbBl}wZ&y!#An@5qmNX4UEyBWO8y*Pwn*Du6 zF3kGXB2bw=y*a9`d8+#CD&zoJj)xJblv$T9_~N45B;%=jCGTLE2~G z#R_?h3!2@v88%$Yo-MdNh8G~Kgy~UZfFhuc3~s(aS)1E2^FGRH(ZSW-D;4)XSV&Me zvsFVrL@IP$r9Yr^4Y^996@h+`D=9lEpuCeof1#ahJn?GEN&<$m z|33krR@&^TuQ;a)58FsTSYc2)gt5o89>zqB`rv`R+=D02!U`o)RPV0%XkBYRg2{Tc zedtR<&n8V{CUvZXby33>^VAV_ zo28_y)Vx~3hLwL}h|yWEy(g(C1e`!I>8Q~e)&C_K6@-%&8ZNE%AWR6k-V(1Qw%&hO zK3r?;AN4iqzi$0^JE20*k|t)uu3V2V1p*K9$-z*%#F0>!@j>q+s$A+}Xm(5aQ$?5? z^hu;e>po%sgHUv3PW(9vJQ_33mri8i>5?^CM4+KNg|h4FTCHK+#%6igj<6M5*jKl)+7k_kNSVLW=+4sutwduA4z`$+91QKTh*59JJpwvT&rgZaciOW zlifIk*rp6Ac}iNLLt+|BIvjxNjD1f%SFSo`SXJ1&5>t#nT2WO&s(93g5ykru1ErG4 z$D}NUBC~@H70*H(EC0RwNGbmwgyqOdXaEQ&X3|NqaCf}9Kek2W&G)50iN;ERgI5HW z8=w-trpc=QQ+%q*sXoK$e~0uQ#w=S^o`UW37eF3ux}aV5==2JVd`VsW!i@HZ3yn>Q zi5g!xV;RzBICC})I|N+sSJ++*sE(@Uf9r!mrg1GF(8AP-F-Mo~*%stmWpGUUWocL8 zO)N2O>vfUmWZEmCc{a=*efbgN0D=`S_%FOCkwW<@my<8{@z+J%vBthFWUW>&kInwG zW7z`eBwG52DzXUavS!(_Q@^b@Ynw(jdc;fWdY0e@e$5_iZ?jko%y-N`=w<3w@3*xn zFl*H-CJ-O&HamIO_fwPtyJJeO#Qy7`ZxU{0h)M8vBwASMg$w-zW8`&8m&z&ZgfZS& z?Si0Xn7yrC!S@;9fEj&Q9pG%u7HIZCHylp2t#6gS)5RN8OPX0tZNQKCiV>?nrZW4pX@Yg2Z@e*?YsI$c9hAsuU>S99owrfJ3k=> zj_JeZsOuF@rK8R%|5-A?{F(%QYY;h~Ns-66Au*~>0-95m%&ELgelJrk&b!+TCoc_p z$6Gdi1B*FEJvsYL_WJd}e@U#7#|FwP=c4c@kx7i&^g!4RsIP zNFl{rxG@1lJe%#i;3}CA!XjZs9{pn$6U)P_2wlBjwM`HBz0?dPyU2E8SN|g#g zM0CXK5NFvPJ;DS0+{w~N?_#N=aI^G{F%Mak6egB{k-l*xxeJ-=4$kMejSs5(}|d>9LGg1 zJp4Vyv68;OA$|t0x?OLnfhj#sv>WH_A$DlsG#EkB~-0(QRJdz50s6wa7Y$0$X+b z=n25@&W1EOH|_bw)m>SU4%gD;SC5mM>!n|-H(>UjQJDM@F6tj_CP6Vjek5xxVdFM) ze%)&0SeNHq%F$EA(+!LL5c`ZEfmBNH5o;B7HEo!EHJ~u;SVvQ^Txku^#+|kozcx^- z;2xdue?K&*uA?Ps%H!~*Kdh)n(AWBGkt&~5BczDWJ(s1&HjW{@l`wbCRlmaH4|Z+X z!ac-_x}H$^b(Z_p^~de6*7%MnBmJ|}2twASTV;ny&|I|>-{~A>#)sRUuAFzQAnazw z|L^F26j9jv@z~YLAZt+x(70N7+@mua1#bh50GtMLq*HowtI>2}rtQa4xK!5x;0D=_ zHTl-=tvN~uUscU!4Id-3bZ%Pn&7bmG6z0;5=Nclp=g*7xEgXv@vFt_n`&i3B7TtaPLE(Iwx8=gO z8a=t$fGIG2Xe2&i>g*@ahOqledBG@+FN6L^<=gt@f_9D)L^}v4St1FNDSJXOy^ond zUSVyQ%JMW@-Atq+0jhmrK<8iO&3=uokpwYi?7OeP5pXR)Pcs47o5C?OZd3dF^M%<| z5qX6w7!m1xXQ%US;F-CvDfZhf7xwm7n}SRmQ(t{*9@Q#6pa&~SAw8NI+79_Ep)(-U zyl4bkWeCot*=>Ls>`uTn2T7LrWkw9iDvdbs`bLct?to{E|&7JV@_- z(;*-0pj8qlb^B$C%VFH2Op8Pl^>vu>sjDM&)LL=ejDHmKc27>(@{mtb_ORN~t;co3 zF!k>zQGx$j^i>W~{&wShQ)uHx+A2;fB2ixk26s6+Tnz%-r}@M)5u6~;&p-3zyYXPc)DS&(|L{R&jsR#e{saTZ8_X5k$ox ztW+pnKSlds14h-Q3A&=(4N-u!^V^!H|i znha@22+hF*mZZm4>7xHEi!B|z*#y#1E=;RT&wr{o?E4TOnt=L&J_8FKdRHMsYMhCs zj7N zbHD?T%R+%@=1Z^kM>^DS2m<@;9Z+TJEVn)G-9l{Kx(;jH90ZQ=&eu=+a?jv_O?pvH z%;gBncU5ZzGLOiy&)em{6Fk5%tHhY2UQpS#*2{RV!B&C_ zYx9QKtf7~no=OOfbYrEwzK$+~>HwQ+zm;~E^F;K(w32{k%3sI8s!4bge#tw=_lI?8 z2(ar*D6m>p50>mz%O1ly)$U>VzW>UEMj%mWSPJF^xUV$H=5@AG2`y8zR zC0jB+4+r;%{KFh2bfYNY@K{&=<*2;a*o0H* zUEv|1t^no?K!<0|FODFA^#4~9D&F6Zf$tvy4Q%YKimvI@CGe_}aX z_=Ql{nb^4Hy=)S%JI6E0Oee$rLQck668;_nNrbK)R`{P_@PoUmsjmpjOoMFkM+Ohd+b_K4i?GTL;9crx4*vFd-|0tPRBd* z>vjz{ZmvFWEahtjhjZ_Y-Z?&{x$V@#8z$~aovk(-@rQG7nk>fcOqS@-R79z3_$<*jz-bj(Q{1<+A4S{o5JjvL#xKe6ZVOO|3beJru|x zp|YE`(jxx(S9tW>ObVh-nX>h0@lbBDc4jsimb8{@9LV@;ryN+1s!Q9NMQZZyqDe9&cp! zhZ1VOaECwx$vK8zQ+lP6Q~`r@K|E&!v)Rhi331I(O`tA7pw-}(fT1fwcr2yUygq;9 z1At>_F4|VUQRKHJqX!#svhc(QKxN{>g?Od_e8jv+xgmKKrd|#P-~bZv6}wvGB69Uy zYRG&=_cMU!sK@8ia;Fd3pH$ySlUC%(uKdH7l?ptQn1`Hz+xY(8rtB3rQY^*-<)8Z# zOHG=OOEh70WeY!TummK_gZA#hN)R7V6U8x$OqT^K!hl3Ksm=?E0UD-|ZTrj$mG4B`H>MY}Z%7Mh?jP%S5EPeCm)V7QQSC;> zIA)}@i<8_IF)CEG4~Zht!UvO^nc5t`CPOk0kIfyZgynhpIJZ`w#dt4=C`&6@HIr?J zSnJ|NyOljczdjTXz%K9@cDNtHUo?fAI?q80&XIm&ESY$}%nf!0c}iKi^y2=`pE~~G z3w_gdMdsmaeTek$4uMLC(&ID9S7hzg@mt5WGy<)XFKx0Qwpz!(aS-*lbbv_!zCnh} z$Jz=o%9>&)F9lrur1t;+^#6VcUMlZLtsT+o-a<35#<_IR03Tf~1I Date: Wed, 7 Jul 2021 01:36:46 +0300 Subject: [PATCH 098/102] Change i2cBusState_s.timeout type to timeUs_t for fix i2c errors after 72 min on start FC. --- src/main/drivers/bus_i2c_stm32f30x.c | 2 +- src/main/drivers/bus_i2c_stm32f40x.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/bus_i2c_stm32f30x.c b/src/main/drivers/bus_i2c_stm32f30x.c index d39f74f7bf..915e295480 100644 --- a/src/main/drivers/bus_i2c_stm32f30x.c +++ b/src/main/drivers/bus_i2c_stm32f30x.c @@ -87,7 +87,7 @@ typedef struct i2cBusState_s { I2CDevice device; bool initialized; i2cState_t state; - uint32_t timeout; + timeUs_t timeout; /* Active transfer */ bool allowRawAccess; diff --git a/src/main/drivers/bus_i2c_stm32f40x.c b/src/main/drivers/bus_i2c_stm32f40x.c index 0f4d8b45d8..ae96d65f15 100644 --- a/src/main/drivers/bus_i2c_stm32f40x.c +++ b/src/main/drivers/bus_i2c_stm32f40x.c @@ -121,7 +121,7 @@ typedef struct i2cBusState_s { I2CDevice device; bool initialized; i2cState_t state; - uint32_t timeout; + timeUs_t timeout; /* Active transfer */ bool allowRawAccess; From c73accbfab1929022dbfde76d5d327b9ef95e6c0 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 7 Jul 2021 09:11:39 +0200 Subject: [PATCH 099/102] Docs update --- docs/Settings.md | 2 +- src/main/fc/settings.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 4dbc9dc715..0348ed086c 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -454,7 +454,7 @@ If the remaining battery capacity goes below this threshold the beeper will emit ### beeper_pwm_mode -On some targets allows to disable PWM mode for beeper. Switch from ON to OFF if extarnal beeper sound is weak. Do not switch from OFF to ON without checking if board supports PWM beeper mode +Allows disabling PWM mode for beeper on some targets. Switch from ON to OFF if the external beeper sound is weak. Do not switch from OFF to ON without checking if the board supports PWM beeper mode | Default | Min | Max | | --- | --- | --- | diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 10b5341ae1..b61079d050 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3738,7 +3738,7 @@ groups: field: pwmMode type: bool default_value: OFF - description: "On some targets allows to disable PWM mode for beeper. Switch from ON to OFF if extarnal beeper sound is weak. Do not switch from OFF to ON without checking if board supports PWM beeper mode" + description: "Allows disabling PWM mode for beeper on some targets. Switch from ON to OFF if the external beeper sound is weak. Do not switch from OFF to ON without checking if the board supports PWM beeper mode" - name: PG_POWER_LIMITS_CONFIG type: powerLimitsConfig_t From 6b3fb82c541b5cd06f34b5370f9da9cd13662505 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Wed, 7 Jul 2021 10:26:42 +0100 Subject: [PATCH 100/102] replace WP toggle with discrete commands --- docs/Controls.md | 5 +- docs/assets/images/StickPositions.png | Bin 489411 -> 682099 bytes docs/assets/images/StickPositions.svg | 69 ++++++++++++++++++++------ src/main/fc/rc_controls.c | 7 ++- 4 files changed, 63 insertions(+), 18 deletions(-) diff --git a/docs/Controls.md b/docs/Controls.md index cef8fd3aa1..de5d18b45c 100644 --- a/docs/Controls.md +++ b/docs/Controls.md @@ -34,14 +34,13 @@ The stick positions are combined to activate different functions: | Trim Acc Forwards | HIGH | CENTER | HIGH | CENTER | | Trim Acc Backwards | HIGH | CENTER | LOW | CENTER | | Save current waypoint mission | LOW | CENTER | HIGH | LOW | -| Load/unload current waypoint mission | LOW | CENTER | HIGH | HIGH | +| Load current waypoint mission | LOW | CENTER | HIGH | HIGH | +| Unload waypoint mission | LOW | CENTER | LOW | HIGH | | Save setting | LOW | LOW | LOW | HIGH | | Enter OSD Menu (CMS) | CENTER | LOW | HIGH | CENTER | ![Stick Positions](assets/images/StickPositions.png) -"Load/unload Mission" is a toggle. If no mission is loaded to RAM, the EEPROM mission is loaded; if a mission is in RAM, it is cleared. Successful loading is indicated by the `ACTION_SUCCESS` beep, otherwise the `ACTION_FAIL` beep is played. - ## Yaw control While arming/disarming with sticks, your yaw stick will be moving to extreme values. In order to prevent your craft from trying to yaw during arming/disarming while on the ground, your yaw input will not cause the craft to yaw when the throttle is LOW (i.e. below the `min_check` setting). diff --git a/docs/assets/images/StickPositions.png b/docs/assets/images/StickPositions.png index a08b2c52b3caa1b675d7cb506a814d24fdfca81a..4f7365952d94bd0525b6453a0fa8ca17dc90163b 100644 GIT binary patch literal 682099 zcmeEucRbtQ_kUV#wN-SX)M($Ts`e&UQB}JrY8NH;R$Fw?Vbz{Njo72q7PD$oVux5Y zB4&w51iu&h{;vOj|9xJMN4@0LSI#~6tb5M$p6k;ybw$d{43|M55T(-7$66rJy#x^G zX30h10qD)yD=&fDIf$&9EC}>1f`Vjr9{7C6;;EJz2;_4g1PXi)0ug~nfy*F}2OkKu z0=y3f2+%pF)M`os|8dq_Me#A{=tD$LBk<{x^HY5{5QwVv_}`g!r`%V-LvnW|H3jko z@(WjKK}@+70J%Vr(qq}@UK6WR9w{`#`%PQrtAiEpN}~Tn{qr<_@ax;arq7?Im`vM9 zW>p!bciw)!_}0B@@T0qD>)b?y``v*k1SWbcek6HPn$df5}|*|4T7c0%5asIJNJ&HtjJ(f>K-YK6?OtQ=lBf zr72K=k!)>GT&sKSG+lnQ`L*?f*5H+ngr&Enwh$U#)jG?+963Ha<(AL-Xaa{FDV|QX zz2>?yR7r7kO((;Ap-U$p+0A}O;>f7VY(9AEwb>_fDkIWHXpoALPN7$xvZY{>I`b*1 zM^C?=X3{SouLQS+#1%`e{H8%wX=px_Cm2)|m&kt#r9jbg8Ga*u+#Y3HpUjKVdI)#V z{!GKE`|za?(_en%&YkK6w6@D_P;agIwr&(&Xewi5S=XQ$O}xq8nSCg3cSw>tLlyPi zWnL`%Il91Zq);=F_vT*$W3#@GfmL}^#4@=cKDK_qeeOt^Ic8wBk1 zGUm$30D(3qvVUL2`?K0dA1#%r1_>DW?K_EZycMMM=<0-^#m~?+6Ux`COKF)ao`~#R zjKcXE?#594gt>!K$l;!RUg)TZ^{@0V7@D)!)+%)1f~C*?ElK{`Ksl#Qs*{Wnt@~ z{3s0WZ{>4QD=99b@N>oL+ozL(oBcQiR7l0W696ez3cLKkIUg3v<0-I78{2`GOB}9YxtQf8C z{TL?amK}q4og^MMlVQE%XSUNF(&w>=vZl13FaA=JyLMs~PqphY=MHyAuOsO}7n{Zh zrY^sxcYoAvB$38*(8qzKprRE_61i1mcBAU(>ES`e?aPw_J0CGPvQsJ-sZJ-QR`4$C zj&&*EgVk|j{Kd}kY3kVI&CT-cX$!n!_E0FX7m}DPW%fKxu2*KgI)Ek!JJ`c zgQGoBGGS{8(U`2>%rZ?%GyZWTbsR+>C15K@dCWDg0g)D%+oP-IoT9)z%c5*ebmMUU zupV#~v9fKLYms8o^hH;Bq+$>ISJN)V(I6Y+zo9bls=`Us9E{vSV6Mb4n1j!NsO~{W z3xAgzszJU2kpVZ49Zl+!t>X@34*TKCbt*%UZ0IS=>}dD1wuH;aI+(HENX&z~Ra+~p z$-=dN*}uXO;M#v*59~g5g`GkZbMU)kce-etvr#V^CGt+yrxFD$6@OoBqB$x0AJxuL z_Co`zF@m5wG5%BbC77Gv$47TyGZ@`tsO0#9p27tf2A957QX`Xq{{_(d?}Q4y1a;Zy zVccS(`oE$6Fyxd~Y=>C+c6+k)8Ias$>Jx3%obT4*jp#7$)D2yu9$E2PFKFGL&1&78AR)$aC5;x_-i8T$j)by zbJqM;V0(vAt>3uZ`R#@NG@0oIa`hBRzn9a^{t}f=sAO}WuYc*u-8_jYr8k{&`E2@c zB00&^4U7M@h0rzRKSPg=jfK)3-XnO;MNZXKZcJ2I`M#8QT0S)Vj#=>L%|pQ-nWSzd z)sDt->PaHF(Qb=efACP)bSbe!xS;Z0vI+0$Ac0@xPvxhE)*I`npLQW<{CJ0uuUA(q z7bJH?*j|>*f5`^q93SGijd%BX@Pev7TinQy9dtL+sPX%=a%^!yq|U9BJlkPMWtefD z4=zJSJ<&wyFY#w`r^MMPeFr=0x8QVCk0Me=hYJid6C7R~>K4Ti-CCR)>$nX_jf>o> zyu)_LX%~F$l?qg49?im@rM~UZvxhbWQVqp!qRC%R2z+*`@WQs+9I6J@eLJ;h_IRPu zaLNL)G4mpW3J7(?(d+Pn8ZDm^u9rRtGmZBYV?{DwgeO75t{k)Q zZ`3`1YH1TIY!#F}3{F1dAiubpt+3vFOJ`DLxRMbS>NTi9~=B0y5#V%l0T+ zS%WcIAYkqcGN(Bm(|!LV z9dcz9XIk}p%N(w8;ds_Srt|VNl&+U@T)UMam1!(k7~$DlEX4+5?r_D9t!)^yIO{}d zDd*X1lwfCegtxZU($4f3GA%!l#D55gVKaV)MKHOs@Vq3xKP3pdsC=Ta^yl)}`RH9t zpY_u++?I6hjk7avYTr>G4xw8SKR$;OL`KFrwbF$BsU)`_M@26uk4n!i4MT%3u&fbr zmG;3J$16W@1>SjlVx`YhaI;xvN!vO{ztZRt2EmI z{Qk_60uCAPW=IwRJae9MiQv$&eL}^B{*x68pq740ZKy~@BD2k|4}!jrokt+XFJ2B5 zp^+JrDuq+e(C^LDS(Mln|*}5Zh$;<^@|_xTEYanT?FE(*1vI&)cYLC{)58lGixTAA<~#} z_01%{Fa;@CzI)@ZY20~wS~_Gi#8*m7&!zO)KY^7>Gv^4>gU-~f9ITblYs`&D%8(IyEmFUoDE6mUQSGR6$6ATyswP!T3=uYa1|kPL4*Thq`Q0`ee^&Ad9cKl=6?o?~ zPQ_?tGw8FVeb+GM+2R;!-(OZaALvWTUbxJZX;b`J+pYUuqlhcGUTFC{-)1pgFI(c* zgQ4@H+p&KG$yLl=+*N>_G6xOBU(6<oIl3Ra5r2d@;ROV`sCZ)Ck2ta&J8k?WO$_gsR~oQHAYWiXO)xO> zzUVIr3#@3{*Gu!lX_O^JMyw&-Tk^Wdytw^Pgy`ww9@z2Z#H4{VWuJSbU5|GlR;eC0 zdj;XncD5-Hou`1|HrpMrg|;ALi?{x)tkIV9me0pQZ}R9N7$U6~_jWD)}U} z3@{LOO3?amUnlu#YgR$X!4n^UU#qu~=MZH+ArH6~rI4Tgng!@2LRR0&uflDy&hPx@ zA0s-itNRRsW}fUqM5I#NhJJ^w$39UPh|OTX-_^2SV*h_ehGH$Y2lz}>Xpta(%r{?F=c0uNN_iK`uZ+FYe4ZMww)EHkK_}v#VPQ*t!ID<5p-3xlzjA(V zC*=yr@fFW2cVY_J`#1Z#w|WKnauz?gtam~F&zN*=`Yh@U@Vg&kzK*nWjvzfmK<`rx z^DmP@68eNdA$>|20w3`ee{BTBa+>fpdURR>x|OFwdcFX3>&^pupK*ov5*b|*@EwZB znxe77uv63k1bT3y4`9Svy)Hj5XxhG37NLIh`S9dWPCwbnH?Xv;m z-bc3p$Yv`&cHV`d|3cu^A#q*Wsvh@@;x*}epKPx=fHnSp>DlL#oX2SHHMUjpCjs^d zFtbS};nXXjyAM?K^e0W>H#{6F9^_|Zg#Mb>BaYK(#B&XTw6OTtzwJ~yo{_7lTa-ig zXc@ys5gm&^$EvSHb7Bg|qr4?MwTk6@_((hZ+P3GRY~HbRN-=@t`Y9J4n|(#`+l1ZA z)w+bV`D;gkT7TJk*hh38xtG=XMW8A`DQhg~8bTx?~B;z_hsSjDi6qT+FFaIm$K#IRoE<@Y;`{Az3 zKq9K78K>m8$3a)$GCT=sd5n{ieP9`X@06M2VPyaL>3+=P#rrN~MG@_zyH4w@7DW+N zwaQ0?%_nmWuzf1Fd%(q{qM6gb5UQD2ZrOX|_U+`x$B}2@(G-)ZMG{m@((Zecmppb= z?VtZ-e5mn;MEFC;6OD2=XUJNgMl3nY$;q`~${{ge2AYEBm0aJv%`GTya%+AJ;TCiq zy-M@Uu>`PS&)u~6$2vl=`)`M4{e7tzW#XJyUkr9Wj!pW)QP)KS<5vtO5w@3jV`QMT zNX(gwkLD_;_Nkb`UQd}c)Fl(S%Rh(r!q`3E{KIznLo-C}7?q-4oq+C*ZCSKOu(Rl` z^o$z~(7WX_(w8srKI4NPk_c)!*0L}9LQzI&MFi? zWL(tHNSiM6J^K2NJUrimV@YG7BUfOtk109lWn{tUMPXQ?d>%P9^MvQjuSAQLAwtaY zkFf`_{2#Q&1(v#CoO;ER-)bxfW`KqsCG8b60-}!3)iZmyuyt+2a@S#Eq?-*U9QgwgFmqO&ZmlPj}p0kw3$3i>{*~2fiYn z;{ul5aU6z5BOX^Cl|CifZRLk0SF&Zhi7B>Sj?Ew8F$1gMUpq`z+swxu>~p`%2#Mu3 zgxik`c&kD}gzh;RS2-RK*L=C9McZ%k=zlvNwROX!jSw56=QR19RUFn@!>L>7u2z%* zFaPfOaw?b-Tg51uV17HX=GiwnJ(}A5mx%(2szCS!(y;3REW3acUJcBxUgC~m0cvz7 zw{}C8K2&oP!I{@(c&<%Fmwo&vY^vTnSnFZsYZ%x=E|2Z`%8GvZ5@YEVaX+s}t%uNF zaPP_oo!jApobg=xW$42a5pMt>RL+yEzz#Jue8gn2Dtl-ST|?T`-s_Su)J59-OcvX&^9Ntsuh4XQfJxNea%yKE@eI7dCGl&~)$ z;LtZmGlJlW;5NvLd8k!qR=(0~Kwor08)ok8`9nAJxV_@U+mhU#ovDWAeeKTaI zN=hPlvFcsRn7lT;KC(hKWMni!ed0#WVsFZ~$%gwFEyWyloqX4At1x+ooZw$N>Njcf zgOn86WW`k>pJu+4S?x}WXWTc87e87`lYbuUDr`IbEZO(dqi2Q!HeGU6M}q!|Bfd|t-jo1+PSuhRU929=@*NW0P)q1n1mIVp(W zJwti@&(}vP$}mG@-+g+r6#AULaAe0A)a@ddFTlXD0*Ln=SJ6RA8TA~hZ?$~cRTF5M zWVT}{ZwEXdUlFnQk~&HWocV6`<6|$Csq0+TG;tU^A()04a$q~+59o5OYP+hO7rnjc zpP?*bKUS*c49%so`y>cWEJaSKM1(SAf38{^ycZK<5l?+IfLVz+{G+0piK<-`fe{rx zZQoZnf-&rgEyZ(dKa{Uosc_1@(FM&uj=s-h$XR%fU7;Qv@hyUY8BsZG|HwSjOqROC zK9DuH&lO>MFq(Z-FzB;??E`LyU7NH0$$`L{QTn@>Wj`z>QJc;{V!7_X(bRBl9bL0( z4nDA@`&JS2$s>o0zA?rLXv-Z!T z?er{;^j@=(?Hu@N>aJ+jh;c_5yvq1-?AP5)#>4voFw~VYkDBsNiwZfI$t;$37QD|d zdmMvses@4CAl}H&;m3t;wQA1Tx$gNbX`1_L-)k_8kl*%VQ37_Gxq{50<@1>l577e! zxtN74%ZWPev(>`~OY;5r+9O+}owLREm#-+qEy#G;lEL&qI3(ymHz4xPav_Gx__~gC z@TMcZVq9$irr6lz-b@zf#2M79Y+n-}yVj4hx9e|n+YDqJ0(G@hWN(LopKD?F6&vfF zoMzMbn=6MCRyVE|a7Ld)rC~&vdtA}4Y2}*JEdmBEOp$`BRWT;ld_o+1in=a2C1_M?wug_hQ0(Ow8xsj@&z!% zz%%-F`Yfj0P69Jef&3`}6_!Ft9$v3gOyJ{Pi30HEgL1YB4a&+zI7h49_Y}q#TI|v# z6IS0a9%3F=&Y6D>r1Dg>l-a_tS}VP+@c5hSj~()ifJ8Orfs-Ttaj8YxNZy_dH5QZ#6Wr6=!VthGD9?A~#vzM|S;L4zz8Ad`nXP;QuaHZ|dno6^ggr)C~u z17dd9+ofWT?PV5tJgs;iWwG{}e94L{b-f;r`1LC;(&06dVfuoXLUo1)MnjE<*ijeD z(6+C6jFqoU){m~-tZVNk$^$cg4*}1D?e>!sfmv4+2U?b;zn!Un@Pco?0Nr zuQ3ZKb1dk5x+m9H=KERdw+3M|am(}OI{)3yowHI~OSmXlKQMQi6tg-kZTfguxCgt} zX3g(kM2URZrq#3nL;nvkk1Odl8Xh z@(_6|op|Lm-=j%FnrF=69qY>EB;%58Q*>wyxY7y_gU7R0>{JRkc^_pH5=%-NT9E=G zM(W?sD1Vs>r@67vtGyh_v9MHIae+8Sw$SsjvW*#+XP2RlWLS?2jx%+JVeH>@uPy6Z z6e=zZ?lb3!4DYz|e8XeR{n;eG)mF?dxKcKPZGB>A9XI6JOeW~|`1HoMjXtsW*oUnQ z5ntnSe1(Q~C9qsV-`-bDaR$J%lP40l@HA^;0@gepfQ6=?InBZ40E~ono|GVjCOS8~ zbkr~X>WdrTXb7#xZ@HR&CT8wAKuh4vj&CA~@(ZGJb9T!MOjy!#KSASjiPr`*vYWy* zqb2Lv)Ebw;^~dd5Ph-TYyNUwPLwd>_9y6KXQK~CjEmdC~+I$C%8`BGq=ad4?>C#|+ z?P4^&GJ=4|?^JOgbY0o3vwh%!_E#Xjmvyn+1n;=lXdDpExvm@t@LquGjAQ8X!|=}4 z3!*#2Xb#)$H67^YQoacHCyP4T8ejEN2NNnlQPU^eih-Pyj&Ac3=nvw0TvgI&sq(yX zGrJ>Wz5TuO>+1nDP$7g|>>vGXGjssNZ>6n(J<%k#NXOXLdpPC}gQarHkydoR3|+2A({R9Xbb5aD=?n44tryhuO!6ml^jOwH9^1Ue^sfT`P-y-`Hyh1$6Ka$^k^X6fTP?(i?eL;MlAEw6qEBlH*1E9IM;8ITY4>S7bvF|D>g zle8JJt~sU=GEVkzDK?c{8o(0e^s@S4Uk6&W zThVx+YOEYk^Uc&lU&T&ixa|E#LHMWuHNfaUr{Ht7RvhXWO`OAp0w98g4};`wOtSWx zoAGp*lhamuVpzYfspv#wb9CzZ-TXTPYd;RuDuh|YomDiTc*Mu28Bkq*xmZ-t_?&@3;#(cyv?{Rmt@lu0F4!uuIL~7ZGx76CT4ECw2amuI zA4BKRBXz30_{Q)`?1pLPaI3?G{l>S^E>*Xuk=Fo5%_2?!1(IS)@0M4@5=v%(=!KPA z>{F;MaX z#S|@B!mLm_F|=IF3U|9mv+a15?$OOO)X=dwE2lQ!rM2cr<8mXJ8*m~G5WyzDkB z8dixZ;ho2>*{o+^>=~8T%05M?o#q_#g7MxS0Ae91{?yfuT#RY3^Q@8q*8BU90ifhb z|C5Q=qD<*{=05oCh9Shyp(EU8od&WDtGjFx8|D`AeZ+{X;wxGYPRHc9tNd23!b0n{ z=8zoHMlSk|FaYA*eHCiY!84m*S(<+=#oprbmL+=W+SW&wgNM8Lfh@Ki7zTyU8o6|% zR>}{(lff%kiGBiQf9j991Z7WfpE7`+AVz<29Gg$&(tfW}s*r6!i8tN%yXGlsC~3m! zLK@by4!t&ceZOG^x|DvPwq$1<0}I2+j5Kfzj_6yvaR|hvue2k&G=^ zW7#>qRm#VS{6iVuNrIEofxjx@n8UCJ%$E(fD{BP^0h=D-c@K?C8xGYbtxqiU_Odkj zJdBuz+K!A9r=f%W1C6%vGy5l7g(nHXmpGI~VMMzx7!{>6((e08z*l5&6Rnofn<2UD zF9kDgWpTPuVv+Rzc8;}C3~aU{E-_&jD{=|0$E<$cQz=6^NgbJ;k&*j+V)^k~`cW?< zHpZV?%>Hsl9s_oMJV?yhc;c?Ei;giUc(SO9Z-4RtMr{kb+K}*kNrSBXP?OV3da>S3 zuPj&}?K{%=ZGSq);$-*qWQ}_&AE^uAOdH#-m0romT2)|(B1+l3Y^BH^%E!jrCUbsW z5R$q9vt<#g8i`I@#vBRu+a&2ag<#q~M5<*lNh>D;%$?=WC>?-rzu(ZBMhrX-vbP4i zVHM}bmOh*_6&CtuLc$Z9$8c*Ws!wOl@lQ}6W+u91B6&P)<5|cxczl5DN_789-m>qK zMdOnIq9r#4V05698tsw6Tp=|(<+gLNo5(bmsbTBRcy-ICUDKo_AE)_mNmk%NzsO<* z*alc-^!Z451$26B63alc^dZbzgx!1a@VUf&%P(vE!oh22TBkZusmcN{`3|wkIXWOk zj(2*Ts7_ZsgiTsuj`6WbZ_w$@!__r(&cw&$tPA2omW}#H)k;h_vWGG^Fi9BxH03^1 z#&o-5!F}{Pfl%*IGW`MI6})rtH$_0X^wM;C;32Q5nobQ5!jo=E@?@LI!Bu-j|FCo} z`+U)XnN{CpE)oB;Ey1}z3!VZ%K`l@vd$`wPBxg&QZ~+1^x#ck}=o=xS{RCe%2!+w2 zahQMT`si-*eD~r$j+-JtX_Zi1)2VH`0)a!?KGHV z-F5TC&KJaciRuCAb*PkTT4?v0UD@RCold-8zFC}wXz@@@?tIZGCWXgAWu-_Md^Ahz zrkeKF`R+=Ka|KX#aPm?h$M()%D9lxi7XH?T6L~66(Ps|<8_o!%NoTv1Wvxq8^h6W= zWEdKP-nbb<`M^i<{y2MA>sd?KRB+#<-@Q%Q;+^?z20ehQz^8v3Ev`e{B+=!GyQ-Da zXm~ot%_R{QrkAXC2Y2_VkxT}q>9#f8Tq*50yxtRP_2CM{xt<%9@a~1qkSn3WXcVl|^ao%*r=LOcC+(|sgEN&Zt9;|)1H?O+HA1rul z5V=`dv9U7>o~leu#eXD9sgJ5h9?R;~_zfMBQM;^?b#DAUi#DTT$ecL=2>^aX9etn1 zyG1!B7x}6gItr40Z6{Q+_uNm90gpeiOUo~<0LxydsSQ$U>Cr|D!XA*ejU~37UfiAU z?#s#gildDYK2Cc$@V3PaFLqLn+)}I$5NL&FItVIx@(kfEi<97l50;!#h9^F82g*$C zwHa5Q6n`wKkEi<>gFr&C*CAGN|8teJQF;+Z&?Qe^)DhUc*IFU;A21yqn&L`qR*=M{ z`XBhJ3$1k9iiSm^FgdY=`=9fzz-puU6!XCsT9aw~wj5Gs?_axn4_6Z~S2n7S+)f5e zzQ?r6mbY%tI(S-;(P?e}=C3=LN(@~4neu^ad~>kO_Qo%10w<>=6VJl#RPBiZ|7B}P z@FxHjD{hk-M(#(1!ux-)sejkMy?2M%%ep!(6Ds!WM-p0;Kq7TWKS`@@SZ)g22NZQ7 zAo`poV#GbEn1<_Nh{XOEjOuLk8@yLTqRJR}8tdS)`c4KS4C8T5^j{0NOA}lOw>VUH zUWF4T=+19sqb+ARf`zVlPmT>GgE7$DSwCKlB|p#4yT=Dj?qsx`lRieLTQp~r3!OGJ zfKB~q?>UF?_C)Dx@nWMkE`h9%+wxV%Z)n}nxFDjcY~*;vprjTc5J*S&AWjBa%%vX- zhOP|Fw$|anUNL(O*slG``?oE8eaa$@Qm>3_q+BVC?A)a)FG~bd%+Bo@DLse1%=dE7 z-F=}yxi@Iw6`xfjWjrmanV8*w^j(6HGUONp(4lW}>N=mI~^Gs`& zdm={K?apbNM%NiTNng{>HmDiQrdaHz^O%LENw|BB#&Kig>eeEn#~e&N(r9beMLZS2 z-YY}7nluYj zn1}Q+k1rg)>lO7h+L%sKuewyo!%_RH?TXKg0K=;aRQHM!O=VU2B z1LxRJSNY0a0+k_i1U`$;M)fUj3kWB(*N^b9g7`KO`@xxsp7L}zPdhbucIh}%2@R%Yd!sJLp!r{;IX z^GAzy>RMvE`@XPi3@9se#8$f>P7?Z9;LO{rNA%(pv+|YwW@Jd43+Z2lob{?WjJ7_& zwmfSZk$Pq7YZId+yt=tNvrc+X(2**dv}6h`npjn$7T?ybq>1PF5$V{xnE`s-jNA zW?H*$i9rQXgQ0TIiI`bz5|`~5{ZrV@^bo=ybXmuy7^wc;cY9>|>gaLnuF`RX*;vFt zS+)JBE|+$#JEq%nR&C;&B{n!nWzqq5D8ngWK_SL-v?vR_gmx{ z{FXT(u^6x4$C5HNVEM$Vo%g!e%Oa%SE9=+3`}J|xXdX`bTK%E6ux|{2V&S(*FQUS@ z*Ni8tx}W9vqwETuCN1j^iR@aV;kOYTW;D%p9!?_8v@Pwkol&_xYN|{0fd=APzOsFO zT^=fA7Ws{^zBixB*Gwkhk#v`SBuSHv(7yHUrqhFOOABFOro(k) z?}%)t|ItqNSl8gJ2zg4wJ(QXQs*9+jpp*Bfr}FL=DkU^^qADMfEc7@d?QsN3w1el< zWi9&Tqlc6Sr3vh?HTQfiHW-hq)>08^PNnO+kuo zV^N1b`StpXAF_S}$xgb8i+xE5f%Lg7L!`uJq=VTYnR*$e0y|i2U72S1yA$1hS6Rwb zEsTUgomVHH9(8Fr7(;`dlO1ey!_=Ab4HaM6jBOI8WUd&_Izo^M9afu%BMOcb&y)gZCIW&GU;WKKfeg(Ggr#ZyFWm z21^OhK+mB3Gl}3a#gZY;WN0zw)!X^1i@OMUpI3&{lh)wg!0(YCq;YV}tJ&;KCMpT2 zW}n2Oy$}9Ej_Kj!(Ez{IW_=A^KE$h0;`H5O6t9(FQe-)rXC zoM{QeTe=G2rPGquD81X;Lh>7`-2V87bNc^zO?o+wmNk~ExhVb-XSlR^K9N|Qiq_VZ zh{@a_WgElR*{VtWQ#muKQX}mlQdN%Q-NWa}Xnf5H`6hiMb%%x;an5_%-u7|Q&_XZ% zFF)TBzInq2|DYe3(;n zZL!b8AZh0pLkV5t5K2=?740c18PhB4=U!#W+V$c|JwjG22Ev@W^gyy32JKtJx`%{c z5#@#b`Xx&;o!BUOAL-5c*o;cq_wBRf2i~g`yyxoEDBnJD#jAyzYR{HSy<-6H(YfU% z{3IJGfmSI!cs-$ByKlM0lZ0Rw8&AIQ%bfJ6yS1VbMQE;=Ywq&@_AM=QFw4_8=Fxb4|n6z6&La}IIs3*xaNoZyPUJ_TK}MCHehX#)hZmSi)zm9u)6p|>$HLCK`!Cu z3(sQvo$X!Gg(-~!Dq|!{(`K*$Qvafre2(4G6+cZ6HJ-Tn@Kf7*7~(E4+C#9GOc z)0}I!4Tc=-rYj#>f;}7ebjw69bQ7^8?tN`kW6jTD$)cs6{QD8iVkR5<7unN3W#pgx zGgjrTH|%zmWYsN2m2qt-6}GxVgZo*8kSUc)d??B9cC_T7Rx+6v&D3zMz2Pd0P?}I6 zl(DvZ#d=;p#L07nEbqrsG8lYO=J3OHO(I!jOnta-R)E;|8<1VE$ z&$iJ~r!wX76l-&lRRVe~Xv!Ac5AyK5E}01qax^pFtD`b~HeYpqO>%FL-KlYURN6Nd zGc56~Wb3hwb&p<2-75R}z1*}m_SGb$mGEn6^DX{X#-SxYpTTW5Hgp+koI*gV6ywi3 z!8A;G)t^fh!{W2(=czcQ)2+^^-`B<^oI}kqbMMd#f6qVX4%@mHk^D9nqiH+g3k}?V zJ^kaJF*U6Omn`k5{gf|ScX!y!ZaXR`#20)I5QyA`(@IJYfXcJX&V)m4vv6Am>$S+e znbdRS&EwK(Yh^4di$~lgn0tra^d>w49P9OBA}f(>qjf3pp5GB=SEj`^;T%5R6|jt;hBSu0$<^~-#zAH)1m%-O}w^W83~03o)!`N$=ANQEM$ z&C_T<4=F8y=^R=ZHD(c8HoU~?RP2705!aEQJgIhL*msRveU6U$m*?fUer5c#EtbXV zI_b|VRr#O9yzFKqMzaGRUhe*b9@09~k7KDokAsV0jS5V-O_sjh!fmxi zhq+(one7)++%cEP$}h?*h6}nY%T1mc-&Gsc<%d}ZUKTGDrT52CgflSSxy80CIeSlX zu@i@=w?7~Ab+~kmw{C+z2RV5GmGw2qs!|Zf{UtcYJ!0pDTRhgumEwq4D7G7Y(`(Xn@~dK1vVdN;2=v3o_E&cOM?b#m&{kZs&bNh5E*qoQDWhea z{YI12O?tdW?J=*PQm2UkjXu-lWyse#7)i3lQjc)(z7=NlhAMklQ+<7hl6!0rnX3;> z_N!hMwfi{Lvz#;o=Ez{(7c=JVOid}I%tq>0dfB;E4KceY)I&6t=HfFa_E>d#W@AiQ ze|V79{K#(fMqbEwHe9Tyo{lJ&6V0zzo`;&c%znjAWnbM~2Xv6q)W7MRdPbd|79_=S zQ3;J+i%Rd>_O}<(%{U6zYVc=SlS4_O z7~5CJ4fc#uE-5v3hEm;d2_;6qydOxQwhjaJkYvc4H8psO))cSnuNw$sp78GT5oQqU zO8^eB=sOX0e$y~>0d|&g7HyiHEpFdoJQts`^=4mMg7%?b!?s#U<%f{xEL^ee zXu-^9f#t@C4%vk+78ZJO)+5`xdi_9F$s^czSH53q{r5V{=_?jvFOmvhe8dQNV7Mm} zfn9-*5Bx}EfYyomdR5ZWa(+j=-17FRso{bMQllCR8&$8!&v$Q=A5ttxF={dIt`KGt zGa!&yt$fs2Q-OPi3?WU?yDn~UDS@wS_fN7^a>b00SxGW}bVY{k?gq5%psV(`FwDA1 zKyrm7%zhze72JmH^-k}`)G?B#7WN$i-BC|-G8|LB-zyFGK2#3aQ`-8pA}Q5~aX-V( zoXE3Qo6sP_nqm3ohNo8|@uMlzxhli^g|n}DHrx!Q&5m+Gt82VeVLsahs%QG+JkS(e0JQq?%q*fkK~Nw9g=ruUaUFZXeCN_C^-W3lOD`G0L~6p|AAnNnQc^ zsm^5UUtfwxiB(7Kd=wMf7^*bsNq`2E&de^5A@nV~ZVYzReIO6Wl;yy6DF&k){iF)+VvNM==ug@Z(Gme9jRKoFfyDvrANzwtn2>;vwW$+4)W_6hMrg-#4f31i zn|7^_;4hVyv~3Vn`h1X5n$EVBLZxzmfFknvPyyfR;lCFTULrlsTtUX$^T%+K3F-U? z)5s@_sYa~@N`goKI6l4G-`_=ufB&ZH%AeKibC+hdn-9GtWpC1M7j06dl98oe3zCY? z-}Za|X8Jwl)I!OKKPWG&uSl ziW{FXBzadC%H6zpz2?66U=+{|W`ezQ*$^>U{yXOi%?H}l;em1+WbAeucLY&J<(9Jl zV`8UJYt@t#fV;T#XAON&^LOPDLzXAu`(Jr9mXobOy=Qn)U*Zt;29byqA{=npK>d?N zs!91|(Joe$CY0m0zbIM)Qy%yfkZ=1V^l3d?`KWzW>;0-c zEyRUAsvmI4lbEDc4|nIIa)T^{QX}}BpNz@py3-*Oeg0YMUN=pyT~6%EUZ;}4AEzsFx_l34~7vDPQ?X`<&!_86&U zlnp!FBI0aXdJ_}|J0gf)Vr#yh%B*xp88|ChelGBnwNyVpc{Tdgwbg^uI zwd)$0R=8>HYrj*Q2Uf1IGHSMR>Zjz<3z;wz%M>r|U#{)l&4dNb}UrAeaC z;Euo@mmTO}N3Lg@D6Ej*BKebN$V2{;ZzoeCtqkZk1C8OA1K2L_4;K)m>F~>(Qg!to zu`BVg6PoW8Ymn7!HP60$CNz|~$&N-gG}?{G~G zXUA8prXV)7HFB=B-s^o5r#9#bETT!CuUxVZmfu*)J+bM1RU5U~IPy>f)*dkKk??Sm3MxeXuazyipvnd_S;EfEYglr%r+E zt>Gj&pcvx-`a17o+!mF$T8R;WjH!=XEGSPAzmIC`(NAcO@Us(QS;$fzx&(5qW4oA3 z_;;6lAd<{lzpD$ohp-XE*hhWeJkBGe(Dp^x_wO5iH!Qt+!)qx7%hxm5AxUq_M#XUv zp2g-H*S#)!fyBzzium0R^W!mhVuMSwH(o>kSu%nng)J0l!=ik;y+cIsr^%j z;$U zFKw|KmSAn_QOSjLQ8EYAZn@Ti?P$KXU=Bw3E;nxq-32ru81r0B+_U|ni+$P~Gi})N zFBLF5O8du-YikFShPRYCI)^P;`fyRnY;ch`=*@V$-X9;>=HOE^ilUTES1)PLn!UcV z55gix=?4~QK^K#V7k>_^&uKQ+@TyMOp&U3urMUo&-bpBpy$#H^5I7hhEzmcd%OPJF zL5CRFsf`7?wEQ?jx{2j1qC2K`|AeS`^OkyRS;Fo=JTIn}v|iu#L3V95(r>mT$!{4# zMR`y3yv(4BNJ|S*@BJI6_XFkP=gED*B=TpV;Xd9jLFU0n2jkc zT|TOvRBPBxxaj{05i~4Bsd}@80H2>?rcNl^ty5fC$`2UTQwb7{`YI2dbr|`>+M2uC z7s*6vr6h0Bu+EYxP97+?iW`bKIAwmo<($gw`7P@pcQ-6kJ)Q)Y6%D> zCj7?N?5FiJy*{HxdU5;*1y0W_to{IwphQVi_~%(<7DbE}+4~Fwp*CQW^>X(?h3PPr zRBgvx!^KzlY=?O^%>|Q9o3OR-_)@~7GV#uGHIjN}?Mx_@Tyo@U$ZgMohWMHOD+Dn;ufmlPjM{>Z5he^*1#Q z4y#eTD#W?zT^Yb0!nuTExAC$-ESt+JP{ypvE&d!X>6(L=47thiRF@miSY+MxWs&{G zHQI`zy>GnMoexY0bh2;oGSlNOc7BWJC#e%IbgvKSbhs+A?Ol-TMDNG7A8^#s0b1OX z8=_mdF&o|0=f6BE73$6yyYn@FFY4%%q*LRWnTBbS2I~$Jmd$=GTE(F0ra)Kdrdw;X z_O^6ALMv65H%#KC4=mEYpwvujni(!Ae6L~Zl8trHc{AOlj~BmSRnjgr2uAz&{Bb*@ zu^m}xrnSi8M*Obs_4~GdqU*+DgXLy*sZv&-Ri*+OZ!_b2KFFuBj(KWVo9U$T-y}b| zm0okJ!)*<#q(smI#h!{NGDH_>^?IH9pzsiJnEh;3P2UK#|CQ~hN(Ol9_cVj)mcz1; zzsIEX{gv&WL-wdGkNsPs2Oa;YtxTcbM;;t--WAG@-B7z9uI7)B|0*ygW8^imW57C; zQ&v{z+7hPN+Gpn#nFu-xwmmCOS1mmO`VXC1)^3e2r=;xzdVo|6Xn-nr`7nj}57x zT_k;R8~QB8*#11o^qj9535k?%I(mL!7N8GbeVxX!I9hviJ>R5)x7=XzXOyGg}KoKhd2s_QR@5TEL{P?o;*c_q9`3 zCV|T-WB&juPHiBzHfCj4%=pZaFH>WO!qY6=GC-wnXmg2x)LEhhi9>N8y{5}U+W?!p&x{3ygUXe9VsyE z`%U09D@I!>A6wv5Il^9wpT&}@n(6x+HBsO#Z}`~!L_(fVRg-Ei>{t_AJB4;W+@Rfp zJf^%W3*|H-{M0Xv023p`|*-p|~pMN1LE3YgQ$3=Q}_-;$ZN zU9ANx78%3*z#5jEFCm(#&(s93E21$dWQAiY1^r}YQqVHUA5io2B|lbZv_>FrAqHlHc{c7b@}j zgF$Ww7}NF?%MCkW`s5pZBEIkKl7e}$EQd8r+h?_H8PV8wM+b-W@2r6z+hK^=JEi^` z=QF#LUKye-Z5xvlkOhs22Dlo>>hl7S^J(9n6x3QA3&3wsKiU3kB zD9NVBiRHygyGL7ASg!}v4P7vxd8+3=H`F0C9b$v|>2|OqyMUm|k?;l2D;WZpfXqY& z>geZqLA@M{4~cDWX+-~{*p||0q?p+?if8lXxI=AX?kOE6`>c=NpO{!$eqZ?4P&cRm zS_kg{e>&yep5|z4t~!a!5kkcr+It*3WWB95u>RzRmuXCN?Tuf?d7HGzOi1ZF5Jf5N zB;qLW%geR_J3-9_VSf3U_DSr)=xEkiqe%zERutMncEOfc(jX#m3a3s{>IeetR_cBa zT64K3Z&kIM`Ih@#XNWxB<^6TLjV}kG!MC`}tD!v}#~ua9oB_d`(c09EoccivGDr95 z{>mLJm@=vnV9ESX`qjN#<@~n|CznHUJ$C8d`V~G=49u3NZdgyDurAVjShHQ3j0c-Y zum0#syp1Lh<>cOclfl@)1g_xK>78$?Qr#4t39Y<@K9LafVT$z5tVHVh5b=vf?=lZX zZmAa>;qK16P`j=%s!n?8c$uMxQP~mMGi!Y`5V$?3i?~2d$yaH{ZpE_!fk}39=LO(E ziVQRjfv|0(&lYC&r}Ipj63@1_#W!d#j43ZW{lw*57-z?L_Qrc!y*gvx#T0mt&=2=j z+I%FRkjGCU(t%ww*Hq-H0d*5i>H+sHVd1z2fr|~axTBlli9hA3Pb9zLDvF2%^4$5% zlK}=diB+3(nlk(C)Q{Aqn|Cgs)rC8qs29sL5N4&j;GF*W z=?2ZbanWTb3t&RC1>>^|2S9cF#Rc+}MCK&AtFI652$nfhpypezsjgt^Cr<>=GgWiS zXl}hcKS~-~JE!r}1hBu)J@+G`+dpUR?v?}@bMEHxNXd1}Qt_W(I*+NorDOHI{5duW z)#NQ%LJ_<^J@WaA-ByjuJg)hU188UeaK(lrs(ImrAC+gl)n2?Lq-rB;1a@p#>MNSV zETg^kO6SkA<6nG|*$>WpKWYs}jB;LN<;$G)0*KOBYBn5!uGhG*ey}waVuNLJRjWv^ zs^r7b?vEj>=+9Dv_}1&=%FC<3T%REQENFiye{L--)IL0w{@BD%$T@Sy!^f5(TeoUeY^wRRi2}0;R1;8)(`%m0y}p0#!x!eSYp&9l) zjMAqkYkj$T+vv%#jNS*&U%-zvP~B>G7VZL3!}c+_s~KqT_g=q+{u|zO&&@RgI(+q9 zt>f6z3ziFoj0twx!MJv9K^e56$g;eEKNNxts>a(=I?oZ%UYR--y>fwU{;Y2Yy^JG0 zdOxn(e29ox27NSZeukY5dh3*x2cM$F$T_ptFaMB(&iLeC793b= ziUn0pzT~E1T@aYLn#Y`o_E-Oz>QzY%(&Qx6_oFGR)H}v!WsZAxh%H>9d9D_W46Xe!$5=FUn+jGM-E3gu8VV8?NAQ zN9^+IP}~swr%EcSd#)lc(m-Z@#;zWW9CEUw5i2 zQz)`4cMI$eXiD?&Jate6wa>C*_st3qvo}+3%#ybwDtt<)Kiyn=$JbyByoS8Gi%E<3 z)G&C!jIT|-#EeXcEuT-ZVaKroC!SAEX`vBRZ9-A7EqBmGc$Y`w_dxQvdwB4hUy~un zf2thj=s()*rE-p>s>)9yl&^T)##EFTixC6X1_*UdkG$7=8s|EC?2jJ|8?gAiN>+YX zK4cdkYYljuqK1k(0LwYEJM{Z1*=Qp*OTv)$&8G21X|p1|9-clym}j#mjkyqb)TSNr zXa7ih+?P=;0l;qPw+%1b@7S58Y41JCNFRL1tL0Pb(mJpMon)|qUU-Biagnm6z*tla z>bt1lhpKNfy#T`N7LT)Mk_lCI@v|+%(w&F#^p-=+8);VUiloWLCVYq~tGMetCEP?7 z^*7G;Y3T3?DrHbyj%v2ArxD!=665Dj`;&FK9?B?8m6tBwU2OJbOTN*A+F|~g<3D*y z2p(XSb%N-dK!?r7Y9+ysRj0Q38(lAsEd73-tXtep+)Wr@-g9|KXL|wbS*_B1%E0)j zO?G+8b-hNFCdAyQ{#It;Oz4)_paQJbo17f~V)Zsyn#^r7c%`V^vhlX6wcg>9bLS0u zb1Y?lSEZr)tF%%(bg{YPZ-pOAR&l6^>Z|-CZOPCjPFMgv=R1i!4mECu^qULnQ~!73 zXr0*A#${Q)RVkxOi_v>JPywZ#Qa#u4$*7&4`0Ovo_m|9V$!z01OgKI_rwbTX~!a zcrN4qoeYsP14b3`FmZ%rz*tnz8Yy*04%tI)Gp_I|#0b$ONIAo*4#Ch)Sdw=rWJ{{ZfP)6FMZ6f?iaCE>)PYHmW_gk zJL|8#o}&`^%{R2}$_Lt~hIe#v;!J~=`!Npw+yw2wu!N*}X>?qkehC)Ht2gNv`=f8bDwa9h$*MGySdFdx!&$QKD=dXs3 za$1#gwO&?G7xI)E{&tSPWGkMmT`5c_9#FZ zDk?U3Xtg6rs_%Nsc$C|N49%$26qn~ceMuOuUAp*k6`uI?w*r)F=I|4RnBZSmxvS%< z-})TSvY+GrN>22!ZIytNP(60tBSNd?PsC+XqVro5@!9?LI zBhU5mVA_W7lp7cu8!WO`7q%7-6^qK!M2nXoE+W{qk)L!EL2m+3y7HnyfVlrDqxDAK zanPZ)Pb%L{-d9u60g&!{Dn$6zj3ane>QUND(-`lN?Fuetmmr_tC#N*&h3iM>{>>)7 z6S8@QaQ*LD*9;?A8sS12B;C&}Yy@?GlwF$){gG9@To>_LZ_REMF_Li9HQd^LV}@hp zCrPT~Xg~+l$X|-eOo>sQxjA+r@ht%t?LnLm-E^v$GsYEZ$KK*OeV-^w-qablygf=< zbTmD>5h1{k!es6l=?8m%Zc<*xn@5Jm-Hcvq zlrRajj+Wgj|KwR+wrq`4ozm3uaGYg-)ZV7GNIEWeu~q(R>?LX?sC!g(n%ue@^!0N6 zx(V6w9V5&J8=d=SId@tfL*Z@nYgJNRV~OX$Uc-apGSm2$Iv=~iFkK>p-Ih#7b2N30 z;Ho&VKXtFnSGP??fA6{e(x!NqX*Y=Avg3-i^z|qHiIgJKJBT@y{N6JZ1r3zRAJox# z+dG+a4;~ZT(p>O0+eM7WdY=>fHd4!)cjx}DD-C!^#{@Zi6Hp^FwM$jsE3MOEIT0Ds zRmtAQn`Zl|VE?j7{T5;Hy{h6y7J-fH0QIGdslrwJn^ykSSa*QK3UFed#%g~Iax#*Wm}z*Z6M7#>WBZ9JSg# z>u2GH!5w`~B^eE15vRIJoCkl^(6~J_o@t!WFLd6nTF6Tnsj1E+zvR4_Nk=wZn-OXM z=9y-)B&isX*Xh{Uj}+>vbdf{N`m+YU_gNh}vA5u8o_TNh7Aw>_uY?GV7f>)I<1`L& z_pj@CgmaVlVm9w{&&hfd2ki@L%f$Bu&~zDEYN%rNmaVS6N0GQk^r0)OnlX4T zNs3aT#tV@d0@Ss9k?CmDykBe;_M{o8l-jv!hty$vY}qMMnZMw@yDu_+NN{~zU^y$^ z3BoBDYYW@fp8Vq+ud{8*BSVflq<+2km&Qo1NLB_?&es(;SY}SSfCU2u9Re=rj7!PU zGV1~=&y%r8+g)4CdyS~Qz7XDXES4G5(P?VW)Bn-vNepytKg-`^h+QnxHjI3oYo{_T z1LqEKlJjVa{2k+08?!4AX0f&)Lwl-hx0oAZhSDlr?kX4=1*~hZCgE(6nfFZw(m6mG ziSm2XvRE5Djm58AlWykOO9KH45(O(;OY^=>PuAQl?nj1sBM*$S8sHw=TN&PL5UX6v z7)<#BVg_4fBD6*#VX=&L{ixL9MgeDooOr@_yzF-@PfPdR$DVsA{cyh#f1HzZtn2vl zhUS8xt!QwZPNBCg$ZeFH*#qVS(JxhGbB)W$!QO?cCK8PfE(j}<>slyqBan~tHas~8 z0A{`=>yzy!$EF_;fQ(ZgI&;~yhfc;_{KftD7kT@jzqar&FE@-15cEUHKcJ(>Wx&cuc>Zvs z;m3ISE(H&jGX06jm@}ig6rPh!eZYfy?6!fjT(?N*&ZeHOEtQ(Yp5v|Rca9Gk(a}C3 zQMr_aKPwv<2ChI0B6driSj`C0E*cVa_piLuU4)KHgHol-w=`FxrfQUc z4@~^K|JwZBVxXk>?jYcFbwxGE?63b8h{6-xhGiunGIQX#1aH@c#Sh{VHk3Gd*a?T# zTukb36HR8CdZ_C7oz-xY!E6P&#}xEY1A=8ufC=bD!8s#@DvUO+c|TsIt(%a6eQ-vo z-G6)y?99F0V&(`hXrO*Lh(Q}v))@k+!{5cC0@;61-(d{#fMR3sBuKvmO<*f?gpp&V zXQ)h2z+Nq^v)!0@!yL=yNwe;X4B~sl{*l9Y2rO8ed{$`c@@HgUqQRWZ3_AC8d(aR| zVRDSg4Q>Y|Mw1Zc#hZn}S_uzF9jg=Rsy zKxnJXMVin_N!= zn*_$J()k8-V2n_SX>Wn*@O97cxYU&d;vS`wd zM);`-(#q*$pP0z8U|*eG4zh9V$5=cT1UlC57@w$>{wLql);m@y=uM^jR>E4t&*Q&0 z^ykE)0lUc*d)P3v%B4|m@TY{5*fn6+APRhH;9*FKTH1kE8?eU3$C;ybK1M+p5Aqy6z{_TaIXL2v{dTd+cCJplO z$Y}0f%>T|w@%5}ze_)SsbEAk*#Fl|}g07WVYNoaJa4ju@&qP=H*#qNjlGnmcE%oL* zI%PNbVou79)nd!6#oK*F0qi5r<=XOMdqu9CdBi8vWV|-U;f^uNo4YXf-G#gcEXE_edSG(@}cQIM*3vx*tTbT$H1?bIxw`elquB!#zpa zz65`TxYXAmtel5lkNgofCIwc2_O(LomE47adfMBa$Strr5OK==m?Nwze$tGprn??E z4(wB@UCljQo6i&re&vUw?MuPaO@b|e#MCRQ6L-7&a(1;BhuorRVpOmX*MiL=f1RPi z;yMsNogg&Bzzm{U@$(rYRJzz3$4vucquXF&X9$)-jD8}|l`;xr`F8ls7%>$bzG02R znX0&+*)`yi)Vgg!js>P)`zNZwVaLOa^>vM*F!yHkh zRqxE1)qj$pv*jgxzUtw8brk6|;k)7GF{BMh_CKU`QNAptG+IS@-A=mYq(A#I(O{Au zv|zHeP$$lpf2Hd#Ve%zYFI&hQ*V-^5gtm#x(j>#g!RD+yprDicY3zoO_rl?W$m~ZH z>&sJcO#(-NaeSD;?(tU4;mVJ{8JDEktiamZzD|LgNz8i<1s25*sVi04-@dc}4iw`m zS$Nb>^cG))t(5={bXGyl8{BU2fEEcz^=OJNVby2eKJVb4AA^x@^T&dc zk(o>KF?f50&^D*J1;Xxmf#y(P&TJ^iQ;rzi4Z?y+N>+##(=3eOo@n zH>kfp9OEC^37jZi4e(^W(> zyDGWYGOm$sp^-*MGvn@UnGE#;Wy$rQV^T>-(IN$_xBXW61(@8kTVO{h>fsIcNfaCK zAIP%2!P4CzUH#n?=Z0K*Di?O0x}gbcH6_kFg-G0UvkAbm0LsBJ#gX$Lqcr23eU{Y{ zsRkXF>@D@t7*trlWJb7|Z4c8WmdyT^9%=|h`t{lf&h0<*22eInlujW zfY10>lEJ8{@^r`w-*B?bp?d|jn@8>qYTg;5pquLoNghU)2-ICl*Et{R25Yq6jPb*o zC!T4W3!=U`>fsR{)Soy-v?2hm=n+RrJSj_4`EOV1kFAZMptH~fYsohmvh(}kW^Z=U zNh8lMfFdwi?t@dIz#XgL^?J1Ot;sb(vkv0`+JZ^SIl=t0{Zc>`7qelFAswTIVR!;< zjqyn8GxM&>xcn9FG&|{ntDW(DJr}rw=dkl8P0-BcDb|pctswe;mISdHvPVKfAo+AR z%<>G|RqpMDaRWi1AY-QNY&fV}dYJZoxBptiU0JDh<3mNayALg{W&sl*i? z4H6^5@3`!~EehT-iz)+?T9@Z5t(rHzAGS!O=j=Se354D-+mDR=aWZ(zNDaHk8c4?! zCNC)Js)KdR`5^q@=w5oDc00c5WQUBF!0x@-jUoByaO z{M{;gd>>&`Kow~TRTA92z(iADe_O8ap(&=b>!PeLasW*IKTP9$wNwHJ170vZz?d=D zZqL;IG-n8TV@pL?69i7TTV2zQd;7uKIcOa&H2__c`&lVthBo0PKUsV@Bfm~j6ukE; z%@s4I#YpDZ=USNXFh%)+xF_1)2mI^D#FG9;%#WvXy$?zHL@!0#^R+zf4?=EvT9tuk zC*H4Akz0R!hlc0(^Oh3&k%G$HQzAi#(L#l=W}!3Vc{FkAs%D!~?@kzAb&I;c0N?HC zA@Je?^;cs*k&1(UMuJE@M_D|=;j@$Ic?joIYKtfH9TDD9!N&gmSag1IFVTjSdpN^r z^?#ErpxWMS537`wlKIUaD*&$Q!##t>C$>9s(lJF2R7Rmx$q%PDZ5=!1APLAH01Stc z$f+fwy}Pkt-b)}7y0AhZWi$PA+J;v5=>rIr7%2on`7GJku+iUS(Ets*xFGO7(xGtJ zoYB^Q`rBw+(BpfS*eu?H!grZaqP#zWSB{DNS5yd0F!o)#Uzy%o4-#)}=vF5g46RBw zae;l;#im5Nfcrk$(zMc3o-r5eQWAHsCB6kJ*_gua&Z;6=WGf_Y8F7{Eg73SCYEzsz3rLZrHBFHyxSmtd_U^5uE2js@H?A#%Q|mXBY@~{ z^w0d*{To1Ln+3AwxqIt%nCw&np)TwzXY5r`rRIWj^6IP6z#a)#kMplAsl(vs$g`6K zo*DZ)OV2h|o5UOpN2kBU=wkF^%r?{;mi)mZXUKW-LjB)c-V@O`+>Z?dRBXK&r2+j5 zA3S+AF{d@2PuDwQ=SP8UXrD{+@hvb$4e<0CIXrEF**j9n9lUFNN&i#B?x7#w)W6R= zi;LL?lX4t$ItuK4=mzf_Rn6mpIIaCSq)O#))c{`b#XZ%pUc;M^lY?``8`L^%ywVlb zX-Ps81n%%C@2F??uoHB)v8;0EN(!OG4Gq!>yya_{-bA``RPCNM$ULCR`u_AE#e3 zOtb067V0v2qoH60hND;VP2ALmEE4oosZu%!(Jfx8dn~8|Kfx)B;fZmAzZ}msS*s&DF@fs}K{fCv*#))|?P5 zz@&uvC`eEF66^7Fs_n3BDAqPI!#qd?aZc3Y`N#~~j%BatK zp10Y5SfUrm`1oz0kI^r|QMA!Wf#h~*{@CirL#n&Q`>ddUUu?t3%o@z(YT?!oK2Qgl zt4cQL^+U5Q#_H84SGhN5z(aHGiXWXEF1k_iq;UY<@agqKEkTASGUpn0wdO81Ej-4gleRi+SSv=&*O8wje&Iu3e*VPdn^*|l4#{H}o1x!1BAKu7}6 z!~uSv(xPFM#y=%YmDzOX<1l1b~1fxX3F!9`FrP>wc%?R|**XY6)H;H;ywO_{qA z|6~(*GXDQ`jG)g4@NHm_KrF2;YSY;BrDYH3oI%I}AUPq4j{lMJ1gB*9xt$7Hd!PpE zN(X0~iJ-pT`z2N3;{N=T!r!Tfe-tSX*^t_AefPmaXAM2g*~Ssb*hm5AVaa&OTSh`V9kkLQH(B zoQ+h3H#TR|dq*MELjax>uw9M+DY|mOaXGQ2f10&78L7D1p>oEb#=&uLHGvTrqX@|- zr3LM+82K8upKr$(=T)vZKijbrH2jZbwF>vi5r0JmeyR$$yAL?<*tB7{DIrQZP1rJ8 zWqHqTEmMLP(1_&y5A{35yYBF1~NL1lR%s9Rm=n!ynCn)EdJHu z9wghpTdTwERa3n6bQlgB4`1nsZZigy!?Gnc@>s)<{(wF(aIvl}jNhX4>+cqaMjpPx ziKI685&Ax^gp7Pc`4#U+qgzXcptswteVg2SJoTGJit@Z9jq2vJ$yMH;{pP+@5)hy z_n^OLMv->1_)~YiHEx7QcKVsFvAyjeIshVyciq#HbI6=jine)%DclSSg6d#MnOyL` zQl0YxtqPdoq{bL}bI5vYM&t~cF7|0`*l=!cJX~xR3wxEu$&qlTY`LO+K_S@C4b#cbLAI3*6sX_w@Pmdb8a;P{9a?l_djZ0OGOGO zQj(w1yMQIu4J;RB5lO+pS`rYn+3}$_m3abuC%qE@G`0A!LyqHhsoYZRN)@dZHcXf! z;|tI`Er~Qt{bcf!ajtbX!e_S{t_c|Ie@ge|mM(p=HWifv$GjO@O1dI^g|JKhYhVk* z1+i$mJCB5kfD7a!YyAh;x_%yyPeb+%5jdi8#aNH{lLmQsi14oHq623xr+(EYV6-2% z0199NhEYJFVS#QHT-1#vnB$!wAeBiCYdh^&5~{~(zMZy+e(dcRi=+p#C~@4j;kz%# z8bI-)pHdi8yuI*5u*&O7NI)ulu{nFM{U4svT<(!xxapvenGrE0Iqt534;Ra%TAFYl za=JYKrJ4wWs_sYC&NxE_O(e z(&0Pq86%^=9^TG9%}WD1IN~Pv7E$I>hm<@z*WOx|m(t{tsKfTD^_8fPnmLdHzWdnB$Lb%7x$AQn=ULgbE&5i4FR^o zr|^pwJ}(x60#; zdZ68Bnp*}Ou?m|P;ld3UoWPY(;m4TRFbfF7I|!cf;>0(6RVqX#uuIHgu(cA}`jbJ<}BdEqOFlt|A-ecRS*XBL31t$Sc;6I%E@4!p-OAVwC z(cyfFWTpw#E*C3xq0HN*cFo!4y>!!Y!fazU%<*b`+uJJJ7eE$0U?pgntEiK>VyIhF zp(guJ3L5*KIIO1X04*=NT{=o6;d*B``ay05s7LQZrDX5IeU|-1Yy=D z4+7H?G3f7x4XrE~3|RdXtNH{hu%^91x&vMTaE=v!ZZ(;iA&!nF~+ipM#OG!PEC=TJBp6)^W;=3RlZcM^AVfZFO+yt1E$!CSlnW;#hej>UJW{L5=)*Pd|+JY#MUTm z=IR}Su>i=tHBUKzXWqP!7Nz%2tQO*;Q-@i5k{RI<930`_Hyp?guO4N#OSC=dlTl3B z1!8+@j}6JUlH!adjvwZ!Azxd|?a{17OU+@C1RhENNKpTMq+vw~>D5{qwN`Jy4 z1?fybHZNvy3)K&-vqmq!h5IliE$%)(*Km3wU&c>c&K#rD`tE% zm-?0`oz7-XMsGmB3a5#n;bb2Nb`BR9UPR3>qQGpQOx@nmn0FwHKuWS%2r}#}Nqv^f zF2?ky-JxLPi6hX{-X5E?vI#SBlEZ@eOPnTXjFMnP8*%aj0qfH}`tWeM%v7!I6n<2v z#@#1sHt}o#%#PP3fFdyXBemgHs;K8NJv3Zii~FW4&BiwUT#HiIOjZ?v>@?uhPF!)N z1t=+fCu-Z(D=c2o*9*AH8H=&%FEIl%2-ThhQ>N$Af%v^blX?I|Cq5dk?ilu$zSkT5 z&{7%8l2vH^#KLH!;|&~k7e0sn`7iMgp5S)d7Kj^a=IvusP7X}0U-nB2#tu8D(_}*zrPHD+T4!U6`1O5@J?vosEqTzlYsOAG zKn$BZF~CFo0D9}6`?_pbG5f;*1t|l1_y&or!kLlj|D%p~C3z{Dja${Zkt;Jc0}Gw@ z(|fA(w*7GZycBlYY+UUr{_Pm7TBK*I9G$ViO=_;NyjLsL3pCiF7L zAs2N~7%7$S-iHFom0&Jo%xbWT^ov4{Q0-0Y6o@+raQtemej1N_H-+^lcfR!lL(TvH zfe@|#reNxs>rcww~7s*YzA% z0WX`dkqB~br8Wyjf=-&v>RP@`3#S|c>xG~H14~Q1ACBkgz{UZV4lzzZRh`=&n2auH z3;Y@RrfN)hdTa&H&1>K_Hx+UoQZUcQ=cE&4jW=h(!gYU+u>i4tgSB5!zyd)* z;A*;xCHbFk@_tr!+b09*uDnTQVPp1A@CjpH`IQq++{o*l%Gi$IoJux zSnqplh{q$b>`A9_tGQZvkze^zu0VhWyB{Fkc&n;{=i~}Uvf(g^=o*x`7g6jXv#3LC z1Jk3xDbXpSghtY8I&XTNp?FLNZ}D>L!%Ix+ApX}ySt@7EGDd=&LU+*FeWwZYJymzP zg?^9oAfJL_lep!a|HoS$iEoJf0Q4F1jh3;+Gd&zM?i}7Sezn$n~c@{LEZeyr1!04{dip8HNEBqUBXW;}{` z@5X#XxWQ#|h+y}-Rn3YwtTq#T6if~G>MfG%q1@zcN2Vmj(1zV8+_K|S`d zPTf8_hj!+g0&R1CNgQ_rN;08Fpv6tYu$?Gv1brLa3Fi<_# z9Ztz^4@0|OAsA^><&)pDY(AFyvhw%i_{+#Ar7=V`l`!3Jy%$-aulz=Usc`+zovhWE zs@=H4U)Rw$(zR#}5nho*B%p!QRoX{!{9m*e2i??q#SIaT;tPwUDfELfT5oHF`6jxi z0llPtBFxoF_%Y+>5o2}v)V-vU+N|CLHnb1(Yr3k}SKE^SenSCxmPnn$M7vArK$wCI zx`Y_eH;xQNnSvTYf+C8>l5Khf9rio)e)MvLko+fr&o#Wy1wNmAbs%1#gCQeqc?r5e zTg6kV>u@Z8toN=0R;4AU+_0KbhwKG6$0~Up1{_4)e9!SP;o&6ta$`A>LS0|ytShAI zwl>D(POc!3MJ|$UAT(`6i#)}9!W<9_2UR*-x3Pia`Y8-ah_9Rt+WVjw*v{|&^_nwB z8o}(j^|-h7QJTJq9}KP6Pfi@BNiQ)2G5^2Cdv3YPHg6e1|7cUus+5OsB8k>gc7&;K zsUQi>t8qXu&pI-j4CjF*d#HAm?1U%XNPcv$adjl@J(R|xBq8Xz>l^Q`Ic$vyVj{H2 zr}d6(S*e688A57Qo)gYZ6&gK!f47x!EFob%Y4|=s<*9Jp0dV0;>&4lmTcb%BAJ>LW zGa`w!N=oXysYk0Ks4be2Y%Da~2mri)R>^}C2G77zgvwU^ay2tSM}U!gHKvW9 z;2l4?C3_17yt7;KI9W`ax0dfZOMkf%Bp+MOBnbTSniYao?bX4eP?a##_5_aL0nJQ4 z`#U+Be+k%F{MV_Fjmdr`!;qfPKay%}VghJxBGn7T0<%RX^!g@l9Ha4rL%sggfVa*l znD@`L{dZT<=koh#u_!oc|HC0n0D)BCA?iv!Xzw0c7>tUO2Je#VDId08Gbve<`;DJ5 z7sV2x;k+rg?7+8Jygt{@Ufh!M60I%fUevaYQ_BIa@;u{ZgSHIlwhmt zfcUH))lcw4rQqL2;ji+OAta+@_RSYE*ooW zU04fZbRb-QAL33WrQXxVbx~j*-}tmWA}UFF*g6|KLc-G#ObP7r6f?dQaBB7GvHX7o z#CG`G^N{Ayw9e3Hr=Hx37sMq48Aj7DLWh)EdFzrEzI+s91Fg=bZQF= zwUjqMkUJHQPE|Fq*fEBF_v$EeilyH8^A=&5On7p0bhwx$(rN3L$E7yN_jlH@-6@f{ zvYGaho&}=Fx^wm%r`b>z;O2MmERWb}!G`T3O4`|A@w*#_# za$OF#56=3Dv15F++q>w+1kh`zQ7QU?FKp;KcY&of5qb$S-W_Jr)O0_?5sgj%N{YtSm%09#T$cI!B2OJp6v5f^ zShewB{PTXMfDNNa&OvK=(>M#Kt@u;h(huTb)WXD7JkSfow7)kzLWjhpGcJ7p$`@S(+;oVga^T zPiGlE|3tIegPBk?#QJwHk!}8pcM2!b8|;0QD7~B3@fAK`$0nR7uD)GgM7Jv6_P@5! zl|f_C-aonowP)A}4?&aLex_|Km`Q@Pm*42O-jHmOnkifX0n?g2pO?cK=D>GMd!K>q zOM9UhL*vvAA2J+CFIeTbE&I_L-$14HHK)fG`H6_pd=^opVu;!wgZj`lQsyCxJ_a?& z#@eFn4=>zgWfG37N@ZfV)~%P@d+2+FbLCH&(Wm9J>z?tX<*T0Id?oH4w2S*7sGm!3 z&OGzYC){UXQL8|`J1|f*+t+N5oIfr9HSo2ZCMyp+4IC1 zqj0V(O@e1=R1Lo_lfRokfvZReups0KTr%5{!fBNNp@FTS%#dm9v8KA;#lnXZrQ!8n z*V7YDuFe}y*-=IUK&dqMeLMG@Xr`jl>$3|9snJ)=2TJXT7p-apaUFBYb_y;DXcw(L zDumwYi-uLUos^{IAttNE zM#Wo0hm_d&#q`LhNT1O1AaM8f-qV*cf2CEa>;awAoszt22K=MQ)VxJGYOem1bqmw) z)oRlHG#~w!6nFQ`bn5=^I%fu}0eNC+b*?n{qd7z9HkfOL*>58DyoIU6QZ-?jpM`zn zg2&k4k=TSgWSOF45FHmYo3H&Oxh=MHw&gT`^}cz~aF|qaULvo3=0sF6M`1ou3m*zt ze>G3HNq=~uudZZn^*+R~Ids8HgE!saw{zP$u0(fkdtK~-{mp|ANXD1_(H-XAFp=90 zcSM*Vei#Mp{qjesOzG9|Iy93+n(WcKb?H*X_ekS9d=E(e-EFe>x!8Zvp{G4q^m!>t zgwph)TYH1(hNUDyb33kA1qM)pRP!}d<1aU!-BK9xizdkEc7nHR@5pQYj4ywsLnUM~ znB#nA2{-5q`=i9J8?$|7#CiwD^?Zzt9?X5+-vW_D>arYo%9vZZMW)1QDrl%zSVwI( z`mRl>eccDaNDVPfHY`wXS{Gys;6M3d~3898;7lcBb!bTmMLr5ex0~9Cl%p zr=K#!pXBep8&+U4{&(FvHAU6OjA5ti-!u|+GAcL9W#$_c^q4wazq)yMZ~k<5+%A9F zh88%rg2w)2KP;cY+xCykxqT?T->zt=PG;jO zFiIt5adQBz{{L=GiAi zCd1SfJ9!;4+HJb`z|B&C>XXzyxq|Qi9iRR~ZkYJd0fZ}*%7@$`>n1bd#}2p7pR|WL zY=2|2eTr73!} zCizU_kmRkJO+id0?K|nk4_?r2&3pbBBOSz;#k<<9y+r~jsyNeqP>`2{&u3RWA4xgn zU^~|#B7WY3=*XUt*t#lynRJw9FO`qvp7I^vJ9owA@xK~73>7}#RRIk&XKKukIwm2> zIbfHcYwRk`I{t$fejvk-4+6W8e(h9t0~)>Wepn60E)31iI0qq}9nd9=pqG95jVd8( z>W~5tJ>t_Nalm}>lG-CoNJzUWPdEbtRQmqv+1uf?KVdoTOB}qr#G~z=aY$aJ-9mMe zRp?4#akjNeKSf6a>jN|;Tt3_2%sM9Q`f4VPUMbHrv=i#JJ(8mNLT940W0%drP%Qz( zTdF)%3U_MgT7R7vQ)SybV&unpz9@>w@5JTo?bHyq6;wqO4RUZqiA>tW0AjuYKbS8U zVOWg6_`;@6-IPF>R3}aOo?LdT3vIV7cgg%?WJ2i%&Q;y~ci>lDwCI zads6P{;n~0>G|G_rC^v}$#cyvX%`$5N+6N4%0fCVg~XqjI%M3K2);wG{N`Yf5}9@^ z17uCwa-8l4T_Q3Z`__SlnsI~pptN1jS!ei1AUY6VGA(2wROoL|vkGDSR|Or+-Cf`Qt<2oS2qAW8e%aW0jVP+cv`F@n2@+h!xTyNIYJdK! zByOZrpOW}=c($MU_qIi&9HqBYONq$KoA`6}MlXs~L#nivlNz2HyFzgW79xP8q5rsd zKWM+r*J}17A}LwJvt#V<NBP6NIzq;$+oM9S!|qqViq1_&-LWnMP*fFjRVIeEOpv zdv8RTVvckZrwBE%;-HCr&+?!>+`QSvz^^hzh;0Qj9gdZApc70ZPV4e zXF6&Z^m)L;(u^ss z-??DF`zCkp9su@Er4Y7c2sMUO5EQ%@N6|6or4#BClW(POT+>oLx6@cJ?CiW|8r?E{ z(Zd1Rwro@SU*iTxCVzqb`Ww}%f0Xb|xB!oJ`FD6#`^zg$ca60cx`>%!2Io`BLvU77 zZC9mvbHpn^*$yz!#!O`T5Nh8W!HVm4BJ||Z!m~J$lfFq!HSD?)ERpCQK1q$U%Y%wv zteuo@FR3P6MHk=xeTzyYg~I?3{JH&K!S~o8*vaj zUcBWSu4BcakXZM!L^h6-FCDUn%@&1I$VV0BQw$#aN@Cc1u1i?vqU>(#k8@tOEPbHr zFY|bm(%;6#e8QN+_=7XD3G-2ci-579CgM=3m@!JkFNHHwWKlWJ(Lb|my(RrrK7o^Lh8;h52m);Q?PN*Xun@RNCzO zN3RQkT3VdsUoHLlSf-WX>D7)$c|PT7JXeL}-sg1!hTE8lvxxY!BX{vE^1UaI-tFBC zLV|$-^0hh}qfe)w$!#hPC}*z{e!~H#{;+@|XI&G!%Nym>`9}Wly=b^2*p%J4GJEoS zTSILpsYpGg@U#(W@|01OE?_Q(6!a1~zQ?X3F)Aqru4qht?Oa@WLs~#}FnRk*;b{yh ztGPiBZTQUS*w(XRR?ob?hp*dnPa*>03kt3AA3jWvJ~-u0+9Z>|8!aWhw;e4Dy6dmU zX+te(?rUkCoJ(V@r(Oz^g;TP`6B9G+Dz0@xJ4koOx#TC0U?}eoOftO99yylqwP&Ni z#KdYxWH+#1X)mvMQ)u^Nc;3whChxOmiZNWfQff1z0iadAq;!m(_N$b!vQc{ojWA3e-c^d=5Hu#q)o58Eo!tl z+MJuf^-5?)!Ru;PS8wa(6ID3_=93Ylo$6-x_L2Gsb*J-S_+cJRZM)e}CTR;SbDQ=Umr0&+|I3 z*YmYp`u=T>?GZBf z9eY7^fY{_AaEzqo5A``$TF&i|xRcsKIhB1?nxSZZS=A_?PlZ43iDwxI{#E%hNPraj z@Y`uTaWXo}JqFr;=i%KRZ2THfjfuaj}|j&LW7o^vmowa z@8xOK8;`RqR@1DCVFI4Rh3A4#hi%$0P9MG|#`*aq4_OrJIWZ*!JXJNv4SA%evh}&) zb)m0ohct3TZLp+lUT{x0?Q6$Oxo%zv!y=8VjjdiwcisL(8I4{Dq2cuaz6GXyt;O)j zcrQ~FE~UqdBQXw6Ny}Z2i{8hESedFlUlf#>Zk`ZU+6Wrd2yr#Nd#&`7y3$MPMxyq^ zNb?Ag9$=?qOWe5J$FlAjl9lr?a<%MX-~ z&Hb7|2bCJ|rNn_|zBNPMm~G&S2l`JJd1=RsU{hi|C*rM8%w{iF7**Qx>OYw*f2GKp zT@NS_*yU8%-SE++T%n_dk_6c=#6#D(0ux(`;Tuo(=gux$t6tA(wNI*qEp0uI6xJ#? z3z8EvJQ@{g>ejQ!**=2j%N9`1>ZFYfU!Q810)E`{EW8s&9e`?TN6x(4lyHbInpzx_ z9V*R2)$`d@Wx;L+IugPQ!o%~xqgs(6b?^KV&DtYbu&HW!ElT|Xa>~v|*{&^*6=`5h zK@Y3fnT^b1#%nSlUbr#fmy@oO!4@E5m2g~EO1)}#ZZwvBm`UH`gy_I1%^-N?;cgqz0-Rv#HxR0APIc z%qN~VT{_awKE6d7vPE0eKC1PYPF_h&Y`&xCvZ4P4JZ6-!Wvo&dWAiJkWabxae^`1d zv2$-gHzCeSq*-sQ(6m->!w5+wFS6j*m#_8qiVrO=zUu~DyT#-+cRS`r^AlZ~W7L){ z9$yXyy}b&pnHI-Kt9H7Hw{@x2XIg#j$ZH;WUcOHZx7BdbQn1O{0(cWVp1d*5d<~gz z2f?JI?X5*izG#PP8Ai^(8ONi;OhGZu-p)(uoib`GD1$f)D6MI69y1ZCZ>7+1 ziP-+ZN*mDZFr&LjXHu5r28-LQO($-3G=5`NgO4wMP-UO)`2MXKs0XOgK+4;oEp|_- zHw<~m*aiI66MrN^TtOY)JAR34T(LD?gasGnO8%1606ZHkxMbPVXm`)gmQf&M!(l|-Qyw>0 zdmO7vsW#NJBi?6+aEpL1dZ6Sd8=ehtJtWKohsdbE%!zxWjaDZ`eM0+g1Tj0lBMvBU zhaO_OHGGs|EkET9SGq#Opg@%T%GS9HK3bG+zI?o?%#%1VVl-%`E6`oWqevYa;(N{L zTS7z*PFO-K^7+yimbjg-R&VXxQ^)hEpKD~a7P$n?TAIh%@K59zf~&tCb=t+JEr_rk zv`dK&3sr9~Fp2NhG6)p6_MH0}=mUWNaXM8%w6KT;8vxHbt z%Gd=Bn>f;A?nYJ4?>xfOzD9DH`})Dx%My#6s;^85J}=)(>3*p9o!*b0FY)qNeEd~d zD{?gNTeU5?K4*j2R_$>X8wM>UC1y!gZ!KxeWeNt8?t55Ao^)?Ik__I_q%`=4f>C9Q zQya)I+Czp=Q~E8`VqiD40NYVLl##IwR_(Dv{gP*Y%sCOt$L`sfQd}w*R-)gaIPk>ZZU{qUj z-+q(GJ-p9j)Wy)%$BILx0>ssX)O)KQMZ34EE;GtiW82cfeu*A|h$!_BG>LPQk=TCZ z(}vUR9&=~1D6XS=BYQ&b;+HOwS4?2i`=RGWD7ci?PXh4yK90lO*LK?3+}W$o8rA`x z#QV%`uO3~w+!(5yBdFpU!6-Hh3P~x-0%HvwCw7js{AIJ+o zUS7qBj+!-Ja$ux}>f06hY&tHo^r{hC5!h&t^j-A0QP)5@shE9amW!J%Lc-*XLvp*m z=E_7wz&>G-M2}YE)>A;=fg{{|3f=4ctqB_~LK?P6u4hRUZ%SE}48PKKw<-&xrQn(D zF)zL8Kz3Y#)-SC%qz|y9T(x#|XXDy38VkU|p5aryNIVWPq|TSMRrK0>L}SJMb}RQ$ z3Cxr>5K;=h*SV5pN-i8^uYw3}S=P{4#0#Xhq4KlscHG+y;N)_t>$_8$tRV@*RMBl` zeMjTvve`9WbZfSK4#N8eCA46&usC52e8 zqE<^!-{};re`<2J*%_cOG}mb`DHX6iGN+kZ>bmoRg`cj|@db88G?0zyR;zG4L+38= z?qF>QJx{Zt7xYRE@Db5a!$HSq^8Rli_EExGo~@y&Spq6h^nlw7b4E!=+)LcUl(|9t z!gQKc(T`b;kGu7vKR;=^E77~=o;mMqWU0GLbyqB2Z7^uTyuFu6D_`GhDwAx-5X4e) zYjNWccYddg8Ar7hL91-O0=$Ka{s~l07=yK0p%k&JzpS{`8Ox!_CgrvnrU+NsS?Ufh zRLw_eMA?FY#~cRLlt|p@Mk=Z2GU%a)v=-l^hmnnmxBzn=0b4!fY>(gDl43CNL>cgP zhjUTR_LZgf7C+N5k3RR;GtAs1zqOd}kmvGB7m11)m&9oHtHIl>dp)xGJ*MY45tKUEn3zoR zMuYFUHm)}_CvHpZM}K)nB^nw@i`S}7+;-E76fPj;#z5CLAc~D8r~DG)RIJL%k=K#s zpHwbJKPI7+IsH(dI?+mjPfAJLjnMsfM41Jkqo-E1iuN(9GOJLbRbG=8$1BW_AQKZ+ z^e5Gp2A+Mo>68(;8AH6Q?+nZptOo9SrP9wktuHu{Bs{ruXM4fQxv-y|x(yEVr_rV@ zmIjeYYrYhBCwHQ}B&b%{Ds;zOcK#FY7^e!o1yGHEiqvKhVJfd zuEq&Cht9oM*3487T4}%m3mzd7jP%h2>z0W_Dytr|J&PeSu=!NIlD$_{W-H()+F>K7 z`BRH#GyHh#Kw4i8(P;Zf3RmO$UZ{v>qR9)SiQz{cb^ESqEdytq&+wCmktLGzjfYM} z6spI-OHGesCbTcQcuqMeg&A(;?Mbs)iT9@B=Q-unwam#cPd&MaAM?B_Ptk$ z@jIQcm4OgAkMLq*^1OI3wc_3g!qSx6`Hce5d`hW*N0TWU2w8)t{;W-YNg&no@OEWWSxne&)fZ1jcpM!d&)emG4Ce6S={@ot6U--#ia_#uc<``6&YS`-qt zikiOIGr_mr)eJ1LX`h?C9$okgpxIzbkYa^wkFB+2C|>Dw!jmBTF|}q@2Fqwu&cNO& zS=*22ajv&as^VOV1X#|IlVAK$GTo4r3YZT9l&dB}ciNKy^t<5+uF>Le0DY zHhOYCZ$x99z7{+M!0YE{0R#Hvw9LU{-qRpgwC;N9$`4uF`w=@&ee-O76+0yMdY$%U?JeZ~N`#irCe+E2s?GJ!u{j;+R?)aH}c#gg{y|$uyu9?@)nA&g9{EQpQ}mgG=zIj zZ#-ov{=_rgwK^YU8VP7w6|D8sj$>84)72{_pqyfl0O6FoLHb_z1Jqq6a_;e4o2U2$ z2I2>MH8p*RNNa+BL7h|`K!1iGpuT>W=vqgpG>qc3P6kk>Bh=3)EFtz9_-zz{yYetQ z)b-@T?N)A>oerg%L(b+P{bDw5rc3l z#WU?ySsGL|`ZKd};Z)ye1nx`&^X(A_`U7)f>4<2ei&0B^R`<)ucxWe{lqR4`( zEq3CzSw(dduB|7^W{ABPer$bJfC|Hg+{gzi=Jj1M+tb)+p0caZDDmE|eKx;bXF=}* zCVLWB#ARZMZFZ?pe~a?DVSX$eU)uUnbMKnRX#CmKi1UJo*6-C2+mb~`6cks5zhAao zwB+WSUK7U0P%gMmUx+sX7FZ#wiRQz3*cwoc%XXEK55%PS$Unt2#=ja?J5|$73FwT!5;q7H3`rau&IcZ=>CQiWB~^ZEK<{0k zNi6JDm0$rM;xR+6UOJGgi!NI&heA8Orxo$4Ny2Q{V)Qq^iu+noPN8#B$+EU>EoB_q zm@hVPY{k+>Nh;Fd9YPea@xZ`g;52cx+Ht(_c9fG=WLJu!ZQD!<3aWIKWc#iY-kqOg zeA8px{o#jGI>{9ONZ}##$`>Q$Zp{f{1&T%EH?kviUbkfxY3ftI7~N}^<)MDJ4JN^5Yay18YR%YakELU;7w$gq70A1RjtU( zU32G>z8bA4f34<(pX5#lsnn`~Hh5IdqfWm>I7wG}VB06=ZZLN>wfd2wE^L2SIIqDP z8{3^AugyDbsVw$Y$+j)J3?Kb@!+c&T8<{9D0(J))PIZ?PL62Awl6dMsCpVZ;>3m?LU!Op6Yr7{Dfz}rsi`|Nu0K6DsTYM7Zf>&(%iUNt|WuS;AvTEi=O?+y)= zAwCvZuhQ@m9v_*3ft-j?OP>H|@(D+jE-tHtCDS9B@=N8ciR*x51>AVAWku#fWm=1P zwjTS=yE;O#-{l>yV9s{`5`xM0Hh1{LswgLA=Pg$rYHO|pSHNbs-agC>I%<*L+#7-8 zWnxmw6F@Ln$J}e-NI4KQz4}?|{SlqDH*4bd2YLR!wCN7F;S^`h7{rNy@WN( zWAt*jB0)q^`x3HVoA8%J0vn6lXMe&LZamD&jnlNq;oa)Xla3gK523N(lNvBrc(umd z@+{(YZgoIbK!A+f)WFQeeqW_P zso7GQ7n#V77?W6uZr-$B4-d2@TV@f+=1~}tqmK(5h!~N(KHqKEqqImVtGtM#4+nRK zs>`$)M3>^h^Xk7@E)KJ5qPQ2OlKx^DPbH^N=93aOUn5JKsflgUha_S+QaWF(R`IG` zPTDeR91Pr!X3X0S=f+x}r80oPjsd~5poYa$J#lfP!Uk;F>KzCvVhmii=u;;7e%Z9Q zMb}>5*RKR4b66ywYLkNzVN9{$f#rRr%}#Nae{?tRv^%59;$^Y9fX^LY;IoMFkA;da zQZXX8W*-wbQoa)Ft0y%)kSF7g$gfJWAjrm7yD3?CN9U%=-WF-Nlk=7fSI#Xi?@9SG zzG6=WzG$!Qt3pT>2@taf|BlU=*JnO5k&7ylc9#UfZk}XHlQ?^zwtTbPiP&RTrUES3 z+h=>bdJ$^9EOdyvr2tggajT!%Se?l9Y7n-OaEh+PA7D(_|5gCP(aPZYxi5H;)y_+0 zq2bUQpju4x=)W;k3s>a58SF!WNgYpRtLyviiIt-H51;QQeil>d>4cJF;j zCN7t{ym;v(mV}aW`YM`GV$gPZLSDC3Ei&dtDW4cYW3XppUjK~{(dQ6y2+!<3e zSPo!am!^ZqN`R=*FS-@$TBHv#1zG++7{6@u*MKr(U}P6seXQ~_(2r zg?&U6bVC2cg>{ddPo_1~GZ?itc(W$9O*;K`9(6B04<)TKU5uGEaYZ&<$$2YXkFx&o zc(A_8AsHiowA3CCD${;nKtn9D|2*Yf@=ED~t4_9pUvGpJ6O-|$rwq^FIpnqlARmMhEq)q2yIBExSD zEJfT1#*ySX2VY@ey|QXt89>)GTW;7~wnVEebaN>cmg6PEJc&-6PWX-CV`a`kG2((O zg2gR88oHg&Vw}+Qg6o9p#|fiwlC=b60z3Ce>atPaio0>Ki0(YHLknWpqEPBm1zj#6>>gJ3 zmL9Q*V|W9P{uWB2%g8`4Xd=x8utkIF`z^PpezsJROLssVMc*N*qV zYupalwZE9soc=lxaOF$a)*88#u6nI;bE6GoEfj& z+kw}Ki^w{F=hhTM5I9<}|6Hi7(!nEt1+RO4`-umPNY0BmU)bpVWmvpU?sIUcZ8EJz z6Z#Ytem?u!b7a-^9AfCBTcWfF?E4Gq*yjG)VWzbF-#2}|0J@axRj#_sP^g|~#HIGS z4SYMtJ5ImDg(bqFwAhU*Y-g`4WeXb7y#~J zit!dKGb!K~p8b-BDvLwEJ-eyjgtn&59i1b{76r_U2^tW`@iz;%==@eUC)oH|Z0 zbc@CHkDJx?E`(4`bZ1_KXYTOoeTM}7VseO#WK$Vz_V(sVFBDDPial%M_OdUYwUdm` zVw})- zHp%wt5zF+7Fs_DuF3^#XX}ZUQs0RgTb^i$#)cySu(DX7=!1p$_M!tpduDUN`^J|U^ zd+-xvR{;dNpP%l_D4txhs-nn{Wfmb#&+xK0>ZH~zcn{}#jLk=YyP#kFQ6&EL#8Yrc zfyc!3fPhN=o%-hPyP?=dRiT1ajRG2|E3Df_@rmD{+5|9ayumv$AeB|V#+SgR9>O?$ z5)KZZ=og*p!R(z=VLr>tC~G6#{f)YTw47#|6m^u$HhvwX;pn>Y9c@~i+-u+rT9qf3 z1=ILt?fU1s=ChFyqV(?kc@@0u?m9!OOBL3tN_G=aqVxcZco5<7!?34Ytt09i&OVc+ z>GO&aIEOPxe^FYSfcxqJk!WlYR-u{9<&qk0?(j*qH(PS{F)1U2G%h*NP0#m%JY5ok z*f$`b2HU3WfWFUKt5$jZKwLR*gV9np1**A|jTSZ!_>!rj%X1Mm66`5rNLGF@Z~P(G~q2`L5Ndlb`8 zXosM}>ZiY-0-vQuEI~-TUeBU1#KTNyEQXO!S(t((p3zi_p<7MqP1yyo9dVoud`nJV zSA9P(5g_gpdm6cHeYz)GvV4<9PTd=Vq&q?^Hius=4KquulZyMKdO>)PR4basO)w%T-o2SCZ>#^(!I4Q~RdL z(pHhrC*%7Vv=xtz%P++Uo|kyfQFZ1A0WR#VK;$YcGTh*SWGN*3PC-#c4}){R znyAW9*9I6w&^|Hg`AXyr_4zt`nPg`x2#ecT5|Zg}0|qR7f6(+}lwXBWE~zW^ zrY&WQ2Op?tOL=Wq5%m@zy2;g=C#G1y?=#qv!XC(DlYd$)1)~g7i2)YzgKA#xw%J5`|e8-DBtyZZ@KMC#7P`e*X>?sOY zO@A$zcAZ#dYMpx4tu73-Qoebt4DxNmTzv`Gv>JX2>0^-WiU2JdD1yL+W3Qny+bO&@ z--a1X*AQB~K>~9A|pGW@=}ym3v(J5(^zD4__HBa;6yaomi@vPmz*+ zHoRD>p%{j{H*|frAzdTnnBV4_yL`3MQ=~5Ern>x6|7U{%|SUD35T^mljou@c*C6~yR2p;w5#&qj5chPMy^Udn4 zjC?Xi#6Z7WK@oT?8$`%{U^k*kV>u<^7?taT@L8^g5)>xHvK!U{=r($eg$(x~i*b3> z@q(aL{Q0%HH3QKnu8D3qkjoiFn1q{4>i!Y?7~-%ff=~_1+WDD2^;LCdI$c97T2-e? z2fSFPy-UyIVhU3IZ7RInWNFwP|2)!)t7uYCA&y@HO*)1x(dJaV48he@H$?GS#8gl$ zo8V4U4)7fH=@wuKM5t`#N>mKT9Wm~#?0pxg?y{9+ke!QMXRvj(F~OfD;zb1OX_KEl zTJffVG~HxnA9G32Zs}z&O2h6Pw&$%y&@U@iSa6^q=U(SZnGOF zc$#0`$?~J(m=A+$^Gg(N=@1MmN_}T?n(s&KIzgBC z%qv~7)mGT*W&dAyuF5qEP)Q7eO#oh#i{PzhP=CZ@d?m|Q!cRI=KBqTphNZ-~y=(w6 zuE5)DzAFoT7n86(t|`d2>&6*u?$*#fj5W%(^p2_Yp82e&8AcJEZE`Cbt#XAs=8y_d z#R;hiJCmA1_XA?4aGKp9KKJ@=1!q)o96esevt_|!8m0G$)>dY|4B}V7J+I&@V`X7V z3;3-to$3~p_n+GN86^s(cXmH?y5ZPoU*t1vUP7zmBp>QvPYvT$0TFf<0a*21^G$oH z(IR{??pO?zg|21WrjxAd+7HKfn@!49v`Hn%yARi!g>o%d`6L~mZR!6ooeiVnwiuE@ zC)N7tbcwl6V)1z8BCm6m%TT`Yz0gMn-{C^YuQ%*|L~B);R*qN&&vhp%IuCzyMO25! zXHLbddk!vqn9g~$x4T$NN`zZFG_xsS+F{)>sBb06q-%CRX0-6#)?1yS@(J?J!-amE z3XJKi&^A!2_9f(cM2Ur^Qiz2>^-nKG>t~gVEJ_BT!RBQJ&zWO&cI|)cILg`g#4CBV z^>bR5RJHLI4ZmodOK`4qUQWHp#3cEfh4g!(;5VMqM}^Qh-l6rY5laI16C6R432 zd-~_SnrnF@*BmV~c6l3L8`}eVQb^Nkr=>A!jS1A_nN;lFwK4+H;U;6Dufhk^ev@E->L!@z$S_zwgB zVck382AqZ|371(faf5z@lVSgYvkXZ#r(wUP@(JWT9FJ^w~g1i z(i+)(zW^mIX*(2)D*orYOcDitNANIu@S3^lGNS4@#c(efV?Y$|?7o&WhTJrG3AU^QTO^X^b0 z+HhY;`9Igm6Z+L#ar(3cXGyCYTK^7rC&7Dty7OaW-Y^fkPyn%3dJyjLr(H~%Wv9E@ ze|59mY~!#+3q=3h-BCGG{2{wW@)`?ot2E%^LFnI~cHHjQmniKT1Wk_LR`E>u|GA=n zdFP%84!@RFTxM}R+n?}14m&Nm|ocEu0>x|5W>cSbNrBfJb z5Z|lg|9)^>s5+J7X>6=u^#|O8^Z(N3XTI-sqmF)cK!Nj7ZX)kH4r-PEX?H<7@sTNT(C-VfF{p>UiY)4$W9pD+3>$C($A%JlE5rWw78y8G`}ZY>D+Ir-R}XM$hjsw?E?xYfW7J^6w>|gu}nzycq9{snYD`vl*8vOcca}e?Qrv*ix z5T*V03;y{#`s%`>bIj#Zf-?mIE`F#s(O5CTV?JqSDMruw@7|rRmgQMe&!0Jj_{v$#ftXQQ2spw8UJ3Z zUl-(f`QICz!1Km-=3V~RZxhr%BD?7Df7ZeKwH83=AQs?H%i?%M;raLaE6Gp$d;bpx z7XLrpy~WPu`Zr)2-Z%>V`=t6O21`u#?LX$*|GU8?KJ}Eb=3W$i6k&Dyz~$^h4L~Ej zOwvA#5>nkKkIdO!FZ$o4-!f-ul}>xTV5t6Diw)ibZm4o#PRO0p4>T0gYs!jp?!47rSP;A8f#Xz5A!bTc`b18>b>th2rkomHP}p zCHHnvEQB+N8|@ke`W(iQPYp5T|0o})vHZ#ZFl6$r-Yeos^e?=H8j2%q|A8iTqT2E1AYfph{U z=Jr!q9&#!Is3Z%r`yBkVDf1~utMNY=`CPJ^9iXyIHN(S@E{jRRW|oo+ub|^#rejpL z4z{vz0x1u?=Fnv+hB>M~b%?~6>(3cG*sGeCcD#ea(vzJTsD4Vau8Ez_o!yfqZ- zO_7HT7mjF0nRQ0pD-hA@ue5J&W8*C@yI(NpV{58;vLgFY;vVtGE-M%Pb3p3Vysv|K ziGxKIqp4cFIN|HA*_QW7TeBB?(ay4 zv=m>};)2RMZ7uxd$cDnpZ-=3+;KVwjay99F?FDmn=+=S^av!u&$t=ld3{D<)9d>Kj z9$kK(YO>$lU}&8AnMd5SR&HI;W+%+z9J zJZL3`V_gu$gtAawyHSK7Y~$z74Iw(rORFJl)V*^3K9R3Qnm^5nXETlyR!=GNSmssS znobvLlhTp(+%A1~kVIOAuNg40FpWgb#x#|mU1fBUDhEC;;>Y;gBxbasFfO<0+18oWYEK@1-mlI9RORPbI@N` z1Lv!t8l5{b{$n*_kt8z4YjvZx;@1@1pDacEfO>NxFf!9@zDRlXbE{kgl@fdNcCa}^ z4|!6gm0TBQ;yn10G-O&*$MQ=`rS5&xkYGDR=;H^ZjLq5-y{lIFil%=9V~e6|MRnD* zSsK>oSXeuubTkm~^#;z59H@BGdc?Rn^n5_y@FXxHM#a|TY_Pj~jGefgbwCxcul67j zZnIZVH@^ru8*AZ;zUJ#AUo8339$O?9LXSAs@wKY?Xw>hlSEKWI-H%qcTdS|klVYg> zF_}y1C5I0~l)ImCDLFDyMRIGnNU*ux#VnomAye`oj=FY)59K!Nz=hoC(iTzsuvfxE zqlo+*wE`{m%dQo3Ye3$*`7@r(eY{+!VA#2+%AOOOZtM5BWcC$m*3!Dyro%be%R@iB zi>~pC73s*4o-k6-FR6&5qV`|{br9;vq=rU=ZNXf`aL8}yuy^Zwy}~n_U5q54 zp>5UO??X1^P1rltttTJ+3R1tWVQjUcl0oBkiM(YN7GJ;81K(IX<49;Aj7Cz-1@rHAL6;s&CItJ*^1zA>-J{YR{2R&W>Ay2YbOy0$+G( zd5oy0M)NW8s)ADQ_RrWTHbztwq+QOM-tXEfxVqWV$kV8xFL3nXx!+mZ4D@#t)N3n!OfRi(R-=m?R0&;HGU1$}9+&(Hk5r;Ar@TbZYa4QkGwX4Vjg*Ip_}EMA|Xlfm5>(OdRa8PYr~{>8vKj*s9PS zoh%o<&ZTRvuvVwVr-L;0^S(PH__oCDm{6PMN z^J+JHhfk#Ka?G2O`6NClR<&X(|0?$=d0CSeckwJIVB+*macnzN^r8A z5IZhiPkMdeCw&ajTGsFoiuG{qX3W*Fo!^Z^>u;1gip&}?fk!X@(Q$5NmF?|Hh10Kh zGB+Y#1jC+}@eSllA>5lKVePI}S*w<%&>ZKC8|L<2RLftrv*I$(J?=ba9?0mIKE{bg zzT>QUX-rI#c(T!+tqDzNRtAhC7x!siON#(coY+cw?g((lBZEi5}WVeUWe z6ht^ZvhJ3K?amfS1FoRlqk(LMNUV7$WDbp%;a>IV+e(VF{N+&8@Gx=mqozr~<+1+F z@t#`lcC@nGkw*q*x}JYW^>n1N0Hu8Ms-FJEtW&r4!E%@fLIA9eUd0b{S^0Uj<*XVB zYyy4LhsRNZMv5T*v)z6xHDkj|i(9G>rt5f^rT6mgOEdB;nlx*-Rc1c-n9iNoS^5IJ z=J?cYw;0F^@x1qGqYyF`DA~Byv&ql`*vc!n#SV$)-B1zzTTBFXJnakP-}osaqP4Ld zJKx(=0e^$k=bLcKV=2!5g{q4H^^%xzUOt3r?ip!|Clf!il#<*k z);hXVBKo#a5Te@EoUA$ZL{q~}|Jkbk-frcYPqk&k(mDuRR?GA2PYL}O8TJRg^D!ei zPruc2u9w5WZ?+l3xo5F#Xlu$46wZuOmno>7%PP>e2L=X^CZgQjlR6&)lGc42i;TH| zDfFCaSk&fM$ZSh_2t9h>p_&c+BNsr%XFzsoG;LMg$u?5+QbxJ043w$7JvsT!j#=8$Kyo>2 zK50bCoFTbl)i9IcmW^uc=i>}D)jZAT=Tk6cQ*)7#+nQW8*LK~@w1ZDE|2)U6r5MBV zx8-8=66_L(c9aFkK1&TPhmBL3wt+1RMg6`F7HG>2+u5##rrpBLt$IxIoqKEM$iv*j zO5)2|c%rwSu2Sn^`&2k7?Lw^Cw!S(sK<#3x4|Ju@b{=JR^Amvcqwv^GHIU=ypdjE5F4mD`Yq>aKkaK!t3V#)ttbojnVLxoY<88oSOA=10U7O?{Af0;a0rQb9}=3 z=U>F^R{Q(?Z6T&zrg|@1uXDj1I`_Z!&<9JPpU{?B>rLv^00G3idbOBN*iB#q2SP9R zxWF!>ABCLfh_xN7l6HFh0ML9tqPsjI1S)?m&ct&xelaID=_T-!okm@u`72iXc|L|2 z^QcH(J5{LNMn5NJK;=_-?OtWWO4rM6&2Xy=6}27HRk{w3!mKnJ=TzfR5^56L z0s@~S-o|m)c|wVgxS`I=86KdEcX?y1fhhg;R_uO@G~0EKrwF0HDVSR> z+C7cJ`>|5s6@Xac2fS*v(>=#>Qu8kM6eBS#g%TkX7`{<@%*dCuSjKx69d_LkG`WZ@ zGPhXi?!MHxsqyLkFXo7QPj1xU;8$NhTa;(Ouj{xdEh3?e_4h#^RK7d;S@B_Q!~Ke5 z@_eEPSuv4&1D+)xn57FrZtn_uly``ju=yg?iLWy2gY3I-pJvyrF4+i?Teug^ zh0*72Hyw2O$lZz=?{vgF-w1-2(aOGHIdRjFDt6a6veKetVj*T2^leMvbx24d+)ekpv(I)@&RiQeWR}C zRb~|)QEg$28JS)Rg*}MvN|y7QBO8i6IuDTFSAWZV>O9eMo$R*onMufv8;Ms`0-W-r^#wOWQ_MXz;G}5iNTg36y zbAfu@QlN2=do+wNTH-pf63b6A{sJznC4#VSBQCAz zCGf)9DqYrN$DtV@DDbQ|WMeYa)m=>v#OBAN=F7-3_3hBLEOnw^jRqHiZi7O@#~dt2 z++4`AyZe|{eMysUTsqFN<0!y%dz7I5=K9Ra#zjXIqp3ULCm%pSz>`i~OCHiM|Ms1&e z0auRGgRJ-pZ60mnz0#+U$MOR=aZipb#iT|InVVZMr1HHD%ijQDs~La)|iJWdaJ-pv8;+Bh73$=*a1R{H zv}R|QvZs7NG;nOWC$Ly0LtUmb*q0fl;PE7$%5E+ zeV4ZVzcPxRy(FAYKfFU7ykjce< zbM&hdiiT$gfidE+{*ATfD94g5zlL1g`PWLj<p2YbLMnatVp!b-ulLi z1@}J=3t^x3^Kopr<>HeaHHQHkgV$XnO#=sXdLOC#)%H@gD^};mket2_6?;n#h=-+_U!(ckWeMXv5FrJ&vkf zXA_kQya|Fa;I@gqV+xHLicDQms)(N~Aj0~gb`L~ongda~3E25Brd|)KGW(XpAJIW+ zn&Y%RU;B=V=>*_QPy)x;$;H9N{>74QKdEIy+~@_%E3mDx`9%AAg_geJ!KVfyqq2Gb z(C=vvSlRt#NSHQLsFxQHeY~d0{l04X$ zdSIMKQRB!V2i!(~+~$2%XkUt5#4D+WiNX%=cUHl7xG536o+D^hf&GEBc*isYi!Jya z(*%3Y3m0lppDy1o@tdu2V3&p*m|2;VeKKKmXX>Xqv-H_Y&*9(ed;Cfv>G)^3Ys=+Rlx$^AM}Eq$MF$(Esu$`i zG%)N}VT7CILdW#ixfhpsn=p ztz?;Vb>&!P4j5JVpG~Hx zX7kt01p+T{Zz*|T6H!2fzo-@M4wf)^0!^8y&~7S}%UV zePhmX^L|lpdbr~&-%0CT9R=2uZTpT_Rnq5uoYpGPyjI)YKHU|Lgq+hdHJbYGs4b)` zzF80jR%^u4CAJibbI}@W33c8>&!NKAAY+=Tob-SaKcMpTNUU;R*gnm;PBP z#Ffblx5pzDAIM*OyEGp-rZn_j1O+wRu<3MrGW$6JjOQloC8v(=tw!xv87mk% zs}$vh=C!`Qt)~=lA{TZyT@uLF<2nKDx0or6hS~jT3WihK|q>AN_Tg6 zr=)aucY}0yNq2X{q2ti;9k`$OyZFZsm_4&|?KQKjH>Hzl?k3Gkai^@#E9E2=pz9FN z9(RQexyT*S;WBkxl=Bz+zP^a2C*-ec2mk+CH;YKsZDmJcyV(=hq$SUL+2q``xZl%z zr&})3O}Dp1WX5IZm<2Un%5R$QVWWtMnRoYR_;UuHw`)y~mFrg8g79a#lRN?Cy*v)s zA`3UPRy(-|KvoQO8WRt7EP1W9R-BbaIu5jDjN&-L>yHxmo5;)-%+@L5Qqo5Zk271j zI!O!-N0Fvg^;E-I%NQ_3;vZBG!+T_;38#5~`uo`Jw~M$W#{ZDxpJ>V*(Pj$-4|Q-Y zR_X2pVs(JYpbmP+e8mi7xwZjWUH8W(%ZzWHT7OpyE~kMhw$5mvPy1)e19Y5Gs9$)G z52GhTB;Zbmt0yC>v=J!i18-;@4C^F6dTd9k#h9%W2-3lMg)G0CTx~>+big0Cf?Y`4 zo?)%Qn+wW}8gz@z(4PI{_}DO5H1Dl`;xF@XitaWw{Y9&Zbk)1RZpP3d7Mqng>Iti}a6wMaU{~as_|4B!go5zZ6~KOWfgUOjGxSyUd^;T|PvH-@QJX%mA14{@WZCQ9f!SMJez5yP1r@05vY(%hl; zZu!ziuM6l!M`cq7yvv~4NItC=TBj<02YQ!$V~k-Cg+ulrVU;#41$_o>8q??&NdvP| zU5_*v4&LYI^!jXi)4MHIo%;OOcR$pyT1F$%SGn1EYHdof_pkY?qHg8|=1b-4HzCQ^*O%h z#+yngde)41a90ToA2mHcJSs+-t~o!`NSNFJ!S4mwO+*&L(_BGA(pNrRE@2uiYUay6 z_CL#ryQYojw;0!VDMdJ~=}7*jmRZ%JzccFz#AvotU;~%uPzo-OiFn*-j8ful8B&ZU z%gU*H4=A{8tFi<}tj=x3XVf;k;B4HtvVJETJXddtG4_Txsr~ZE*zkP)m$dZVbj(L( zFON=cT&heEALZtrIB4MQ#jBrv4EN8vJ-m48Tk9=h2be8yy*cr7jZE;e@5BQi!Qfs@ z?QzRhoFXFjQ)jVZn%B&$KKKRwQi^6?9~l%B6afJN>)-xs?q_YcYr#2k3N#y#L`6m4 z{~(|#n3+tupM7uhyIymb5cpC&{+Y%nIeE2(nY+dPwS)fb%5HBgO?7i`?{twFbKwG+ z;%TDbA$yFP6#)zkSGopm1GXnUVMtNhifYbh3w{xAme7ClQN+z6$fd~EmD_R0hE~+V zD$cu20Zx)sk96MF2=`rPtttrE*W>Jy;68_i;IMIcGA@twj zG}!3tNA#`vwp{P}Mzml@>9EvEJ}&3gc99k#(0T_PApV99oLvpL&{Gj}hig#FUwuYs z-QPMkU)cPMSlzJyjenSTa;_eD@N>2}WFp+HgIwTF&9-Bj2#Ttx9T7r_pZ?#4Ik{Ke z? z?QVETarI(VR;SL(%u8oA$ib~Mi4MnpSv{!PVxyhX1Q|m74SB37&hFnj@~fBHh=f(g z%i9vDU86i4YyJ#+-pfwVKXGW1piL@{)g0Q(z|{$Ca}!scC6PL)Guu|!hyI?HJ-smT zPD1IVG3Fg#^%z8*RsC}Xbuw#8zBJXgb>IYm-gO>5yL zj?=Tahv<||0TGEvrc*~y%PcGU<*y5mUVHa-Hs(0=;gI# z);C24%qBf3jaS932@* zy(YmD^CC?YT^oths9q$^l=~q?qefvjd$t3#SvKQ2CW{W#6qec?Hr-^ZMg-7Fe6853 zMM>pHA4SO=k&oE0+7?@~r(e%phpcQ0)vxN~Tm_5pP}oE1tb?oz_`H#)xvk!i18gcO49nRkFA_=!2 zuf{%_nwh{L2q&e6Z=d2Kr~sePud-NrrcvR`uHbPU2G4#ZRM`dlB~}YXQNLjJf!Zqf1%( zJDR2Wg9_I=v#xMorNf2(Xqr&beqGTRXMvCwu}%_NGR+ju-DGbPbW64yqnveT_8=Kq z3UN~@+~Bpneocvywj(~qP>Gk9P@5xJyRL{;W-F3L{8_tF(J>=S-jw|w-)YQ@i)|}B ze*cH{K_J$dkUReq1&v4)J}Ivdk`rkpC3-Sf|0%fPJI^69pEmi%`kWNVkD*LSK+AL+ z{Lc~b2@vXVt_Xgjn`Uc}#*8BUJX0ajYX_0iXo|B?0Z$nkJ99_TYlgUM%o4Rp`uMC? z>^Iz&voH*yZDF!5D&O(H$=~=Xd7c;$?hL;)4R*e995EJ`(}LsAF!U-aV`yfj@^`>? zGM9P(h^gWkOzj`6OV1o2Zl~^6{#xH^!26n%4TosR#xwhumvBau0QY8Q_uhu4Pi z)iHQuRcP?rqIVGKjN-No9-*x5vzuNI8VAVex|He)(mTFH}ktj4KgE(UT zrMXiU0eGL>Qkv>0d+txkY&4uiN@LyrW5^o^vbja7Y5nx0NurJ3`io~!rkzMY)_>_$ z=MYBPPPiDOus2rJ2Q7K=%Tp-r(1T+4CF&8A56sR7-yFSxqXe}EqNKB~*mI6BCzO>i zzXJf{Md>g#KT#3L_OqyhBiu+55Fun2>9I zl$BvqiTtC6kN=+VeQ~L~PsVU#+vb^F{P4#xs~INXjcQkab3AladH3TgjzTrZ<1f(R zJ0~V~8XGSx1ff4k+ERn}D}Of6(SO{QfV|2k!G}av_WY09Pm%09srYUke%^M8Z3Rv0 z4k23P{pX(%mdd!KdIW%F`9f@3V}us*hBK#otBT;6^Q9a$@z~<(QrCLKTQ0=F*5W%i zv1!k*q~|u-jVamcr6$pCs-!2O;DMiXZFz>H(=lpELS$fd#f8R;eer!8C}yJ`TqrY6 ziXT9wSe~ltNOc|p8E%c8`RV(`b^G%p60cl3_`Np>pKzWZ?t91i%g(23fDq~LB;n3k zmD)cOXb5$o>|pu)dtWLtJDi?}MjvIPqsKFN!23qv-I0~GA-Py%IE-mjXswG{q1kA& zx%BLQd&(p6hs^)egAw8&E=mkf;pHpP9Pv_Q2UpKY`b>tWAIsJ&VoiiqIW}qY$>?m7 zP~>E(2d~C3^#o~vaMd&b5IlV^N@#}8|0NIXdVBwtVpeK(*d2Kp7|hfp75abO+Rmh+ zprEk7u~@tc1p5o=ARObdj3%$!n{v@$S$`L(hkIzZ!f~`1TI&~!5@tW;k-Uz0c8urj z4ItVY%>U3jIvg*2irfOFDBLKd!#*8}l~ZiT`nXGQ)p)PJKq4s?z8$!ZKBN21 z>8kx^K3@pYD~sL5m~yj2z?4&SBDMTZ`}2TwMu-4lD|cM$rRU&a*&9Uw=3-3#Z{}2NMWDT?N9NFRTB~=(AP!Sb?AUVGaUdXr@NMfn zjN-Sv=NX1x0syqr6ZM>qQAOSUIOcC^p>X!vaeBsWa}9oL&V%nO&f~_C_Ukmcb=Q>P z(5GVQxTCqTHuoFh_B(P|q?fiTf?ur;hb7r1_Ws_Z1wkpnT1TnIt;pJYa_+1oLrOt6 z5w-Vn(z2mK6Cb-q4Nr~`nW-#{fiCP|*4QX`IxL4o0!zi(+0b^`dc*sesVIko3HD_5 z`tpb+lF-JrZ;k++pHofGk2eIJ+C*<&h&ZBBt0mqQ+iImse_Bij^f0>8F0!@KKk7ba zC)$_6QRNfmQD-(=dpe18!Od>DhSh_O?7StU86N;>slODNu{QKlV&xjy3*%_6u4<<| zW6piKyX+Qj@;d6ot9cUQpEbqao%i}dYG>3^R9%X7Q7hI6Jn3lO4^O>K+m8t0akAjO zp!ijzBz2S!*>9!Ua>G!Qywqd43C~ zyYqTYbCxJhxy8ZGJie~{^N5L=>TpUCXB&g*jm?15-ADHL%=LO^*ZNnD2d4K3`&HoI zsJ7SO-0tW~$uxw(zg#k9g+hpWN6*)n=ay6KOz@N!h|co#Ox93mj#>N3;e%zV!{+=W`onMdO~mG4BZUA6@hf;gTvy`ns@IQ{a-A9Ug3WTLJaUHOE=n?02?M1sh8T4#a@Yr%IU03m z#mDnJRPugTC5y?akaYwyt7p&l1ZNWgI?0qB|uc8eO?^h%R#}uMwP!wi-99 z)-vH=B&1A^f3q$VV9ZD~mg>`9RkOUr%?c|+Tc}FL5PueZq>v=?|LQwH4Hoak&eEWr z>?q!A5YGQ=%*;g=5Un$Tj_#WRy=J|UU}7%a8)ew%tH7!I#B=0Db0eqX75to1q7V!r z;PJuOx_$1BUalzyV9)A#$BKj*{?$1k^JR@p@Cx7tjDaB}F`f7E=IAQN!JOA-1^+SEht~B<$;RDzoFit{wz^*i}k~yMlBNlrUubzX$ zdrfzZYOPqd-BkVV)A+~VVKp|!rkT*4h;T_S0_N|-mOJ@SlxJvpnfV+ zn_5k5{NQyh+qDXxL%G2F1tB)~OfSf7F|BHZ)=}$KMS1a{rSA?{UK?3){m>xDfBABp z*cK3w5fU6;^y_k7tQ)tl;frbUwN>apvgJ;8JW2#Byy{FI~Vql(t^gQEa1 z=R)ngj3=c=V6O=zYAoK~Wi)EQKtv7n$wkODQJ;T7xCrnOykDN`#M<^xcWSJVrjh z7GmnmWjSVA^PWAku}Gk%rzF!A*zE2Y*CZK zYZWUSH9wgj0PYQJCEx^-LU}!a=dyTAgXY~4v>qE2GIIC8p^IE5{ zx`)y$4|08eOTarvdp$Fct|*kXJqqmac`DlHtgH~>4;{PDX++olJ*uZ|s)mUtMHMzw zOdp`lS(I&(0kNx zxDS`mBVYL?ImErjg6?@v(X;Yb(z(N$&lq8eoWx_o=8pDOUl`YxQ65wLvQ3brTzanU zjQe%)!wZ=lI4&`{2bnlLxBXZbhD$!wi}bZewh-mV9BY8~p(Eg!tWR-*Uqhl)e-AK9|*C zg!;$YOL>bWNO-QnEYDvYV*7;|M|u?v6iz{_;uRQ;0N%@(KiHHj|% z*nZO7oPl8)rFzj%{J4vid$uB!P;+AbRBXroDB)>RyK?(tPCKEmhTI=n#7vD?G zas936!AvYMUTvdVRaspuq`3Cyk`W5~?f_UO0_fp+018f@wx%VBU<%TnS@JpR&v2$RVSX5~Ih^LfsF7&O=clgC%6oX{`V%C|RFoL7D|3CJqG(oipK%v=+So&691;P-X@#o0 zZXs580Nso$ z-`vw`TE&K(W=wPLij~z4{6FFcrAoTpAscAiAK9iE`wQ&EgR1e|bsZlqU5MEhUTGRG zXFebAW1m9QUa`m~gN-T|mu{H)eqwuEoLtdbETS!6M68)RouwHl zT;p8Rx?+nN%gR07LA$%EdRBZBdb-y7A=FW_pHgzE)S>X^meBg=iX82vY&c z5uz~ZHV(Ph9HPH`Ur3GPnM=mh8Qxv`uhB}nOLvHkrBN^c znXA=M!AXku+fP5sX5;DM($DOq$d$-QJ(Y!J25{1E;?yipoxDu(cekkH9VNHoLtLDd z;}`AmKEhjV2%9c$YMM2ex$id7((RQ>Pd3tN)xw<3@MncpD(c_B|ztY!y&+*IsYjeC3^9b|TE z=5BojU55EwVbWeUQTtZP9aOKD1Pw9*%nX=)8$5GUVI z9lFz16+M;<4&{WzZW$EJ*sSdo^z+=RC@U1kHb`jBO*=kEEDlW#lr6g5cLjU1KRa^a zvL9wuL*G3#M4-IlSc!C3c<+d=u>Dz44j2EMGC>U7H-+A{#Is{_mERt3GL@24etkV{ z*#i+h9H7o?mzFS?O2HfZTt<9t{e+Teo=Kfcz>Hg|PbDVu=#chdoDF;s9A;mtdQJPu zBC?=bcW)4N7u4O_E&xeeYft}LZ`;X7jYBdWROzQLKMO4IT$Y4rn$07O`OGV5!^b*E z^M?w3OLf5pU8y#%;Ms=6&GSaLv;s;P^$b(}l&u(C7 zZFDu^aLRy;EXOMGtb4g;DY56%++ZeH1WDNv*(Qk)n5mY4$H4hr`b*2mPqFo=(*ojz z$2;_rLj*8{JBLbcG?5#0+^w0kT?h)=2(bp)H^Ivuga29qGgtJ}fR~-F!=!7M{FPm) zZZ|~NaB#>MqS_h?4JjT|V|h0P2F((C39usRLs5T=mT`3ZPXgvm9?q*%S9#Ew5cc9y zoPD}c-5x6x%JySrSgV@sKwe&5+K166mQmtpW%Dr~DK4sUjsQR@fk`SfMdNdwi}$+4 zcf-$WJ0niSS5!xM0wCAILL(aHe7~8iAFs&EB66xL`=L^UU>#eOllP0j{z!-5)!9k_s^V=F2XfqlW}h1`wGNoD9AHnjXMbWx5fjB zX|ZWOoZs@@WZ-8fKdML~W187beL1Zv#D7PZIc_=%4pNn!?YF3S_Bh4=Pl}rMpjP{) zhco3iZhjOu59=khQtqLSv$nRvDs3Bdyxsa})Z4mFS=QMpJLq$^i;ru%NPNlDn!{B; zxGqFEvJB-GyKDbxK#s3l=C8pdu5y#O+G_SE*U!bAlC{2qG)XLh2lXbrde}<3F&hy8 z98Paq`FVLyM#!i@Gk4daj2!9(6Pd#}w& z>>t$SrIDI2uQOWDU;=|V)n`s2x0mykRl#eOhmU&mOP#^%RwdsJ9J@p*&4wgs=mLP?EEfVkxTwTXK@a>h)t0Jkt--X}w=Zo^XKpI)45+}6fXwm5xZG7V=c4E^Dei9ovyU>W zK}i4f!iA=coN0PV9#Wx?g~{XB+2y)AIaN+=#1n<|YzR%>f;yelrM_8Cg3&@@@wi`q z`|hNNB{i)*{^>M*p<#5IAscrd{ltFs0Zs`sR~%n&UTr*hUKxBO3e5+|;s$HqyfvBI zzJohEr!<~|twg&?&PsrB{&qdnoT4f}=jl>uq@QVe52-{sZ@_D(8q?8AdQLLE@_ZzX+5JY6KZ9TEH|(U0K9O}gpYuyq#5~gYbMpuS!jh!}G%Fam^ytL; zB??fhEZQBUTXw52O_(e82tCn9a=9MUdxAFi5ske#{$PB%_-dXtf{-9jghRh?V>@;q zX%cM%#VvWz{&SzYm1%zjKZfuhwN!|Y{{cC;V#(n4)*A0}%G}$^_-N8QSb;6UC-43_ zHmFK=3Hp_~YM$RZ`MzgerB5KfkIvC=o_Qc0E>_HiPkdvuyMj*I)s~rdiXr#<`5Z3x zA8-*bkDM@FnbgfyaVzkqWE%48Kmb*)UWq*h;+r?$Fk+f1mq0sPtE4C z-f!^?#W&v~HH%kB$@~Q+3Kt^haQ&u1KD+P_et5SODkL;C$|}tp9WSrFN0?*U9L<{U zJ?Z|u+&qfbQ$;Va4)8bhvds?3t%EC|ws!O78%VV;Ep7p@?ljvSY)?hHQO*$>{HAgR z;0!2o>vX-zesgz>$&6R#3RrBnrx-IwJ(bAOxfrymyVyflx2gN%>*+I!{ozx<)#Hr`9|vdw=`}Wy_bF5{sh2xlqEIu<<>go3e78dS z=ZP0e(MGi-mUuTvLX8)%%YwFXtP7nJ%gFxQsX7-Luud z8i&I!%mT@#l4o>gZdSSU+HE|;-WA{leiTWO!r@f@)m>lF*n9nqjo~>A^Po_oQ6+ai z?7f%FL`LDi zr4n@4*1cQwlnQl?Ajn0H6`c8Jn=wePY(?t5(fI9n`Y?h_-oNhqRUKbqW^i}wgHRiU zdPoF-HgK^n%P#!8wynqniAAMu9ZpKq+z~uFg^+NuDFrQ}!IF=?b%E;p#Zcwp%t;*` z$SK~4E^!u9wInBaT<)oCJCoqq#yrzZ(>3*I2`p;Ag27sX*eprPeP`{!xvd z>X;^;_V?B5My7{7e017b13x4}G((jej62!)B1bXdikS zGLrhKG%+92pbCN#dnp)`$Xa=ETRK1y5X0Z+(T{v@5y)~#kvCg_r$x@)bQvR?}9nrWYRuOhrsP{mJW zqXw@xy)1XNiL37f!y$(qt-HCu4R$D&773#|nIs)MwTxDeExAU59Hg7)W=joa*g!F) z?olo3N_6cqe-ydNW|d-Qy=NW*@#bZdX8tI%3!ScZ}%E#Q(To|byTe;V_>}{0S#{DuJ!>a;>aI#?bY|m4YDXJ0nbc6 z5mcda;azAf4Q`Z#i)u&2$MLlKfNFSUvKH!GtQCD_B5In!_^8}gEg_v$V}P2$+~9!! zGs`|YS+qPz`EzpAABD2+Jo|>7S>KOIqcwjcw4q=KrGE^DFSKVffvvc-HRV`EN#JOM zI#;3a$R#WSpsL|s0_79M!umMQ^{lg9bmRIf@y+1RD|_d2D57!Kwbkc|lkT@zDyd18a zYpW2{S_F7&_`38Rj1IoKW)~atO>ri}T`SqeE%T0*D7hw(N)e7h;Ee+sc92}B zZ1PfKLAcq_7ij}wN^8D#vH8M-(bX=dG6q4_VZzE?U-2jWnvM3Cp zi~$b{ly{Q=(ynYe&VrN<2+5ldz3Ff{;{I3cn*v3JZ4YMp#F}qLTdAGVDX%c5c^6*a z7$7jKD(KB$J@LQzje}%z&6lc=3Jo{t@bL2usoK0aGM+MxaqLfd!c+fU9of?23Hx*Z z3s&Ddx7H$R4R6f~2s}I4hGy#|R;VcHZRr$ck`2dZ=l>QKWy(hfK&t$@(VdNg3e-350fH&~J} z#;)gCY#xMXi@DUdXx-og09l$pK}g0K9)It-|6`dY(jA$daMSr%`XcB2uT(f`A{ zwrmBKHy*4F{&!pfZpm~4(Ss??dwpr1KjP&j~h{}#h%a`rV^na;$T00E1w?* z4ArfVnZYo<(kP|~%YyP~v_{jb-OAh*5qpZ-G9LkmqA2N3eef9i@Okpll+v*X7}f`_ z*dZVq+oZisI4$s3BS>3%8ud4gJcGIvKg{wb*%H}ZIj3K46VttA5>|>x2v^g$A>GTR zSAiO81#apUOWbkXBm+z9Of5`~&4bgf%5FnSH8-k9<47!N$azb)(%@-}92MKEw!9^# z3HxhvEWnG6?&%ZtmqN5NueOX=m4x`>546=6)h~+&`yBzPZB^yOO@eloPsz&}bevem z(mQRGFFD)4M2K4-@T{}1NH>qBF9IbKrp{rtI?XOn3N~ALcwDR%NYS*vTm?*jMAAG! zbxwFNEsK`0rhf=9G4T_D;hfA`{9um~;|orhEi!?}5WRpz#q~QP#MZvePFipoaG+q; zP+-kSY-I|*5!yWXCm(D$Dq6sjGZ{YQrrpOesPn@&G`15RACmphbogB39Qzb0mB*Nso!+Fsfa^4;kGSizPUe6M1+ zb|suDe^PQDAeVC$wHo{LPt}OzY|e>E&ld;Wjz8q%lJ!OuJ;<~$L!m{nn)BkF;IL9X zgjOFJ0yLH-f8$Tvg_h2_QibaZ@>ct3wfbh_7O8c(3ojPFz#n)g(8OSbLq`mJ>*H_$ z+~&;wV)ot`(ZFDMHKz>{Zl&72o=ZbM8Y@{#F@MP1f)``8jyaWIc~P{}X1(#z=S!&? zZhc&+zDu~_sY}PbBS=S87Mf@tTYjL9$=&e zjQ;?0I8xl)8-o{LKRs&gz{99qhQ6d^c*iY|bH-nE(vw+K@3gyBw9>3YYw-oHONylK*|ev)G247%+e1udS>_qbie>laO=_l4${2|2<*#TU z<_fP|MypG%;vsIW!J@;!swgV-6lqTqXc8&u%Bjr`{uaJhcC}ur`p4&WAon%X^sO)q z``1z!Z%%)mCL6%>-LwGM)?|QFIW0d&YY9&qWu-`aOT*Fk zbqi#*Ww|TNQ;Vsza$m1gR~%i!Zq3|U`8(&dbnMqB0yFg%=4H^B;qNs~hIS{-G(jpK5_SkBbxHw}TS)VVQn4)JiW{lJEX`nmy)@ zk}ys60*)!t{cfM;l) zD`^j|igZv&*QI%W)!1P;Y=PG{PZa&>Qf?knB>l^s%GhB9eMWwKNWF)dHN!%HGu1wC z6BN%`$t6hGU5u<{J6?)X#13L+WpS2aw6=$iTeqymCDuW2DP3K)Hn6@dKlG|-ukHOf zHc!$qEWI|0X9NYxOc{2FKpiiqh)P#%V&dT za~+`)NN+rfi1zNh8DDc%+7ItY7r2vZ2%viTuI`m@g(-u@NB}-xbXH(s3dx(0gm6|v zTMwbrV>*1SUPhI`lco)BY3)>?dJT?NkF}|$k;jVgV5*06h^5zLb7!#n!5B3?`kIm! z6Ng{MB#Dz@+A&IC+o0tB(jKfik)9Zb zi4=_wb;iFjE_-MrzKN;B7ZA4EL(80mr=92K{h;|AgGb*nqTNa5b)|Z%`>zJsj(zc7 zwCO6;AsTf&m#fSB0&!s5a+j39dD*DX8cTsoA`wuipbhPA1J2;x^dk=fxQqxf4)FwF z2=_TxLrQ2Jn&v0IJYh1vvhq!;QfJ9$+Cqan<@aSI%pRLjGdrvJrC~&cfdhJ=zp|?p zu3(S~#uIfkpH~Q{LLZ}NX=dUP+=J5|S1Nmz!(o**@cPc1$Hfg++&W3SEr8WKet$Qt zj@Kxtmrx=-)uj>uAmj6R<1s*Nh*X!28d&)9A6u(f-l@;%I1xv0m45W6L2YEgqsFzB z+QY|@shXVcZso3QHT#abyQeW1+H7r|>Z#C|b`?Ela@7Qav+kExQnFo9j8ku7b zTivvCf;vgvzuK_DAWE;1mljQ{% zz&XHbB?5r)aAA_MHA9eog@2Sn0fsydO@M(SEmJJJ|C~pe(GFStoG~hd4J5~5@a59+ ze10~Yg{jL*MtC+5xaDjXy#K38FlkGXmAk{7ms-ynp&ilrWX} za`a=7qT0Ec=f{*!-@&voU1hxKv?cyf7C@yw_I3yecYo?ACIas<{8J*Ge1Stz@qKg7 zhLYQH6d1SqG^Lod^Y4FLy*r8Xi3V4}xgQe6hGaG$-r+ikPAy&*%X~vA66qHS;U0Mf zvvz;Y}H zc`Uv3Vbht;7{z&`^HWT<%OaB@T=SGg7sAd?uXVBXuPB=(9EYviF0KMFrByCvncLr^ zw`@+LhN1j#JkXoh9~qBbtT#DhaPaTK-AJaSQJXb>EBz@|S7`(ja8bxvGGw<_X~Zg@ zAad{UT9$?sCA$#Jf5C=jcNHX_%XGT0Lz=53C-DUT*C7K|PIFB-M!47raJ9uDriyej zj{9l(#Mwm3Vx|TYJomG@p>eg4z;c!esgY>z4((kZvgFt2KS?sBsowsT0^vI@HD_SG zl>hCl<1Oli;hl1xh(W}Utr<>HgI-H^N?3xY$4dWv?Wwt@!Zm&q=2>o%QbO?JwNy7J z5z%jsxf9o&*N+A60du`5r7cK>vamMv8`55hh76!Ziz*|~jKYYF#ntwpT?vHC#JmtI zvDgO9x&Gvv16TkU|Q=OqoNJ`^}QwcMx@6-C?FH}rS~ozBbcs8JHBcyeiQYXqP9 z0f~%U`Tn5SEsq(A;)1+fdp zXRT%mOt$S|F^AwXW;kGd@D4aKMx+17+}+Sd2)z*bua^n|!4bGGn|Yb=@WHDXn%>JTTywkr1`~wn)aJzdfG7 znU53&k(L0cLQ){75aVD)$##u!F*}Q*0ZFZn5R9Dd4tdi$)e&Vf`35=8I37kB7e$%M zIqM5woD>Kdf2%_C_13yr8>dxlFwY50HbKVo+0#5uK?~KTQWRXg`Lk`FcJcaakav+4yH^Odle77p!dMZh-jxh8SRjq3` zEo~;>P=dh)y=5~dqxe7b27i>b^r*C$9v;yVzL9YBh1T$u;i}xM21FZaq7Dyr1|L~k z8>+t7u;ubX2bmfns7ET3w;`cgXvrTCPanl0y>1zI-l5a98(8v3>NiN^hSsUM{m0ltb6jmCFM| zIfpxfp(ZEy_STfNaureil)c}E&Ca8@?JvGK(TGF}(_waKQ89jQLKYBnR{Ax@=b*ETsDU?)lu$h+Vox`jBME zs&dvp1#3_GDIT*(bYt+r$1@Zw+;Z4TfGrACxM4}gso&gkPSoz7uB{+7ztzA!RT*q} z0T+v3BK<4wI@}Z-^6EwzjPs)5d7B)F*d$E!Ep5Tftx8Jsp*nMxqe4oxxH|;8FHCZE$Z!=V<16x*n(dR z6*Ko8Ai(EI5nG8GJBG`!;3GP=liPkM?C_12yk}Qudx<%oNdra$cC!0N25`jhQz43kdHpNjRKAlfjjxkjRCwAA&j%>o8L$v5NyqVYt z(JO!S$^`(rGJ;1Msq5%6egn8Qxfx3FyVul@Rq8AM zmpdm0N8)MKSE-N&@Slv$xyH_5Wo-9VmY_XH;1bL)zuo|J1^4hJ1pu;rF>7WcMdclj zWl9Ue4oXaY-^iG=83Imh>$Il8tB&V{df}EOsv{@?)vjrv_;G?)$L{(o`OVE2(N^d? zs61)B4T1xLC^=Op9f{d~6WpRE-$AYaO!8wT8S?Rm!qK6f$-Xc9l`AdIXI{sUF=$v( zL=>6{7OM6}NU*4PHQbw9yQT9L>t0{6u&_k82nr;H#cY24`qgZ)ShMpl6ls>talacx zJ#Q@n{`kVk8D-?%W8?Vw`AwO3|E2JBJbDqo$C=mo%9_r>6p-O3nWaL8VAsEs-|5Sz z52ixFYG@&)K3Uq9Au>c}u(jd}f>%o42yOLUpTWnsRhN4&yQn^w9$66TY*xCrd$BAeR6)2d6u zAN>{pC`7SM2q7tOlH6(oPy$c%KOCmeWC?-G*Gp|eFKF7B{Pt=o!=)L|jM~97nT)h{ z!$)j8-UGAFr%Jo}n4Ge)j=*;xaapv z_pUVIh$%nv)Z(>LB}}YaTL4{jyav6=dgNMxY4AZeNo9NgJ_FAFm^qbU!(JinY} zH;tx)vo3iY9lWaRJv@_6in=PtzqIxs3B9-8Zk<#8lzKUaO53xAZ{hvI_k(F4W-x=9 z#64of4rtJY#f0{w!c+s@{MnZn{y%4=5W&6?wlcoI&u+Qokk0!3=FV2zF92Z7X0hTJ zz)rEb(uD5+DX~(vB~Os=6X$SpxcW`TcEa-dYJK?Eb*4IV#ZF?}H{-UVkN5eEuk|Zf zHpxK%q{W)r^&t6Nl}9fp?}#H6UXHvvn@~VYjZBObs zwiJj@27qhx@K<2Vut~ICz|3jsbEe}i-B<2XwW^CL#K`;_aL5!OZ*v5^hO|_9uOAe5EwMXkXA#>+!ecZ*tCZ9$ zu^(N^ULX%|x}bQ;m;aeB%w1o{smWXg_N<`ISG{J+|E%y+4yMy)y9=DBnmoJhIT7)K zu-c~9V%fFzNA_LRCb>CiJ!bmxg9C$1=|DDA=OE;f?+@;x;5yKm4jgCJr-+cBB7Szr zufOyto>4!hWI_X9@l_Iud4dq!Mvs*qM{-vb(8x$ZDbzX%0|T$XaMUzv3 zcoSMlaYeOhhDZLl#HLe191Hvl1BaaK*R8*nE8WIw@{$gg#>V6_yJRxREpDKe6Ya{4 ztx|2YUAatrmfLKx6||~f)28!-f7F|pEcc!Ly@KBEA3?Cih@R^wK}}5%`2Golmuu6s z#HjJD98_Rm4&mN8gzcy$8|#y|voe&fu$J{C zqB_e3`9(aNu5(K5Vvwz7d&wwe`xK|DjKB@K2i=$m@C{q)%S2NC4^cf-`XZ{M$Q|?N*1f2&yCKT=oR=frQs<-Qk>KyBQ#-*`(}M1Jqnrv0;q7 z%>U!*s>AVo-#60?!!SKP-P3HkyW0%Iv{(1UOm{QQtGjc$hgWxdbvM7qKHuZF;%cj;kiY_%*Maqr!KZhdcIT%v5jxnRN_!v7B};KFCV6O}TM7^ZRgRDNs<-z=-wphIZ6+er|Ow#7_s zk6(2H7G-qafrR34U$rPMQ}2fkE`J{0eYL$Dq1Fp1J9b~%dru7r0kBoa4MN+AWc6R7 zV%Fow<#KuicYr1manoG4VcZWAR%=&ThP!gZvNeHc7Dcj5w}U^@dUsAT8q(l*^oz}ykoWlm4(;$!{v za#aH)fn2Oi9_hUgCbDTZfHKKPP2k3=hV9A`({(#tkyr3HJO zMkwj^`1d^rQx}6MziSen1=d$6-gKqEeC_D^E8*VgZxkz8`@h<>ccOzyn@w)^#HA97 zNMf;ho^hG3HvWFKC?Y}Rc2r;wOO+1&T3X<)=_7sHK6#waE`+{N2LKj!TiIbB60^*$ zgeivkIMa+7+S?t=S=%lRl(DWK>J~-3GTH{9gsOiHoU7ElJV=B9Nci;(?)ctHeZ$vB zRy60@Ug62oWX@@`SRUvGkC$Zp96Bu)c&Yr}4vOHO>ZOH>vwhpSH$#IG(_Z zJphk}E1?lZ+Z95NXNA%!+hIhAu=3p>{&Id1($Cu2lWTdn)V7pIsa2BH zELo(-Z2>C z?qf*}a)F{Apgb>gS7aIFIhdHqPPJ==$`q5Dsnc;hg9OI;Lf>INn;*H4EiHV^^2u3z zqUQIk+$CVUuMS0|h~Y-pyt5VC|j7sl+DE99HR7 zey7o4AiG8=j*JuZW?sNNM{9kwV5y3T=lUK2o5zD*U8ad$!W(!HBnaK;B*fz)pYQ$>*}#2F$m1~ zkQaezE4Cd2c8o*(m(#Os2snK>np|y^an$q3+K!O+kdgb#r&a(GAK^D4G^lAh5tBXy zlV0yWXj%+sCl6Q&h}elJQ{hb@2eRL`l@95K`bSxgR<&cyK9zss;KcG`-$b z!x)>~!u@zPp{-modf@ImpIjz5wT5J(5b2~hed5NLFsChJxut#n` zA|~^5EcNoqC^B>C3TFWI7qeW|T%_bAZmu&@dfy!)C&27mm%B?29Gx{6I}#3-82D&>Z#0jEP+CuuIi)F&y2is()d4Kt^{F@@D$+_%uFt1tI!&_I~t z^VVRh<%;8F-aPO#&Ib(DDMEYqIxbWSm;=0qTl~_8F&X>@_MuRw7s%nuDB3L*ue`3g)_kPG39r&yPGdp?#INhHdF9 zC7xyr@s1R-CwvqKSl2d&-(_ZHM zGog`1IIn$X6PP2e&myx7*n45_gBTv}DB7kL_wN!7i}!GL)3^D1^kctT7guEaZc?vO z@6Qi;f7&u=UFlLke&OdjK00r6Tjfoy7sN$-=(zU-5o1;ztqvUZVaZ_Xzpaz{yrEjy zasM>`Wk>g90&69(uUaOaETYt~ek(fcP+*_6Ha5(S$?v*%vm!z|*L!+Du767L+t})1 zUIz6XeR$*CvAJNuR)EX5_B7y_QrE$}Q?KqBGbQ@<1tCxqsle#D+y36*`ZJT6Dn%;G z-=|K&RPj_M4-&||G3voAo7w#x2r2Jv8F6`?au@%UY|=9y1vSf4%zznleqZe20*bV1 zqfRZm!oBNy5Gt-fXV?seN_v*Szbc*U9FDWrFl~FSHM*w@IL~5qpm(Q7AN$vNJl=Fv z8}h@(4(4Y4_i(SrP9*U4OXrFazF#MpgY|uC053tX)a*LquCfH9xcxvV$I-Rk+q$3f znT)4rUsp^$O87bxPX~W&F3QvE-Ly8O@6R0Ku8>i->3VY0(dqi8JZnH*LAOEJyv?ns z)YzZXOPdGgs+Y68(4-9(!(6@*2qy@(?imWr1K+`8H+#D}9so7nVyk8&B@vqbqY1La z5|kBrcImgZO+!4bW}fbrgD&@(e`Vfz)-q)|#Ma9hPi!61Fy|Xi4aQTc572|aQUcAG za^sfo_)GYNL+s*+fR!EMA&Cv}WUH-?k2dGydP_r6M$^t55`~1WnN)%L29Ve7K9&(k zO4EArs9h?&9NZo7bJW9oqL_0)=xh>n}&U!LA?`KYJ;AOx0 zUZuIzvN%iFJbB9$>ax=MB+)rIwyku%} z7M|cly)wt88!E=(fXr{{;=ak#!i^{Jw=&CI<0domdOFc-d&ZHi)Qq>$dqE}x^l`s=b!?+erBxe-`~2dhbYaZj|Hlvi zA759_0Fl{Esv;svEV~WeY&L5MBvSMW7Ow=U=a}ZFyTnR9z;3LPb9@K3f0~nL;7XFW zGBkw?g}2&jrYz?bW`pc*O-tEuE@W+~22(Bl_cw&0<9xC0aOwDiOqM+F#;K75+U3$a z3@_O!LKW250|VCY!UumQ16Cr?TY6vTunrXOBgo%ouMM1%%4$4f)y~{*<`yu+Cm{Lcy*A}Yr zAK#WJVC=IcJ@L+P-N4brR1~NTH$x@ST4|gr56$a1Ea`KV3S*F7`jt zF}OV3mw;{UlzV-JcSa%eMxjeQvStDZ5va+X2At zkP6 zI^i^?N;-1G?-2kofSlR?x!SB!Yx0;1_oBtFFBr0Zge_;?(=w?Blma2ggyZ8iJ&QAc z?)c^Ptc^aAL5L9T@Mqdmu2fRnl8CsUZdbgERFQ6w?tuTlBY{)&r}-7SlHZbUuA5yX zR-E?&e;(!|;S#o5QXHSu6*JY^qMH}CZINvQZ+k?l+WxvK_$~PnBwec7;xRFws!Ss z>DEhr7La=o{E~jD=-@F>TBPb_S#QI9_s%e?j0pJr>RX`)U#q6dt%1`3da4l2ZIHxi z^rI7nhb)R^s+r~DS4B^qw(eZ_*5c#_joCCc)|t&T9=QJXDjs&9S674m<;7ll`;+D` z-vI*0fUjfGlxW@_04b}SyJ%Z~i%GwIPB~%g5j%BZxM72)LlJu+FV%IspW-B(1AT4y zhRpOEhe+NBm0Tie0gu&=&PPN=kM>#9c$|Bi#jWmi&7`-Bo*2|sdkzs_pPbxZS?AkT zt7_h3q<2Lwdmq&OCS;<+rDDHN{p0{t2iApO?pD$UFJo+!0fWN@Qdso)g3Hc=JX|MSa7bc z^E<_Sx}zUqkR6RWAm^<%uRpXFhk>bhP4{^7l^D~UV%z$d_MW$VTJ<{mK&uzBq1N=x zY(eo2ASt;nQA={lJWoyBa|sbV-`fAw-vig|a_F&s$7t1lH+9f0Zx@W?vdZ-MpVYf^ z;DN5zMG9PJWhZPYB_aE|JD?uG4tf5qi!tb z5Gai`6#_tq?sx5|xX2-b?nXOhv50)HT2=FtYF?KDl4Iuc1ndvSe}dZNn?IhZq$BN~ z5Vo@JaX}iT1OL(gi6;@-9P_%j&X~*6-vi!Yr!mC(K;tYtP5P^mT#gOePF13KKYK24 z@Kp^g{MPaFEO&BNXtDFWhQjGoc`{ecl{q1@pjJ@T%uJdvr~?fevO7=5_&Q?>$Fp^Z z*}c*koJ%;_?h7yxF1d|Ij)FL423}9Xo}waEJFf>aD1*;4)&bHjb`^2ghs}rmS|d5x zH>Uxa{3Em6`eT=y;v^%@8g*UhWMZPVDI$xs%(b}Xr>?r4@ENN6Vm7&r zQdH_r`|2i+{t_`{zIH$Ia7-_C)ndnsPTzx?>^xI4+amZ%B9l`nn2_y!JFx9MA5OS| zN2AZX1_`kWqMV+p_8+K0Ic6(n?9Eq%c3S+&Y!Zq0Z***(C_i1B6ZLQ=xor;ocs>wx z{n1jsr`bE_t}*7;acr?M)f;4W3Eqn2QgEs}Bphki#q<#im0OYUft0Ujw3;!QD0?MZ zlI$siEjD7}f+5X;{eqisc%|I zotg4Ly60^NchSxaR`4A>M2mF|(S?pO96PZFKI5tY!8%VwU+zDT-!(slVs~Nk9b5kZ zz;m94p1&)IclEId+58mhWg66$sLryR8Qn6Oi9HUt*xuc}+`;e~tkWGyLL89BS zOs0rj`NI`2pF!!fGo{atfPJ=b`e0}nKNGYIbH`5uG3C+y!qdzxpOKqQ zCUWfwaRwj-4Ey|ba!bvUV+1Zz3wo({;eVT+6{h+PBzneE*S+r-teU%Wm35wDHIAnO zuIoAOn~yUxxz=KW2AnVNr7wG7(+-{B;9mImUwksie#WhG915F)?y2!&}k8{K*>l?zJ#j2u$8I%1&`~e@F`xPv?oZUOo>7j>3OGJ3f>wI^SqeN zR7Sm=w6V^0EdhS1{Gm>tPMWv!*)2(f*=e{WaP#NgcAradu5voUHx476GoNzR)>1x> zMq<@102sgTc3ZAaFb>LZ=k_IK;J%v&V-8MO1^q~Q^fXm9Co?misBD`*`|xqcNq9N2 z+0T|#OJ98Q`(}Z7P#G#KBWa<9meR^b>dJ%)SK@vwhw7QtyX$j32tSftjmKq=cQvVp z_u~yvnt(50n7s07FKhq0BiRCgQQ{ABcPz5%^(~trr*z2V50r+Cp)Na@U?}`0m5JXO z>x!AGZJC!~?Q-Iys|aYl%l^qE5AZD`2ztP^h<1B+E6{!`PE`Ec<>&cI7EnFGO42u6 z4`k`P4{^}ns;xjCE34^md=_YS2MJn#-)aG0lk3&hb1$Z8iQ3lcbuCo2*?f6Ef8&Ee z(PL4K7ejs3?1^&{|6B0wx2T6q7sYbm?fjQqW(&5!y1kZvW;@i5k84#tJQ}jbIZ`+2 z%~MpF6xJ6y{Jn=3J-&yuU}1r>r|h#|C6aOl*~rcsdZkwIr}lw8`fEd_5~UCH8ztE=$tfH0smWDO%xUpXd5;6gZ;8B3eM$FSa(Gmx>hMMAa`a?4S5+ zD4&}e$wF~y^#5{({s9$CFN?L@Ax##N1OR8d$gc~*kLkBm&22LWzoOz^-`U z$U(d(fw2C#_BGMx^nv;2@U0=iW&)FM&-MwGP{4+yhb+!{YA>VcVi-Di)c^j-*6G@# z!C{sM=G)mNVdJ?lf8}Pg4>Xo}gNy_CGkDX7edJJ$eCvDr6H7Nn&<+GJd&`i0ysI-2 zbiyqzH7w>c?<}(uqS4)Mk5@V@S~(SKIeRu-{zRm${-;{OpPKiXgpj!NOQ3WDctM@o zkQy)w*hqYS&Mm3|T9v`efsBpqO$`+>WtyH>Y6>*NT~xNGJMUG}IIPH%>*D4L_z=dk z&1yHFYGTjts#}4!3;+-C38 zx7i1iO7P1hMkDJ=LQ)i^?n8bW(~W;(v&68`X?PXf6j$RG9wHyLdalEW@;_3+j;yMsmL4gwXCZih6n{|88!? zIDK-ac@|f+KS^}eygQL_MW59i>=^*OrMJdNvE~#n5n${J=N8mT2z|`M|JL( zPMgV!+JFrWGi|cgMWx(sIakLT5>WX^k!gy3?=QNufCsAec@oXxbziM!a+q>@sa8v0 zu>&9pjo_PFZzy7Eo%zl$OEg2%@ldj~3VhRk+QQNApIFd#tmzYG-ii*lLC^3=2c0oiK*7r#kIwm6F0kNrLpS zeURe{uiOHs*`T0p?ezK9G^uiWi4rZ3J=#+rc4svMP{z0qeKv##1=%5JH+S-L^1P~M zrIUUrUu~%`;-F^%s!UavW|4#LWc_$oMPq`YN(g8Fw(H)sMFrCEX%JdK~QK4o-)(9B8Ut4)Uy;E)-jmmD3*%)nj~9J z+R4Up!ciyfHzQeXPJr#&;q9*Upl#FAYXhjb3ze9lj>#;SAvr?!`+wyxF@{$kZ|h#o zOOP(on|N(oqfheD^d!|rdE%(k!stwqK21FDvo-#NhHd^=Yiw^YtcsVvg0xu;fx`PT$KlkEr)wI}x0DuQ37BNprFu`MPs;j6C55KJ zDlo|nYK8#H%C7s>SC({2+?K|%Vy?l69#TC5WvUM=CPa`!`b}vjM!x#Pm1i#t9BVc8 ztHgo`Wn)7tYq-3${ktUG&CJdB{T#prY0iDV~L}9kL6}EBQK!85fN$`ig3{;`05%?Ofia_KAYi5_9BZxiv|9#o%j+h-W~oO&cprqk|=ws?QAXBA;7Fx_{j3zSDbsE(`+zK98Co^Q`O$t%Ci;yB~geSHSY!q;dhFkxNle3 z2882CfMLgLwH0qHbLxSafD2Eb53QFZRvmj1uII&=#Nk4zN`@b1u)a?}d5!2u31Jpw zNbU=ma;GH=Y@S;r;-B+%^TGeqV?ANt^14V_`;jS5md>1&W@_NL9`f>^E_^<{*c%{- z@=cIlA71Kwt!bF1GA?r2ZY(}FrtU=!xMW;YZ8%E3ZT52gv)U!Nv!t31l!1Ncl%j2o zNdtM{7$HIQ7@cNc~YK%~&!o=QWj+)P_wQ%Ysp zBKkv~b^jZ+09<$RZ-Lw+6)kCgA04W7;pYwEIAX)1VJl&acQv0q!%6N9B?(Kb-|toagO4U;p)-|5-r@uIARvG&ulMFG`nDR4}gp?P@kplV}1=%z8{;f&~K6+YCBOuAfl zrvk$>)XQF;kz`e z%7(hPmBc>7UrvYE`DqZ6Yj0}+u&sYP3fx=&dwxJ!LVP?#Hu=7_V(XU|6Q_s4=W+Zm zz-*oYt4xl-6%cC8PZPtvWBO1%#wAw`rxK_Y>?&iiI_+=KiM431iTY$GUC@gjE5F0q zmVu!svu?aE^pk;&?G2*dh(P95dtBcxfLtGypwUXDPI)MO?(9t24~(aLI7QBCjh?JH`-% z3iI|K8hjrhHa&9^s&kjnHGOYrkhQ016#SU~lRoA;ssGkfh)sF7cTt_9I!j}9EPLj@ zGm|uQE7KksCWYEYBi+v%C3R&)*=-RHVgZCB7358VUb4 zVJ~B>^6+ug_Y5fS(ZBfkNFkG}elxxs@fvtpjp%sX7D{hHMT6F2ac=?ozC9f7_<2`0 zJBA<}UCzk=-UXqk@!ek@p?qHYl_9 zBu7m9gz4XZFB;D}*p|hgp22D2;;v1(Z8_G|t{u%$-@Xo-{J|ll2(~{15q9kCn%`U8Q(w9%Kil)}sARfox6=A!Z1+0vP-THJnh~Q*jeiXR?Fbs*j zZfx;~zRt5;NSwx@%SIzNFUot(C4x&m>>2zdzK5@Dp~j4n@aLgdK|=QI%xdn`dJW1P z6u$|Uu!`lj4HK45lkm`oPJ=l#JML3^TgW};e;LHxmW$qSuc^6>rqsm=lor4jD!}@p zt}p?tbCfQVv&FkDi0rICiS6$#Km2%E$dJ$QlDzAD*1 zo|;9>)9a&z2*X)*jI%wKz%q8aoOy*r)UiI=#tLZLJ$f-s~JiasMSfNqznpDL8wVl2>ITW_Crjo+y(iZWFGE#+=yWK)vpC?yiJJG z{2`~C#S5)P%6uU6Q9rx2q*OHGYN9|nL^KU+y?x;eF3oK|xAp$5W@=p=kdj(w@gcw< z{xb(SG3R9hN$2V-D5GgW-#f#p&aHi>Agj21Od~OLHau8foFJH+<AXR zduRtlOS~Rv`lY($W<1VWZM zZSo~;6oY8(TJtY? zcFN}oG358$iAcFGe;4QFhVK|zIvm$nke|lu8m*>RRz1Mmre^yi+T%@ndH0JXlhWDo z=z}*61E1JnN>TH;iR2hvD=|#Om-~AjMM=CTeb7r6tO|S;DcR?-PY?mOc5xQf^sEFb z@Ll1k(huhr*p!Tes+KM3G}w4G^AE|iwXY5ju8^U{UGZC?T~rll8bi6e1=x5ce?kCj zQJ= zJ;GE{8P)5NR3R?>rUm5+Lxc~_pbX)D&QG455T`k@wnTRJ(*#Fd>$}Q4`f^0y95LQi z{&R+OenB=NK+EL2<(g*-PjW)Jcw}k6&VN)m8Wly`ve4cluO$-Cm{y z3H-4IHaj$~bb@WbaQ4TZ85-bgzHH-J5}DCifMDntV(0kMa9B!Q zo=*!vsMjdkeZ|XoivrphV+nxi#cq<58fIy@Tsq--kYI_ z4-JOtA6sa{U@u>b=uwNIaNk$~TEWw6X^SDabQ3+W42WVr$p6j2r2zLfQY%kCFYhwe z{6T!~Np5Wm#_nx!O&q`8Q!ezS@3PzEGNkcb3gm3VB7AIr+XLpH`iezM`aM!t0>Wc2 z=_HpD-%qf56C_V0gFtUW1UIR42P7pE?x-H5(JgdUomvhl9o zJj!F-4=DuIg@8O56O_00TzSUJ58)E}XRed-wp8 zr7H!#EI$6iv5<1*r&B63HuF#VED$T*V&q6ZB1`d`V zT|)z?mr#n0RR$v_66A+&;vI9Eih(bPov@z4zA_W~8d!mVp+Qtq)pQchjqc15)%3NA z4?lD(eiFBAtGTF|e_O1}NrTM*sTF)MgiZqwSH`a2A_@#*{wSxSlr)uw(^PLpQ&t#)YI`Xqc7)8HbBa z>_=^a)Ua6>7yGd^@Hx!*keNIHm|+a;RdrW#Zi4M2GxQq0FXwO3%1YRUVqC-$TB_|Dk4HyzrSCZxfrU`oS2#UK##k*5DluKt= z{GwO+R3T9E{?7hGB6w8g%J*<*#54P;{itmFbs=F1r|_ZciqC92>)!OMW#qqxi&`p| ztX_suwHvrdGJ!7N7>r0H2^iKskn55LW_(-{bU(?Cqt^BAi?D4dIeRC8c52J7J#!J_4gy0Bxgebz9GMZ&GiV z@WKTME1OA^E(yQe56N-$rbIY`w#!r6t-aY*^>UF|cd`@x91tC6%k2U#=>$ zd1XS{i36ezwzU4<9ID`f@QL14rqG#|=_QcP=K!O5tk*Sb6m?Bz%XTDF({Cw`86hai ze|Sk^sRW?__4ixpqegwO>?m&(q%P%zv?9IaB1dDrJPnqVNiDxX@&m2SeS~ym!^&wK zD6(3)X|HK7qda@!tEl#f`zX&Y>>F7VFWMf4YsVgS2$3^NakJ(W907yIrr<6Yo59jn zMI3$OW!Tk0KA&Np$eeK}83J>a|27^?H0d^Tf&L3=b)1=j9nnNp0mz_$FUM|EkE)6= zH)ZwUimlz-f_!fd!Id1F2$bqA}iLMbQ;7-;Vp%N|RNz=K`oeU7(Uk>ElLD{*a$0xHzgP3dsSJhULR%DCTgpZmey?aD8#VQF&PTxKEU2Kgv6>O zF!nGk&Q@wdAQeezT(yztahEma@+ZIIdc5&?I)CPI-}fn&*U+#?MOUd^+s-UEv>xqG zA1$?@5%(Uo1DOy^f4qD0ES_YxqJs%OZ2UQ1>*7ihuA&RefX*~Jpp>QW*XLt;{2Q8j zJ*9_km(k5D&Zm?DK6D5+v+@S^JuHP3?X1-g_FN@8fqGUsFsJnC2v-lBN22?#NdxfW2S4^vvs(|B*gE1dag5$ zg zq3~jRyB{N?;Q#|a6z1+3yl-bx*uE_dm{F@2ke`rqX$O3#YVEkuTrsVx%?ELI;~N0g5ii$O|U+A0qPw zPmwN@FS#Rx9<>j6PW4u2uR@;Gf4a?A<&JhA`GOMS&80^s8))K4n|=e4O%mIx1V4r? zdqD_N-seE!;Vtmij6Gjez(dAY_4@C3%qVtO=R&!^tQl}6rzZpRZt%*}0|QSYn5LF( zyZmF8e{G?k+T~z-Mjq)%1{EvBUt^T=@n1*zVa1Lw^_R(eYni^qEFaLWX0h#<@Y2b* zhg;J@a(2095#$M!{vwP@Y>ptC)P6g?_~(bXjDG%51wtQLrrr&xzN+r&C&F)pfBfmU zd0X7&hHBqklw{gQTny~iMPY#?E=9mDk)U`^&0vm}77%$#ITdT3;---wouo=@Kv0m^ zPUk2*glPe@s85|OhhC)D7gHYLGd0u}Q7PSs=Y%wF3q{j`Gi-DK^(_&$(nX?DUIC?& zpOW8TF-8!p$8mu@C%M~YgX}dTXdtZ;ttayTc5i3?Lb64(Pc)e#4lK5iniE$^zKVhM zhCpLMA0J79l=gun>~uSt;hKvo=MC?VQ{J0bGIfux6AAm6*9v4);NP=J>H^P5dOTGZe~o*Q%A|>TU^(6x3uR4ywn5nM+%76i zo1xs&b6kCl(7*GvWePu`a_XU9gL}N+8iC~Kv)4UpN~&AJ6h-irz)Qaed=`HSvAW#s zLk=!busV1=^8hp)RU*=SCzYh`8vbmd!P*``@(`~5MIlEWvf8fZnhWg56lj^I#{{Xvc$A;)xr zU@i3Ums+bne%=?aTMw0U&O0ZCAtJWb6S|K5IO zM^Np)RdPCyKUu#Nwk&KuYo*S?Fh}6~(mO@hQ&T@5MD>IXsgu7z=D zu|XxP@rRZyh;Kw>9IYfGp1yl)Og8#((Q821Bh}Ns1pnx{PWU)7Lv(8bOsLCk)IqQ$ zPzQue0x0CUuneyAWqsarXh7<(kh|NXQM_C_M9=<3lBzWM*S+iEZ8<~_y%L)`e)SZAS@>`Al8^fQ zwW-WTHI?Xvv^ZwAwsJCe$2ps@=;|s9K3gVhtU+xjkRBryock4H`;3rfm9~Bom(TgG zATv^I(Xw!)&D_!fm=XH=DJQ+9H4)slw#CjmQ|WLd1ID;{PadRY-xT~nXXmFC1&#yW znvpN!3&J~*C|1RMvW|HZH7j-y3v7`S3~Pjvg}tsZ2i-jPdS(+`72=r7%lUg)U?LkC z@P^IKb_!=$%9!mYQO zaKy%jnXQD9+k>TinjCSe>AtYqP3?8<=oc1hA(rf~Ft% zng{#t=v-UEW@~MT)mn8ED@mK&ope+@?w!0O93;8{zZF>sb!AL~#f`bUPA;J;^{6Cl zWhTNE$Cu=<%gaWm?^3;fhJpe}lSM^D99|^1;?pEFF!v7inDaoy0?9&9rc%!(jvuQi z$q1jagmen*#bGtj(fMc^e`+Vi***0AlH^Hfi*vc4M zL&jC3U8T=-U(#_cRsb;XBIX8nia83lP5CWX%Gl4|ut$+g1lTiswB?_?*1D-Fe|rrZ zMG@zry;E4DObbBCy9ugXP4w_toWEFM@_YPw##+SQDzM%_O&u1b$(kMMO;pJDnL8>T zYhg+LK!>9SWKfs=U~xS81BnW7ANCeLZ=+p&Y)vImPZnsu+GsREZ4j5V&9_c-P3rH_ zlC%fkE3UB>_FG+pS}8tInO{XkrOj2#wo=0x+5X$PuF7?o9?}QkWQ7Y%gY6m1+f8f0 zgfA1KdfPOWM-rx;M0K;q;YCWA`D#&dqUL#NTBs=l>Lee{cHn<1Eti-rv0t~RMhgIB zn~>91ZmUVTLD4fzwcctGVs@3ne5EXoc(4M4BvxaWK00mrfmD29kUfRq2PEuv3cqK{D# zV{&!iW`DGfaT$#Bf0}=vc#rn*sh~Gq{Ld@K2-W?IsOM~S&IX@cltHgvgrtwmZH)$f zyGFVsc56-U?M0)X%HwKvxh2(sTjoO-bOMVyhqcHaX5aC6$wCm<@XdQtLq}n*iVS(67PL4Yd+f>m;WzWychis}aJ8U+2us z^9@_KGpTK#JAr?IaSSjpmaF>M6}|7zs}7(4K;RpZSA_M}X)1U0T^tD!EfJpT3zgo`_&RJBj*cOS11)y+ z=^<-y2o|uqlF-=9NWU`f!KR^hJd%G(!m6?n8De7zA{k@8PDPZC5xUbJs^A_hR!|GH z1KJ0FF@rfCxYYqE=wFmpHQHU*wyd4q&PxikSew+jTZIM(y7i*U{_{ptriJUo&=ztI znG01%X`rat-6k}7L-opuB&~z=O&Oo)r7LYxJa*%|eX9D2L9#EeA6MZVo~LuvIy-sB z2|mHp^K%jaV4=NhS;xUcgW(n=Ep~&g!6fG%#*UXL5DqY0@zyeQ9fa6EjM>%9MN!R* zaL6SEd~otAGq>NDmTKYt*^vLLM2#(z)~@_`@4be)==DB&cWgV-FP8R)pBL^xE9s)9Horlf2d} zs!qG>S#q9=p^sHR3Ni@E?WsgHbne%!BWc&6%KBq}&eG@TlW;EznJ7m!4_;ufoyb{q z9hJ8EB8*n?BtP|601amLRm4jL?K(ck^%NUdPLNCIhUFus_UC~>Y0{FXTg=jPvGnvs z^>i2#J{mvg5FBC8l4~x4#VsmskrX5WPN5J^w?Xw%jd6p5Z~$85ye!?IHv2=hmWHcC zCN`8ANg&Z2rv1)nB-li*|7$?dHs&!d8#$I=?-`<+MtYXFrta}y&N3ZtNHRTp12e~> z9LSqxmo3cg)nr2kLhUGgnX&$AuBlf*DaYb8K-3hSBM8>%FISPaC#-pU;A{KnD&Qst zFdjTf4Kxi{uq6`InZTB5DdyWDZeriI`fOskGuDnz%fbBqr!(j{bp1M@mgrE6ILz8O%p~`|`T5tfJB=%FYNx9Yi@-wy9Vga=Sn7O@Bf!s}7 zCXrd6{Kx5wZ3g_8$FEIP<^#j&6k2Nm^>rS_&7>!b9RxcKCfrgoQ$pdV?UD0JP$n937@OLc;pV zknqSSyqQ8@W&QV+dK9Ns&;wI(;)(pV zk^)(X%7a-t4A&*SZ{?ngJ$nSTExf#ZYR9kb$4o!y=F4eY3%~HWa=5FK$H{hb6Dg0t ztVp$E5&@MhTtI$z`dEbJqqO2gLRC=NSRJ$y<1KYKzj^*^CpOLd?Cz9Qy2!e|DKeJ~ z>D$3GKaCuytm7K1nlfy0)ziMY!7U&QyhZP3>jto5wY zHa)#b_c8D=Nw#93WUiG7$ z)fsYv<~3u@$W2(8K8A&NUi~*f32-y3YYW+(S+_Lepwe)8%5e8J4-A&GWe%eB-~5v{ z?~Y#5CBMfJvO1cK^)6)h6;jxZ```igs%60GThyf?ZOL(tHQEjIq(HozjG)VI6z3l7 z1r4#`A>hs!@X#>amdey;|$YC{MiWE@w;q)9XGCTfX&c zFoP|t{^EEkIp0|2W%8B=PCIydBHsxUYh*Y1%fO*=RB!DYdO{{XjZlB{dO6FVn_N3e zlIsCk2|^3j{bxhElZY{OPM~0Dc=lPVX>lT-wU3?t?CXMC4pRSf0YuNTS@W^kGIKz+ z;Y7~=OtxBKQ_P6{;neVC&Ub%QtbiQ@pa%1pkzx&Lo=P@7hkHp*+xKMN#9s}DZ%)!W z5uLE{z)ot-S%X5{Yi+Jk+u~s^FV9)~ab<=T6Qra^_l|g%2f}T>D;OZfj^wunY9UB} zPDm+H(0vY2r&!1WPCg2wS0HFNT-ESMR}=YrpW=+gTp8=|g$;g%=5vr<1QNpTGWl-VA|inAqKYRDzZX-=!S# z-*M|1R{W#mc?G?Wb^pq9(DMh+oVJ!2QdqQbRWf8errNrwF3i=NOXBmLV0Nc445#@U zCO7|zd(*Sz_I1Ty&Z&IHqd-Dh5HG`+&Ams5GpNB4uFunmkfIvzpdhK(=neYxm(uuA zrIDeb|HyAGeqvSMYSs^CFpbSN-uv&)x8>@+a5>Z6Tb$~T-cMaUAu04eqG5gNel2h3 z7Z{oHk;-{nc$q2}FU>iKkI|rIMKLD)R-!wrJ=#txZ*6kQd$DfgBK?wT|B+F5` zR=s7m&ky5cMVsFzcJHs>oCJDv-HeZ|-Rw!=4@HOiS@pNAU-Pzq%{fcm^8Qrwveu%e z{-!ftfPh=UjUwEz>6d%XYOr|5>xB5jQDv?+y7}!DTCT#MkuttXjFI;xtDg$GeA4Nb zFqy~bn5N@BunCP=sVbs6o+r_B_l>_`{MrxFe*2(nPhgdJmF>(cMISG}{we;s|G7QJ zwN(HTZNtU#33!-A15BZhw-#9>droJt>t9=E#&_RVb&wA@i_XHi;Ye6D#=yxl_Q+4$ zV+t>YNt*lO3V&&gUdRp?76p{XS7nIr)L58YnYr+i&~MLPe>}k-=P@xU&nf!JUYU4w zj7EI4J&+h>_lvIfbN8UI_RGtwL!nxpNpHrK2E@9IE7|vh;gOHoqcrD z@&$v;BB%K~Or-wHu*wlPk90wPm5F}S8(uD9zNp>qx-9YjC*BRdheUnsTcw#hZvvBi zHyltQg6k*9=?kqMj_Dg8{D3cg1*?k+7pOP&D9m;#OYr03#3c~7D&0l{o88C{E7 zy>nQ0CN3=tDCxUL^1!;!dj$TVbDa7$?@ETC&oixpC-ipmcJZLlYmKq1D90;+30Y0e z+GoO!PT^W*xN=JiUhSxJ!ZiWKced3d*XSUaCrehPQw82?V;AqcE&fOR>URlS@t=aE ztu0|m&)$TRviWq-@%hXsxeDbZTY^KAdr=oycVkO8P1kvus8Z1kfm2`ThK^q+wlKo55b@&X+`6Yx5sLv#2=; z1)7xW`bg(gN;2F>aAg{05OGVVijlQ=Wi?u6ob26X2cPNSk`lhC*eUKgIHSwIo6O#{@ z`}0FdT5QoZ4Ek4LnKmd|f!$TCcDSmZZ0X;Kn!r%83AzE&pH1nD#FSFF9Kqt7-_b56q&`6DM>4)(}sSsK6)roYp`>U0NC)>V;JT1q!A1*FQ`HK_ zt%ih=ng1H2K28oHio+FzF3kg>Ck+ zz3%I0LGpFa?P@(}ChtQM4^^yJph-%dM`Hk6FFO1AF?Fz&QYLJtN=4s2qpL(rwN>aL z!GCn@Y-UUNY}ZyO7^&5>=?H9=n^_~p(b;!l z;pF6THbj(DkPzHCS?()F^;aTIqh&ZhUGRJ7)^6EODyhtp{&PSfNGi^opBaHT?<0`1 zEdhf~`2KPU)wy4$j{c7yI-6KPUc?;YyV2sV*r|EI+#bP7o!<+S?5RG_ymQq&oAV6j za+xz5$jH9)Fkl@288oget<0&uAq1()z565o8EDKC5_kr}6?gN0=^CxLHPtgVy5!De zO_ggyDe`j&sDkJ?dc#73-1mVxb&D%&q-3#1+)0=7=Jx4r31denje$Ph=q2Dj%^El| zTT2K{e=cMfVpBV!#BslXS}j{J`Qb~y&3r7EZc=z2>m(fulLMb>Nk->-{=Jl)%L?6; zDguD?>ZYtT#Y6+(?qfDP@{6W4pHjjq3*6P7(h()BHsDW9M6$8nx zh5NsBgC)&f4p|wk?hkRkOZ!t)^GKI@R8>XP;dPfvSw} zYH|$@DU4-+KOe*fUZ5kFyz&uaANT?s7;DD}y?9|?fu+B)%Fo-spJ<73Ey9<+R87WUH z)u1v51s^BA#Jz6nQ+_?S(Q=C*JG+|W&Aau(RAeqDWPcX{k(1%}L1~iKTk*q-rPrHW z;=Hl(B{(K*j_=)vdJ^4^u+_G%x-fuzoaGL1G0rzVxYjk2*GWuCpWN+7Mpov32?dq{ zS<3T|P6(yNR{+cP8?MQgF~8kX7_ovHWB2Nis?{_WZ8fEb_yO2JJjyvDPpP4{dp=LF zKe1A&{UAQYBs^+>-!S^wg2*HN_+MHBrbNSx^Ya)Fns`qYL!f$8VR#xL5A$4djRE%P zbfM=?L4#DsvVqY|y$~dnHD#5%M=@* zQeM@NwV0}w-}vP#)lT#F5d`9eFwkiYgkypuVP9_Dj;IY+Mi1&5pP4Q$FH!nlM;5R~ zuPpf|;fh?RlAo_N627wKHGYbZof=)>pB)LZ|Db7V+oPXQ`~ zo-UhsbBrWi)n3A2Ann7kL;L0KT;R(q<<5k0NL}V-C2++T>^t^`3t%<3B*9kg8~sRa zJf$Lc%DT-)Q@X8f{SxC{MQLClv4c3nAw^`t^)!M`%HOOJ9 zL`|L`1v~Cc$cMg_4r%&v{DVH{s3V~y6Lp7egKv3wfi1uMS;_l?Pf1Jl|Lq1;vrBIe zOs5K^TMSeto~`MiI_yqVg`F?A1Rw_vSX&Xeo(bml(PZz7iIOw-Uw^-&iEdBJ1y>l! zuc>Zl6_M@7gnUZIM-JTfP?!nC_kI@9mBivPhgW)j*Aj;%oy2N?^Y+SDrENJ+4FTc3 zeCg*!b+(w^uvfGRTtyE3*jSNsnhMZB%1^jG0lon^tkE7g%oVLQXv{4_ zpt+QAM$6?W1JvgB5XTwj(QIT?s0PnLa-B|m8ujB)pxLEgJ$$>Hy5AqWs!(g2E!)bP zXOaS>dbc{dc>Xde6F5R763aw0zU4kxVm1wbNE6J!NUc^~x_NW!ia;zHVs*Yh+hBJ% z^h3_UP8v8XlXil$TV|xwn#9SLgci!J6iAI-^7RGcix(%yWZuCOK*@y3*%}9n`6{b5 z(=`7u7rKsAL$%PASal6MMD6(TU+q+7LG>KEKb1O%(#0@V(I*8HINgt0e31~Q^zD?e zVU4Ihizrv@^$tbkM0%8IGb~O`&T`n#7}S@0AdS{A=6~O6B7Id{HfcYuiCtwyLhPN^ zAIc^7IhOHLwyzQqF{+4;{K+lcxrJs`8&5APx?`ma3vmk-DYZ*RE;a+~bJ(klLsIWx zVJo0q^xj;x%lTd_1D5)&g_2%*=7Mc1vmC$Xu0)kKNShgIlD{co7z9cxXz4v?0D>*z ziIJAK_ig&|&VEr&j3t=o2ug(MP z8G5;T%~D}8Uu$(ewYzO#o0J2?nH^~#vp<^4v%vQT!Z^dkb z9loLxO7Ub^>CNP8%)h)>|MDe!=;AVTqCF^aw#Iq!Rl~=W*s&7%yj)4Gt)dvUeG`j? zuL4tc_)%}1Zh>Sh5}mIF#3~&RTkn+`+j05eJ4>ktE=cLrBt6KpnmOQJfp!ocTxHCd zO^Au1)hD7+$1v5ozvj=Er7`3Z2!Nx`rd!lYZ&>)Q7A+V7_A`_%Xw&~{lBqtTlQ1{l zLdbn{<8g77E*3KtM=BWFk!DyrA55_tFD>*YvE{-eWpCL{UduNMfn9e!hXBm-RzBO8 zOd%8W?SjUvT5#WF>5f+T1_)WF_v0jz@paC$a+q5--f;48auu+!6CazDs_n>-T!gny zvZL5iHM($5224w=5Ac{-%C@#aXHm}S7fA_0il6y6<8tOcfI1#_n?bnUZ8tyfN?Rf< z=5+;SqE}L8a(|C;Pl8^}8lAY;2K#c7UuDk$A6w9bV9_}`ZKAa~%jh*6jiy?hlo^b> z4QzHjthMWk_tS{Gwd2Lf^Y{Uu=XYxrS#?|JGou|augK416~s>OTC&uGai$!*OR1-J zI)IX5pD5ju*`Hd9F8KK^k!xIe<7~yto(4YQMS;o#P}yBkeoe)^Cu~Lp1p})Y;i&lA zM)b2SGm0YB0f~JDnL3CUu`s9r5htnnE5%zpRf{FYQPgmyD%W}qGX)o&NF5@MqLor66O^!zz-JZy_?8Mm6EByd)V1)zcq(lzej9b@Pt8>Pk z#bX^8GQkz^q<-p;4D^ZXzdM@xV+}44?6?_q3>-}~-svRQof7QNB5rp*19>Vv#L+kQ z9hH2mA*HQNz!1>VRJ!~?H;XyC>E$x5?iv6|(vVZV1*sG2S!auvYt(>`N5sS|xqBgb? zy6TB$%{TIz@JUa|Rddt{)yECYoGFg`GK6I9KGzw5f}!W1?b~*uZEsUb?UD%eAq-yp zDi^4G#G9P<(#{+{j@mYDYZrph?9IMSdbfebebG>&a!5%$jR!+cKtVoRFRsLFjs$d-{6@(J^tM6NG2nsCZOnLy%dZX=s@)%Qez*oh` zUMw)T`#@yar_9#=b#77wxlCc?{uKzC+QBoSNZiw2M9sk>cU$ENzm*~y5a}RgI~^p5 zzby1$y9H|p;J^f(TOW`{cG5^G&x?RVYiUMfn zXDD!!TbAcSiKs5K{CkSex6wDpI<7_sc37Is=4UxMY>e&tD9MeU7F$BCabE46IMa{$ znRR7$jA*;SuJPwN`A2)xI(r$dH?n8yh;u zZ%#f7U>}@Yk?rLxL9O7k%kqaM;Nbiqzjzf8couOcy0W2ZyrJHP3 zMV1;jNhy{FlU&v1EcTnmkQN&td+O6$*m=CQuGjh||By+3hvK-&DOv2bq2-Cce4D{w zM@e6Nj&X&F)?IU;J>#<4J`P7lN6wt+yh(SuMY^r-lKAavXNIvNW_!-n`8p~pf?NV@ zbk^n}aeW5O+NAbf1U1;f^!bx+O)M6bGB>}u|ln?Avj3%MVgh?vneZs4nyEOg#KC#_* zbPDdX8Hm4aFJ22SXB|DC2IShn<{33ju#kjUrO@J+- z#j-uYgDV!#Z4S$Hg2{ac!}`YkJ%HW>&b9vlS*W5$&#y>18;ba3N~#OJn5~mWWExr< zcyBn@&UY;p4bm_f4dwt!up*4a#_li+6V8*;u4 z5pH3ux_e{1rk3ElK@+ApCm$wLMdmZr-7s-yL7-~Z)-TGkpkS~RU`DvgVAGkK+J72y z<)GJUrrMI38H4*A6b4;<$E-gzyimcW`Z|~<*kfsD7u9@cOrKO0m&(p%$$^km5%`Kd zc|DwW)CHn+s2y**8@j1^{6Gj-uFp&E`4)wK`fgr*swug`KvKc}vWSHge`jUTahQ7( zKjsc|%At7|+w5tN3U$_f3_|idGYQUu6blJXYllIOA3%DDt#FMJQDX{khvsY+ET&W0 zI!O}>hpeE*^JesYd~lXCVKHN-yA3XjhJsY9z82owbJxOey7>Wg8OAOsD+-r!a^ynt zA2$QtLlD-l#JI7;=4f+~r8=KkeuS<_xFv}1jZ4Cr&NaUXGQ?fM`wTyeG!Rtc`kX*m z8N-46^POM9p$C)vK5$+MWLj`G!{J|(u2A8=8sSqT%HG^wa#gu)qKTwf!D2wcy10af za9$zXU}frrEXVR{#%V8MbRRvqUMi$WNocb4Ks?H)U8DQ)^$mFL1?U^%|wr=2Xx=1-4?X9MuqLnF|?%IBH6)q5T@>Y~VXIl90`6+WjMpgL$ zh=r?QTOcI!Af&fCVj3)g9Wk2_F!#si$gy9DDlo6P+2TyHv$hpnjML&u6Oh`GpCIqb z)NMa*=;x$xoeMv$W(?C9TPpupcPO;<=XATGRYWbhaa*I;F*WX`w7-0=cGD5)_Y3YK zh()O;sc$=Ih`_V`dJ@iWbc7X|G-r`W@ua;1@AfOQa?gc>U=nPMb!^aL%t%) zbhaieb$k5&aNt6|0MT?TqrT3Z)a7eeER)OFOqC6lX(DW7#Ik?CqLliv#Ekb39Hv~# zY?(yN4_yt_S4D2B%4Fvn~r9$W02hA=X4FChv7$y;4Wy8>L;-W_p|PU5U9YH}!^&)xrm zMc(DpPQE~5$*+xU3`qrYc=P4S=`inpwkB;42jF?nsFm*V0H8*w0g(37<$7+`#bG%> zIy=Uo`RAbcdOn8LI)~aQ7}+`|y1J%wq+mYc2T}z#cS@!9_86J`{ttADBlo63d=7_1 zChk!lYbI0q=_>^*3K-e+7iS1!am;4brAEVF`&ZK0i3=GEG9*c``ZefM%$d@R%dV2a z=ekd`dG@hPBbB3i2sv zBEuP8Gf`dP1H~svfdH?U+y=Y#U z+^`th{rcHxuEsbe)Pw)Bv@g4Eh=`ek>IE1-nKA2g2*SB1g)CJ z^{OC@vM#Lwj}zlQ_}BsW_wPAx{#+^K1mH>U$rJ+Ju(hU-R8w;)^0qN4ixeb8d`4ZK z&m7OlMoQdp6dWt(ibkc&OJlL>d(Z9RRBV^db%w!UmrC{6GtdE>C|w^}=~V(*+3M1dL31a`?S3a@QP9>n~!z(Y*mw ze|@oRsm5URbVOzuT#Oam#W_xBJKuUjo(FHYyzQNCe|L){qi3uYFAKmS-+`?~7*b#6}aE=U){A$-5K{s2t(r9H1+R^u6i{zO_^TBEL_8 zq3b8V;KG|$f2>v~@{I1d3M}8LiuL|5a$UxNb3_{DN>jFO_y10N;wqSkr2}uBj&6P& z%dl&1#ARwH^Zhtp?gLdm30i8s4n=Z7CFHi1T&Ak!w_c^wtQDagjhU9`t+79>VKJL) zcNg!H&$s6iji8PUZ&-y9TUkQvj#rN;S7G3z1(J*}^I z$-HMckJcxV*6CWe9KTfG{6NH{eOnxsrPv^2K~uY*N`w#k@Y4Mj7*Qcx5~iHW;(v6{ zJZ5hlUophz6>lNwxD?P|v(jCp#%?|PbE)GjED~L2Cp>x$Q3`^|gaetq1rpgD&Suip z#!12mmlL=(fP7V7s+z19a8-T`jpR#;EVYIi&}!8=U+TLaeIGJFMd(b-;q?j!my9l4 z(ui8$-~2$rGM}q+iJD>}{(5y1^D(VIn1NctjRY4Y_v1$y$;#d2`u;$;A9j-M=I~eK zUJOjkZw`jvW##iZSvPy`bTg$jF80~fKRF$(P|36vpC%T+_zfH>u!;mKjsj_?F~?$q zTe=PUG;5rXw*s!iWi+ur>UGC3FftNWGpY)$_1Ga0`zq1JH&|}&&8j(M8`Qz-^#pVC z|D;a-^2G~m9gse!3hykgAO+HX<=O!ZyRgO{D3*1t%Z*tx6SQ-jFtwcZF0~p}zYM65 zV39;N#rZuCNUDR&ac^$Br3c&dNurxNHGo_0u0P1SiDCL$q$c6dzohg9L}1Ur28 z$+!E1o(O+H8(8|@0T+Tw5Zqq0vROjJ_s!P>viTES03^Z{k1Ovvz7MfH-<#ct_BMPK zaluG|fpBspB?%*Yk=gIv;JGk26iFovPrS03=OQyWNRQe9xOxaaweV>CeDMT)Y=ar( zdI{Vej8H3*p_fk8C4>tFC7oHWDnEC7{vcf`I&(u)`(H*TE6!6%!; zY70;MZq!Oe=v-x=Sh7QvGL2c=bLB+~=M0Rhsi%E|mb(gCDA(O1uH00vhDUK=hG#z0 zGk4|QDqQan-KZe!RY=AAc{AOoi*V4M-ETU>a+dd=16-K(K&tzu;1tb5+1Ddj5pY_8IypdYwociV1_+p(R z=gOKDlxeZM@ZM|~R7q+ifRAk_y3z~_b^u}o9zeUCJ;E^LKOg6{Cxvz2r;S1qV-(h5 zLB&wz`D{+xM|ggSIpE#6$I{AD@|7_wZ$e7X!R~#w6k7a_Oij>hy&g5=%B_b&NstDk zE#A|hv5DFlgEFonF%NDar)IVxUHAmIb_Tt5%l+e-<`e}j_z%sOh~jCzyY%!qTf2`unI&IJMTT}B z0BM*08|IsMA%Mc#h)}Zf&F$5`-0%HZ+89meNP_5~==Ktiti8SVWq&ntSnQt!uVnsI zc`euvtz&-eE0S|j{VyR;8Yv z4(FYzfUwq+Q-tY73WZEq(Aq=R0#61#f*#zEgEdszer{`!gUI$2n9i%&QTlu}(D%KK zNZ-=*)avzO5#S|V`)_-gL27O%d;L0lj_3hxfGv!_56Qs1E&!N;w>m(L!fR<4()hcF zx}u)^wNXJVZ#SC@D$RmIBL+N(9DWfJ?7hqzFu0)?ru-#_R)3JHg{Y7~?yg#xagFQ| z!ggDE17?Bjqe0-eI@<2_X!Jh79z?TIrHvKu6+o6)7vqpKwrJc9&X(;jHaEnu;^XX? zZk%rfv$l{HI0=mm`A&B{M*ICVPWw^$ui`(~*?s6Ovc}buy4P14#f3OwAW-O8U-jNg z%RCD}yf`6_!s`miasvy}haxUFveQY(kU2v<3)F(E^5x08fdg0U^J+4b7{4j2Gi<17 zimYV^D<2ZRRj|P8DXBhUiy6kcl{tld5g!Ar6<;#aeZwq*3aK_knrOqWJIOLpTxfvPNX+nhHxoWw(dGYB=wc8Sh z*|j4|-x{CrzPmM@>rpZP zy=-B{ZTeks4eueLg2l_fgK1z_%vME z@|DTY)gggxWo%$+L~oK)>tB3(@LiV|9FMuxIMhFbQzG(VEsjNF>PBhfNeZ|WwWFpI6dns`W@I- z9j<%JL#f!{zN*J_L%yR~cI8=~0@R$ntO9SDaj3*HjWXe9p3h{<&BG~DD}d!``zqVX zrQ=zhZX~{K&3aLaCb?16h>m%~fLS0eAqZ%b5lXQo>?D!9vTFeh5=!bShA?8523dC= zlEZ=U(zm3!%1|WPT`zF&i=QK+_arUPhfSCh@;EKE++90Ix}Hmp#@Uy@*amO0>vKEz z;_!VFU+s+~aVZa$r)wwBsBv3f%iCs=(roKA+oLHO7nl@3+4}7aQ3xI&a)|-#bmaA; zraPw(nKy7V++BN)CmSLt5A{_*22R^24(viabG0#OOE1wE_6bie22(o>Z)t2}T??GM zrJ~IE6ONs=j=v7lFE)8D0;@_r7m{h**ZmiuQ* z@1E1BLlq*NFR#hS23Q(^^}G>sm=p*RiI$P6R!b)3a$GpFj?iBo_BQ=8y^U{mm_FEY zdSAMrJjh_tsrgphD``suqQXHyx%V7*DfIT(4%Y;-5dPGn2%6CcPM0u%K14y&AMsKL zX-&sgsvct80ohDoKU!o1yI+>U(_v}jWFewX(E4?drW&mg-9->iq~#NEJfETZ$id8K z$Ryx^qLCi9fu)w2>SBycBBs#NoNLU99nEw{DLi%6qw&bx0#JLXgZ{~if4?=^{W_dM z7Qn>c=qOM{6!&u>=wLr+V|e7NO|ey9VAuw zRp#3X)5pGcEk$TEAkP&>!-Sh8t!pVeeNYp!YvfImhdM9t`|plFYw&n@zl7t;?^!Tt z6xWWNtHKA!)xTrW{_fJmv9BY;Iqq*mAk0&_*p++N6^zlCC-CJanm~yLgWp>{Ky_W{ z?7a=@H@NK5)M+%G6mJyo!ZQVSS1m0J#^MS)lU5nTL2@~%J0H6Nf#QRo#p zuw(|{B7ydxCsX=H+%*)lk24dQVAgr#sC#P%vw?w?pBa8ixe<(A@P!;PdH}FPH$dl? z*9r!(L?gMooj|D$Auz*J&@ogGOa|lSlUtp^a7^dS{l-1oa4G${h1b}}+|r>%V(?51 z^Kl8t;%s*&yI%Lbg|s8v^Lyo<(=r?w6|WaMaO4#L(V+soGllrHDlNk00%w;!3e)E3 z{uD_K8S`bD52L;ON8=YfE)Lj+f`hP@uI7Kz>1JnViHK6Xe~XCwmTJSA@B2A1N;8T$%I*(y9T;~{e;OF1C;f|5{L6igA{W8(K-p} zI9YO-ojtmcGplmH5m_%BhI?rKpz7m&|CSyB;{SgP!UrjHRvoXyvvu(GL|pBa!p`&2XTH=lN34}K+G{-0m~4)d8>g0 zO^#({Ex+REP#vjv*_}yRUbbj>#DZpTL~_$)D6( z7JrXJX)>Qs$L3`D{lC6AeID)MiAB3B!uUD1)IBo3Dh+#SH16ukJ*IyzJ1jyzo1f@v zch_VhFn-A$9J>{y4c5JxK^wE20t*jO5i;{{?*~!4GyCj~{y}NqOOS+O~?%Dkz@WnDq{Cyes z|1>c3P8Q-_ZG3q?V`DplIt|0cuC#9c)wTe1AF((ne13OytctH7^^5y?+0)m6*v}8b78Rj_toX3jVZVgSrSci4P%~7mqSOu)5cK4XWw0qaVnr{6x zx}syaF$g#4B3Nmne5Nn+Cve{@x?(j*^ksg!jc|fL6#Jf zunt80Tics!dF)>KyzB2Bkf&M*#77D8_T1nrf1#$Wp0*e9I4__I$SMQK>T|N)H;m4F z_Osjnq$yue2a@s$4N>gp2hca5;G39FXTg$krc`Ze4i-%nTPGxd9X!k#grFAwL(e zopA2Vt-RG6GDhnjS2Ro2G1A$Wj%wj0!-Dc-b=nqkF%kmMj>L@j=8ZQmHYhIb=pM1a z8y9i_9SG~$%)VT(FkOXU;2l~x=0uIpla;aeZ;C-dL{OSi$n4svuwF$FR4)U$tDvCy z3EIBu$JnHp}e1***j8tN62_UF#F}-B-0T?as3o< z|KH(xumRyP{y(8PK!?aA$n&%9`cTRp{=gN|Eb+e=Eqq6y-5cCuzVk*~`X0o5W%YT} z$73A7V)zW;&Yu%8)g%Z19asN*W#%tKwdB?xHqZ>yu((N#>3eLVaOi2MrgJ<>0SKm9 z(H!WO_dh?wA^N<|{7v?lU5F4qfaTM_Bc;4Fq?fx*Vb>qThZKu>fCD@z!UGYTi{$OG%;YzZd}-#5;k44d_m33zgp+}i!e~>CQ&nItRa0`7{vT3w zDbRUavbJL@boA*T>wu%&L_vFO+ws+3w5SdSLNL^p<>neMePBIK0~LnlGZF; zY^kfWr0DPv!Dz^!BTU7C^YNj^;igbKVaQ*N_TGNMC>*+E{JZdfNIa6_|0wZ)l=wgCc;tcq-%^hnkUqYqhjatsDoIh z7wXMIU5@J1Uj_+1OoMMX-)L4@EwjI@Zhll9D^dQg!%1VmZZ0c*%~hst^IvCh{Bx_+ zKui_@L?%~do>oNfsV~Mz4OTyW)XORnpznKztKYaTU^k$2%&kwBR)7C@AF8r|JnzNc z-26dkK<&C!ED)LXdi);Fe0$J7L5&`{`(^CEmnl*5GB|7@9RlDf{`jq0U`8mAN1~<^ zHO)G;Pubgeq{JR?D?|kcHRc6YXlXBQ2n;=l>-;dQn z0Rxi*#hdh=;$PKRk4nTqK;F#5gZCnPX>S3PH^DB%k8l3fnn5?ZC;P^2F-QJ;5s$ZQ zb*We&zZ>VJqPVjS(>T>8dme2bK0FMFjs^mG;ATkQHi%fh;xjl~5n~_#pbPDFssJvwA1<>)+$X2|NWHFc#g>gNq2# z8l!c3<04b_`xDvELMYVkYM)CGhI5sj`a(@CkorG`gs8;4eh@t}gMI%)@H zoY{iSaX0BcidpM!sY(L>+)`%SChYHsX!!+Fng)j`9itz4TDvp-5_ie`?jBIzE*LW8 z$!w}bBmZhdm9*5u*gsM!@*5r{>_F+r?~=mQ5Ua-3X^s*jK?LVGYtv?d})Qi;ix z)YXH=5Qo?oT|FZzmnj-T*jP7=Y`;PA*JxVchl{`wM+BqbfH3W!k%@WPZ z*W303r!WQ6_M#r7YXMX2byzqGY$GbxD|8ghgm(iZ{a5BZf5mvb~6G zPyP1GJu4FHtVa#xlqEcMH6uCYb8Umv7k-LcamT#{>>?D<0%oXO_<=SYIBISEoKz*DGAnT~Y;u;C8Qhk|Z~2VOiIPo82m68lHfn&s#*2B)>9mKXl#i zwqKGxAvOEwdEAm-YTTN z?ZC!qzYIJ3`W4A)MQ6=bZ37l#Rl#VDpfgaut>I(_4X#5@ZU~flB(hay9iGht-mK4Bs|ukhXm0Vo_{rU@ z0926Y>wG+Jr@fh~lJ!2a|Ga_Bvmx(PThhdnxJ}M>CQCMf835gwP2qasvlQ&6y&o<5 z%flCHuy*`_EKaO$ohRXq;XehfV?QyX1me{*P zvD`MocvYm~Ifyq-j)wM`>(0d6Qw(8#sIjzQf%rOXXj2mjEgpsEsAdlhlt#K)@Z5iF z=lDG9f=2BfVn~7NY;{DH6cWfXmBD|l;9@(pK{!FRkoUh443jy9s2w#B$o4;riuR^K zLb7y4TojLkhp*C|P%9}saeV@niP>G@-UZ)u%bbC&50Dv>xi_}q!gRrhkeyL5tw5te zRB(11@S^Br8T2PLPz-2jdsmiQuPUXiXawNu57hyNFkj#BaV}oMjnjCoSo2@Q@qp!r zuPCC=w`RrrwW? z@m$mrx9jtevV9X(&2xZ7;VHCGi|k!zF4~8(e);@W4Cc`z*_PTUf6qkN58DAaD+0%V zV%;?-4Sjr&{mmzeo$P0GU_jor-*wyal$e#9ntl{un2i=IR_-YPE`LhQdTl#zo8hVK z7ymsr2z;w5CobVI0S{y&jp7~Sp7#=QfmG7}N7R?cL;ZdKPpN3Jl!SyN3L#`2j1bwg zXAjx;buiW>RFC^>R^H!`|Jw_ais>%_ zYN@%32+mx?rLH8Kt#Ho!dhqRF?;}$E7j^Sn-u?$%D5Nx$1Z3}Qyez0^ODp8mm)x%B zUK?Kq@QR#T<}4{qMZ_?^)fL{x7b4{t2$>HIpw; zxEDP%?(E)>985(T)4$Mo0R)F8t_CVkIsb3A^sk2698x(<+aGL>GRI%06D0d8_l$}w zoK854k*KXf8GT@3H!6qH3*^$QP8}+5nk-H;UV4UIax<(%ZNjbR$33Tk#G(g81(L=fU!q4GA6+r!SI7~n`q-~`BLlR(1*jYf!9pN^3KJb} zGpQ7yRBrSg-r%1+=7bnPSK9JhUOG^cMz?13Q`;_Tfaw7nCM>RdgX{cuS##z5=@3ic zprxibAlTsJgtoSql>4Y5i`l`mPx(8)okOQA)PczXHC`vHY%uqUL~<4-Y7M^q-#}!2 zHHoMO5ceMEcvtEIWjX+pc38fWB_y_n!DO}xmpDBFJ&qx0?WxNCGcdCP)ItgXgZJyk zR)2O4YUMl({crI?Vpv$&F3p=gH%Na4V3GDCScuzfenO$`iML&g>478{S#`Z%`4=ln zzZa)d!YCVJ(Bm4>O0^9~jw1Gl|JwtQ7%C9}8UA{QJQ!;SeHbm0L8<65vOLbm06hY+ zKwpv9>{jm*jQEv&G95}^hr-9nK@t?F?m1I?MMavgDClDTVZ8I-c>}5*hA56JpE^Q| zd$GNVY?>m-XCW5~*n3y73ivGq$HVM20d(v5@TM;SBwt%96lXrPfECDiB7Vm?60AbWD!{wPr?I>D z5LfhZyV=}&o4x=i+r;X*`%UD)K8OO1cEvrdyTls)zZ@&{vT%u0$p@5 z=9|+1UhY#zt^;Y^eY?3ox5hm{bYVXDWDG@1gH|E&$`JiE(BqusEny`n$&=IITq2PT zva2Bf#}wnoA!o10snmECYs$I*#D3c&xLI=8-_UCwScqrLn4%hpUDb1v>9r>NANk2L?q$_up^Rq58J5-E%; zy)4vtr)msEz&ta_O!W#g;_hzOw9%(Xi{vTp5;&4*w zq4?ExH}fCBs7d+r{mC2f-zyZIOCJkWkVRne#~m!90*aSU=2XKsZeCgfWOk2X#$vdm zol@hw
h=qvA6z%S?Qk2}dN(HpIkk&`%UPpOnUy5`|)4_3M;fq&5=2ns9i+jo;5 z!B%?`qKU~FgyITdcEFYv$nSk~Th^jG8mJAiO)vo@>J)5$)s60sa~X-jR<{zGiODf_ ze_&Pslm91vb(-J#uM^tzf2dcdVfX3v^o*`t7`?>6Pfn|ECyBSg{)K(7jP6YYeh-kek+u5@70t^-471i1f zs~v1v<~H?_|Kcy6Lo?j;mP{vI(Z6pnTcI^Hp{^2+;2}!|knBnWu4r>bo%Tpx6Mh&d znQVlxZ5pM4;mn`{VO75*2&#G0)h>x`zH_MB4t5m5gH#jjG&HCK zLQe^1B_3eN`*Eu}$YZDOp;Cpg#%CPbnC%qg_rtoYz)F0%bEH#6mX>1@=_qUXFZtjv z`@EA42&(VQqIa@N9sth%)8ynAJ^Xsg@nG0DhMS_mj%NC!hxh*YfeO`q19Yu!LFF_$ zUc+f(p_p@-=tY9{$V1&fjZhy1oZf)lHW)~eMZ*7IQCuXxLL|?S>pIH1OSpg z4Xof?Q%)1Nv zHM@aRPS{FtnfNNwmCY?^KP;u8bQL6#iOrf84~inTcw$Em$Ri{&GnQn-A0b_jrdB+3 zJiBDbvrd*qVLpsQ0s|qe7npK3CBJMV20#HX+ArR1`aBm7Sl&r`NJ|mwC^3+D@U=7i zI?~~z0w|XO&2vH+h8x`gNkqzRm5l4Rm&l%(m9cypf*|(x@1VGW5j2^u5?87G;7|Fg z`VaaUI=MF+`Pqqhhz=^w-C=viN=mzli_9niE$JSm^k*p&QoNi%62I}d0`lK5Qi%bf z%{n$yGE~!*CTl-gbwAgT62mmJ5{@q#{qEb~`8ROyO?RO8@kniNE(lx96jz=ec!wC>@v9d*U_J5cm$s7xyfDu z{r>zFz^lOC7Q$q!X2B7>&mst=ujcljT;I6@lGlf=M6ZzJ?0YHxrQLX7NRH)`Mt$-l^hBRt{|!3%wnrV^{Dk*QYe)|~{mNwmvhmGRy;`$D zdOC{aV{xl2?K~#bqfk}@q`QHqA`$3UW4>R)h9-J^D_q)TEfES?i2`u2maXgKg!dYq z`R4z?fjY$g#o*tO#Dcf<(fM?cu{+>+?ND)D3T--T_y8)$Ap%;KZdyR z*zzrKtLPZ;#h55~8s8wtK?^MTR?gWJ6vtxa4S0hl<1r8)g5gm@+iwpwpOHUk_poAs zPoDH9KzQR`7&Pd{eut-D z*KhOEQkA}fvH^W+kZH2(zYXEXli=06PEW)k8d0y=QvU~H&H`D5=i@`TMhI3;%w2MUTigr#l^FNbt zsMgII#6Yi{$BN_RzA-N|8(n?3lDCsJa{0-@EOI5+F8=I-^w%hYc7LcBaD}Nv$+}CA zboMi(^GjewR0LwSfh&7}U*bRRBiwW@JOqh(Gx{&VIb&~{{OR?Ow5&M=Px!eN>9;DV z!Ef+2kHOX2Zmq37?62kRX+MhV!08ZDh}peT{oIzHCsYF>5&Kzs&hGA|`*=5$&Uy~w zd|4dQY;1P6Qa(;uQU4h5W-rmtD1pY{9UCRO1@_f4&H2FBv7E5pbKx@At~}cpmn+hK z+&c|kI+WG_g992aD(t+*u6Q2MP1ubgN?Ll-v6U(a#q9Y<%wB9)4=PRZD-^@1{5kF$ zTDgHx9H38MGCo8-Ml-zIna*tUDeHF@0Y+L9Z(R*3SOD0}Yr)+SN$ZChOP+F)_jUI1 zf_?qBK>lkfmid430`veQy+S@Gx=B_YXTy?Sfc`9S&sAQ83m{ZeD=jDtpXW0a#uG+voMG4Hi%@P zj`gbolqQF{Y$T8!Vs#Ow32bu3q2^;qty-35%-_LF&-FPcka+FZUBj*LDYvf3&+{TT zRlJJ!g)(GoMw> z9Ka%m`1nALXaPT~nd~MKrTDjuY?E!9hKm5mN~|`Y7JrlSMV`a$l13#llLNbdzpwL9 zz&=?U`m{y|AE*vM*PXYzJa(JrnamiUgJv$D3eg+nHNh+OPuPJ#4+viXIzXYF4!be; zR@-%unWH``!^RmX*+qQBztY~@%XNLD4b}Wc3SYeeYK&g>HNoDwt75JSe$4*_z%4sH zC#k1--Ze^4nv?ORWtOIlkmOj3qjAs06^@bU zo&V55<3S*9dGEdwg^7tW5oW~;n`bG*M4)-j(CvsxQ7MdPuLil?B|aVpx~v#|)7gq$ zxN15J;B`^s13i{JKlg!#JxbYl--AEES$|4eXJ)CQWQe}w3dpf#bo@@;M_S5E!8Z7} zeKc_NnirE2q;>af$epE75A#xW08qF`2l%#a>aU^w&93&RfF{Bp$)aedkHO``(@8v& zyrLLxNM#div16N*lb+S?8+XdVsc%`Tw@fW;E#Cm`{@VG@VNTYa4eltTyp$pA{U+P#OKJwqtaf=3L{+!!mmrm<`~V1_~zrI1f}@BZ7u8E{NeE)*4;A= zHQ%BrJ5?e62Uh9N`hf4-m( z<=X35Cq;ZGI828oUcR`5zcY)w!>wPYaVccEba%@CF%ak&8Wg)&~}mChjA$ut~*a^7l!ZIiQhKS$Ohh-;?kf!2z&{q8|8` z&S9s{(kGg5*IZs%vz`QQXlc}SX4l|VW2ZJ9*}3aSo(rR5IF(cp&&B0jzP-@3)=VL$ zA?a^FfdWMH{!~7ThQFr9lYQ&jR> z0)h5u5U(@fG3}Pv{3lATZS}PWtNroFcZO~*`m-+c%ej=#fbT>{I=8X)~KfE#)Jt^D{rBSyaE`jR!00a!n2nPDNCfES4_`#*Q zD(dM%-4S2?o-8OjdB*9aqsi35q`$2#wER-IxWJQOTDIJiBa(X9uF-!Zcy9uvD)?cY6@S69<@Te=!>U%l^2j6?UCD8K30rxOJE59e4K9igsn|#1;4}+=@KihCob??;4X>qHG?t)%5M>1?2GdqR~7}W97E1%40W@BHqa-p)D+iup}(La1jDJ6E%#{`c(obD@f6>D z+gS^-=$+!&F7>;(e^&?b`oNlLkAnT|(EETZYwUDowi>W-O_u30ism#-$#o@RvJTSXCsFX0QR-cqlt(ggB?oaqny zc#dXTzXUEhMG(3WC!KCctyTQsN&QFE4eZBp`jU}a;d1ls=wqPg@z;=o!C#)543068MrX zC?usHup8t$vlJ6FZ&x|sE+ zidS~5yAZ+6G|L>9Y^v%`tL z$k53szkJ~h)Iu$eob3Jas;dHs2ivKDQd7a7n;u?68SOikbDEkm6%P$8XH#*NMBX8i8m#XNkrH#H2wQ0a@B=Ehdg6W~w#^~_^-)Su{FR+avcXR1P zM-thC1zVI;gwT1RzH+Q*CuMeB#rdSsQRhGEeQ=Jdn1Hd@hi{es{^>++-&$`psLQ%} zSH0Fb1>WSAM>@fp+kF!qcyfPlf#aA|`4TL!;mkKq7U8BO!ueTr*xZ>M`;;Cy(VGxC zuk*&WBHxc>C9g~QwaCWk#b)wWip7)4QeqxeujKO#dEKiPe&zTfXx0Exxz-keA`;#t zUxq-iVb$H^`iNrW>R;&Cd;oe-t#4R1u#}0 zN5^sbh3jp(?26U{v4s@D17QW|ShL!RAQ`Xnd2g?h*?SHC1; zeZ6Mc#gvOvTY2bUgi}GCi2bfS1a3ql$mI~_jx(}x;sA4Gev5U%B9#rjB z{2~?U8k>-j9b-COk?Xf=Zii8iPjY<~;YWCO?aWCCnd+2Q#OxywJ6T}cc~R-p!hJsH zs%(fnCrH}CW6QY<%o~cIu86V<+aG9~;!kNrg+55M&KjT+i=R}wm#Ri!0}pF~h9+%2 zdCJtKR$Wm@TCD;9YjF%l5` z>Z_MqLkkvZN@Y8{8IUh{^L-zR4-X3|fQFne6&){%m6Fa@9Y%Z0*&+n%cx}2WhT~*H zQUrItl?*{qn*II7dXMiTOxIdd?m+mit|Gi0TraQrWB;BE8gk*{r=!@-tAa?F(p9M(HI(g!z?b zQ@7Cw2bXd>ukUCY;QZ656DMw;`}10mZ~h>@U!v$Bl~A#6W8q3nZn3?ix!CPr6w2sR zysKB_Tdj{T=|KCg0c2kbJh)qhS(`+w0V#?26R^>#k+EV4%Y)EUpB&@fUm=Q zs+}7U=aW}ea0r{+Z%-BN->=%Rc*>32oo3hm5X0!t=)J z&+T)7AuVZ{xeKO^yQ2r;Qqt>*15J3XJ&BhkF?xW!K1RoLjgU_ycC0qH7+6b7E2#|8 zG_h=CyGJeld}#clQ2bHU%aV?yD|6RTQ^$R7aO!!|aT&TJ5AXm&Zf2<`q1&#Lt zTaj+tYjqY|o4Pf{E7xWZjPAoaB5Vb~oW-bD^P45{;#>kPVw3Dyc-P)vQbA*YL*lZ3 zH%P|uB7(PCCqWf+V!DV|Xhq&U3A8m#Aq#fpmWX#LesJDW?4wKQ=boC&pTAH(^BJ+@ z@-_I=D?@BV9eeM~13UTw7ir#Xnab|b4MDEvt8DTZ&z6QJSbs_FC%Q}Y@wOhD(at64 zF&$CXRswB1t1T4%HIjk3|48C3!0XvNt`6$PG4w$Wq{EKjGZ@!I4fr z%+sHaG}(H3;D-@;Xqm9rrGJY&UA3adUwO!W9wpvOIIV*(N#)QH;6VA_v(i{P{SU64 zI|YVPMtTRPP|>wJNp|q1o86g@++S_X|0T@yVGC^Bma)?DEcI%rPm+`a#J)z;I)grv>bOB23Bm#hkQ3|!F#jnj&qR&dp z?IEdEFCB-TS7!MK3&Q1+M_IJTg#{icOgQ=RxncbSXFlI5zyH0AfYGj`Qj*^^V)3td zo?dPAwqW$30~@}M+ZfaST8B~WmJS{>Lb-m-F#V6tj0%+?MT$!w?|=|JE-NK zKV;}r_gojZ{kHse4J#AwaqO%Y&O1akhUE!qH$A`2KB;ZooU%AqSUG!``a0-( zN?}|~jj`|OO@24-8^nWgP^5#E2( zh#0GUqUK#H#_z0{GI&}pV^3WG zaNjPAJr|3C752iD;p5kY+9XY)GVSL5(Ki}?*^Wm_Ve$8E!5Z@q%E7t$x{>&eFHS(y zmcs}>dUFmso5hBWTG!(C(KgzOY;-30Z=(;UC0vS{A>|csFeVm0`(unFCam&zTgZcl zaU~@NA84ibTQX|Sm0NtP4q6rxQhq-F`Q4{0PE6U48zQ03rFan^lVZeB53_X<`?fpm zoo+M*@T(V5iQAmqhkPNVh zhtm6mKB5O{(o#mwxmVU{VrAXhsjY)KYM+j zXXf??)a_4U;&y*r1!E!B@YTt=u+h;KmYbzneafiY&gIN9r%&uUEne=+KBn^yiqrh} zpH4-idVLpG`@PfF(J)5G)zQs#(HvsUax(`-J{>V$os6VSHNv3)(|vsE+fhe%>VaSUy5;y29Wj zs9iU?(&A&K@+|HOAO<=hn>fl$fi_6>FT4Y&y?HxqQo)6{Rx-lt zt-$a%vF@qd(G*<_2m2N0!8C!!2HhS*8 z($CM54FfNtvS?g$w56dTT`fq_#)kex<|BxA=boeh5iX~9Q-5GN;=6M3>);bEnV^?G zyr-Xbtm|eQcC$6x=d%|r=>Mn1U98mAFy1m85_D2v6l zn8J~SD*9LdkG7=y5kK*^pNTP#m_XEe=egcJ>ZDntqX;ghmXp3L6%|Dh@BUBowWm3W zs;@&$pqt?Xx9_E*2-nGDPF^9lHAkhw#ds$>)eLW}HI_OBTl-LbVaR1?t}Z49Qgg^xDm|CoDNaw;z0?T% zzl&m)Z6yv85?;eX@c9t&)rMfVUgy(BC)?hZ#mFPq1&!l5ygZU25jL96RC4 zug0;P=`OWVVHB@hpIVk5%=&b-EBcC9(4o+uNKJOCm%3(ZS%){#h6yzIm^0i-aN-M1 zcP;vleSL!K11Xde>Ngl@)@*Mwk|)fF8xnrq-t2eB#GmQbt_R}9U%`%4}?R6vY*heY~(FM&7NVj!P>jBUa zqc_L$F1J19%r|i?N1k1)m)Q?la)WZ8@J3Ew|N5sA!O`TC`y1+(xzTT?{$+`?0_Kgr)9Q9I8*25X+GT4D*Kp%Fnb^?YZ6ufF z+G?YFAX%ZCY)(f7&V>Hw$~-DOv*;N_Y$P=Rc`=pCvVM2YJ|MO^Or?>s?g(l^zm!-f zh_&b@sY=ek4+LUstv7w?EvULM#59+n}9Cw z`iQgB`nWG7=-S%Q-0=3T+{9ZoDpu{}*FICoKAhMSt)q~9WJ8w?b9#q%9(Jn=^U2%e zNm0P%RvV1Ik(t;(L||!ISg&{c=soMHT9Y%3n1)?kulq7PGLq2FYIrg@w7`}3^Jz;A zL(#4Fu%fDj^&V+;UE!E6kD8_{NiyP_`_k1A(y8Hux;u+rlv6^{%kEhV_ky(!haT6- z_=@Lrcd$Z}>^D4`Urn6^%Ltc8>0s-Qayyok`T=1piIS9^Fc>ZNEI2*?-#Gu~U6lUH znr!HI@fVW8s2lRq~dCv$>fsEVuf4GFr%RfPDFL7NURp zrR7;#u(U|solCFIv|W^$mV~GCZYGDDlDbDtN3yuK-w^y}D+Zf(;gSDx>%!4imlDP0 z_Z!yh&v&)&vfTG-{7IyNo(pi8r;fXYYqm>0ZysBqhGg5B=}k{~Ksk%bnX&$2ZR-to zJPnihy=@CPvt!b-tiXgYzCd=%=A4L=Mqhr6mJTka(nNv zv`$Et)3~WvrrMfeemTzSKC=2S`g79++3cBxjzHCUP^C=> z-ueotiIloqxS|#EWm2eNVE?+Iz~krqX8*LsVP=#>v9GtoiS+=rk1v){o@iCuq*#Y5vSCfz%UKlRsE%Hvj(c|1Y6v# zSCi)@qp#ivF5!eKBBtG3W@^Bgs0KjAC8;qNwAo(oXXe>HzTgmc`ShimX{0I--QhwZU@wxJLFq*Kc|Vwn0Uu-lA$v8+ zBck->B!3Oxuv>p&fOCK2-+b=Tls3B%Bp<`B^F&>7>J`r-K31VLzG`Qp)GngQpul3& zx-(qG5;^{{Us09TbcxVkg}!inLyvYYUv9lYFUi8g#ttje7k0Mz+Vj}t?@(|W^%`X{ z1K4?ScW=ozJbJ*`P8?<96ir%8>q^4$E>Cg8gw}K@TP5C+>3A_yYFfZydbM9?!p4lD z#O->gLHK(HN!91MWovy2%qm}U4xf~FJmv~B{WIWa=ZDm+3pz z^0ltAIgM53@dWT=yWFVjCPSGjX&W;@(_s@V4jaJH657V$JXQBcy^t#bP4gg{y|*@B z8=pE~+s1QTBoSQ`zE(iSbWwHo(Lb$uh24PN=B#I9=#7CWbirinxDZFc2_zpbS9cjb z{Z@3ii)QA9m3p7vTK*au8Y)NsfcbL>@_FAgLt#%KqeIQi=bT)q~3&+Ileo4$~C;yU^Q zyT2y}!`kaQPaR&n8Nr?9dsgV47FC@MmxX?IS5PmL&Q)VMz{!tz#CZ(0y*uH3`3Z zJC3e`SZZ;5a@C?2s;rl97#4Ni0SDu^+KFR963l!f35BbfRW5JjQpmc%(lOkcHI6_2 zCh*M&sfzi1+(|{CwSM-P-;;a?;l&RaobJ5g2gfBR!DV;n(ip9R;#%G+}1hl%QNeq^R=dp)tNa= zOr9up8Lt}kWi7w@d&4?jXjIDlB*+a8a!di@2Pu^W+qu;6f&LaXN)}vfO(|tD&nVv&iToosSQR zHMr+<8oVQftjH}ZyZr+?QlyTq;=o(orhXv#)WJY>2^vk!5g&#z5l@X!oA_nk_#h3% zM+`?u^@1YQ|E@P|({H%RSd_btTBB4;{YAr`XDQP&EouSHt4Fr3@6{5WtsDM?)x#&D zdZif7uB@4RhM8Sx3yZKbl)nAYseAXIZM`O$bTDw&T!Bu-+w*CLWsy?1qpz947w3Lj z?5t)vhUoBHrz@d5IvBV@NPhQPuU^~-=aJlId_iamTPF9Wh0mI#rsu21qd1b2ST&Os z=B$g-u1cF&6LIA)o1?I&MJL*BT88UC{55dZx zhHY$)<*6T39YlSnRk+D?Z;UIozGZo5r#d2W4)M%Kp3%1-*Y_#!(8C{HRnLsS8n|h* zV795nq5E{lZcQ|}x=_D%D~VFoMPFJEngD>R8y0WeEoP|QF}>ugteVVq49eK6gO!8GpP8EZo{vT$fFLfG^Oj) zZUtNAJbDMKY5nwKO&UBAr+ho(h@P0(T~EgSkf%Jk@(w5`^nRWyYp2`bHbWuj&X1La z;A&sNA#H=;h$)eV=FWg3@tx;EbED_4)3RHQ&AJZ7#e7G2)uZcCv-rSs^32`x&<3FL z%X44M%5`q654@_olJ6&5=xkn0nw_VI-7cqWfAJEkjyb{!(bpK)_Lto^Rx+%YO|*-y z^}$I6-bk8?H}^?vsw#Z^JO4!?vk}@0n)QBBNH*L{aw{3)rj<+)@QjtJ0C**@xsA5$ zoDUY3?MqwNGLuxH()`IcC`uqRqB`CiDey-0)aki$l|U_rhU=QF_1i>d>v3PdQEYk- zRq0oo^1imMjZ_#=Nn<_tJF36UmQ&Z8XD$0?mSIG#UrojSfK^~}N(b0g))K{GE)NH^ z&_~Z0V@7BCrpwn71_Kqf0%=uC>*Z?SXuq72yTOSb3HF`NGA^+dyAMgt@e@U43s*> zJ6{5s8H$(3`SKGO6JWbbGv;1~K5E#js3!|NMn+(z@xB5F585Yl?ZoHtO*zpNlHTCX zDwaF@1`|x`5w$qtia1+@Vf}c;l2m?3W0kYQ=zMuE?hBU7LEuunE?w15je&93C8ScP zmM@L&!@3gmj5BKA+SfI-4czGx#O`v-bH&Le2Cw`{M#zd&v+y-~56Vl6Ys8)+VW28S#egWXbK>*xH@&*{V2#H>yNLcSah;eHGa7 zeBYn{@NazN&AO774Kp8)s8sqGxrX=NiDu<;!t=kuN*be1G3NG8)l;tqMi5p^L-keY z&=?iY2jPw$Rzz!A_=BiscjU*c~Rdr(51$s05&xz9RN!_9{}1 zDN^d79*%|a%^kY5ZyIJO+&SDkW{3EBv8WS$^tKsiW^K6Ey5zq7$@$REh%-}`fzCZ* zLC`_5pa0v=0n$WmY&Ke@-;?PVC+j{Eagp?g^-L+@_hHa2va}2HEbS4#I!K3cmT6yv zySP1jsqHz=z0mT)h3!HV8oVl4+ zz9TTqUEiBHm}Q;Y>h@Bzmy4qRk>cr^TXyk|`J#ZcM{t;FZ!+&gNaPy-bi?kbn%Uxy z;;{aeGDxMFmO*FrXrxh(^xeJnK3~sX*Pb&>(VAlBPJy@55r;0|I`JkWtfgTHYlZGPF4QB*@`FAoodyDnAOcxhpV*kRa zv9wq=xTD(5B}2b%aZA%KEXS;yyVn(hN(j2hqrV1S%9v~r-)$EbUmf39 z0G6y&t4{Q=^`LX<-^ljBGbhO=rl-^7aYIICE4I8GJM8RZFQYH zRpoTetj%`wk)3^r2p{zs)az#!VI*Bj_lBXcaPQJIQt(H@SwT|QyPD>y@!rEcgt>ob zixHEvPkGtb1YgD%WfpJb#MBfSL%lpN;!l;xejFs#zWENTJ;Vg`&3Xl0Z39O|J?hpMIx^l=O)6U#S_ODfk@r()X9~4lhde z1`jY>@*}2TNY%ycyVU;gUL{AulEBsM@n{Fto{KV+KTz|S9OJ8Np@g*cz2iLoMfMJ^ z;7lE>W<0w1yUj zSW-WqxuJxeRHN+tWsn$dm+TxRxsM@um z)P6ic?=8RKXv}?XWo={suS;p8+oY21h`?mc?W?XzL#yp+ktFVJ#7Vv<9bXx+G_Exw zMp%w3LQKEdrvL%38?WEaTp>5pkk3Wvf>rZ4(AMzVBBNk|NuvD(4JFKAhJAl&&Sle3 z_p5a=p`~B<2UR@nZ2c6UI<{=4CUmf8Ado8|XSU2lxo1pWB^96eD?#36N^1Q3+^uI89KYJYVFc zygo^W$T^R_+4J1WCYS1~;nprLYYWys^2I~K(&LrZiY09umQS5#K;WNZS&C5g#UKkE z&J$u#DSqvj;zYZQnE3|TT}Oa3AIRTNl*Owk`+61(BBnP0nZTW~LqU1wyPk1$@d9sO zryo(d6>lT|8tT69+X*b|g0!0S{nz^ zNnQb>OS&}vigN7p;6$XL)s5m)Kk`?E z_5Saais6v80rvFZu+A0iYqL07yFWj75mI|L8s6uPuGTVBggB?PI<3dd2^1W#ET<6{Z?tSLfPJ zQ~y@+Q~pSO|F7nIsJmB{cMo(H(fAjRL??+pKH?t*U&>*0SkqN33cvWdOQ$lR+;62iR%Sny4?T*02(`?8% zll`$`vT=ML-_^X@ICTGmFFsMJuIAB$_HD5r)rOot51wX*`k2#GZ&6)&MhkfvXQLYJ z|Haq%)7}F;2&e1E*y|6j$2g?Hss`0%q$nSS8l^u#<7Xx(tHs-rl&Vrwm?M9bpPxq> zr!8lHhoq$J<`v#E6Z2}+OH41yBNUJg#X!OvP#;)cr&CC|T`@7q_sMr23^oud|R zBzE=-{ZNGVCt3#pbbYnxKAEfqn4&?MTTxAeOD+VG1ym-iTP*2U-G39lWj$emlW^ny zcKzU~9nbLSDj>7^%kZAJ_&0{1=uFH>3-vx17ol-_M?&JC%^109&RZ9IhF^jz@}1)A z#f&R4Bv*)IZqJWNZQg^Y%Q%KSI?`xt7dMTxX=u+yNPY-5kjVvZI9}%AfA@8$-?9J} zAjnbsOYv85R*II!Y(Ptf-xg1Y=8Igg#C43$VKDtlBPKCTeM3%NUsP*MP&8e9obcbV}?zc-rF2DC2GJJKmv6e*E4tCV@n!)k@|!k};}| zSxuT4p5x$R)#b?k7!)CV$8;jIy`w`yHiG6n#5fHbk*E9Zx^}$$LkPE7dki#U3}Goz zmzI@7m)|iY!5I1OU%CJJkI7wH080748*KfB`WA&*dle+PZ? zyQTwi?A|4?@edq&AFN(kt-I!!B zRv9K!R3Q{!aJs93Qh=uUM(7CDY}uyE<{FlY^|EeFk8jgdHAT%?Pf+gC-_A^s17B2F z=yIP~r>RD)-Ozn*_5XPK%CIQgE?N+Ymo`8`O1h<$lxBdTJEf(&Qz_~0lx~n_=nn#h(4JTPJZ+u9;&v)kjFJpO z(U6lvqv&e)oGu!^y`C|0&Jm(ye@i2meV^{(m2W=71n~_h+kRIMLkf&{}be ztB-lKJF$^U;ONSo9_McK>N?24yZeV!;oVY8UqKub&^0{W^@eVT3AZF^&tI2MW4UaJ z=8|5v|E_&wKA-Iw0m0-c@!dvPkh94uUJb?TaF)+h<5Jq>i(@~~i@^Q&%+)9b`J$Cg zl6*igGq$3)g_ZGr>G*Gp;FmzUR(?%n+i>SDPe# zc-~4)7+yrM9VYvkmpBRwXP|KxVjGm>k{GIB9_L;*rR`C999u^?(&OGei5X3K#oA)w zjafJo*S6oDIYE-8eZd1cRlTAObB$F3Gku-tzJa%M`7dekwJqO6w~-ExuwcH06R$Z@eKGi}x*w?Qbim zo=>^3KDT%Avawd`n(ZaG1_(C>4`Qm6Tlyyzd`dr-UjbD{76Z3;RvCcD_>@=NvVbhl zh!qGd*KPrACWQJ`i?3w2OPlPXL}|9Xa^?cc-%p>A)=~C^jk+xnuD~evY)8vhT8)rgc#x zn-(4y>;PS`m&MBRr9{QI9`{3WcmK$BY@i>Y*#Ob*m!cw8TS1?h<&S=a0Mf3uXbyIU z8*?TJf1Yj?dugH2Qrol+;1b+xL*ORp6g@n%mG5W0zbuX%cVeON*mN_&u?a3#qZ77? z%si46aIfMnd6auJ{FzCG*m>l>4&j_`t1*+sCvrZO@$n`R7%FJfdbRwZN*od*aQb;* zyYc#%ZK#zU|Mq+Bf-|gCA_SEAvM z(WsIUwv?J}`_T~e7qL!0TgGlm3jva~7Brh82+IgcYM zhZ>(;OIy}2`;a0$NPgF6n(cZg@>9)~DXF%i$*}1ga&05O?Be@N|Jd`4s^ejx4p8h? z68uA0FqPi(wNK0z^p)^>QOjpWvUd(KLMl<`3yto|pI1(sq{f5LQ3lx?^J~3(mF`J{ z<@m-dPO-r`!LU6~;)$($j5{`!iO~C@>~6bG@>zoix#<>fPEDD|CsHM2)X zbws4XCoMx?f9xnuWj62>ZCj!%!DHLD40E&hv*zT4NtXAQs^o%Qil_&pgI&F$_J8lP z=_uCgIBY%#vV-|M=jJQ8K)l`kIL9`tLXK1MneUj{li>~KJ%;Gv=ZFEL>L{T;nl%$E=yh}Tn3{L;+Eb5GfqC|+pqvP zxA@-A>uO~hbskZ9-3cUo+vpV4>Xmwr6_{5Q??QVj^;$hHT?XTH2Kyt+@kR1Vb;_>< z7+3}ZU-&*!?LXySY#yy zEQ4>Vd-7H!%Z_nhWB#~pD;L$f+m0WvCp_MZ91}q4Eh5}06_OuJrCq#ATbb=von3wJ zvTC*j#OwjMk6WX!gy=lPSkD_qw@BK21`F<01rp-DUV}piD)O1HGz^slfgZ!h*{`l? zW22)HM!T)WOL<4AGz~Rofo%Tqm~WnT!(wN}uX-vLlyNl3HfVtVXdsGbZ5!>Q;csjn zOkumnyiR|6qFj|k;`i*)U3B(~KE}3%#K!xrvko4>x3j3qzW8jARBZ6V>8u&Gdiiu8 z)88@D*wO#CYOm(LdifH1BR~VmOut=4(%f%p{WK}2|1G|y9`>kdA;jSj7UEkh6L#M) zthpC>`;eQeAiMhaEQ+`<;UL(=9XN7r1c1m`a#g~4%Jo^TpTt)B>ar|-B9A8_7JbFE z<+feN-*LNc+L*QDiKJPZ_L^pQFR@6hwHb)$?h(u#AFjEX$-RBkP+UY33%whdKim4G zXV+P@wmb%Em6%%0YOeYiLj)LARDR0_Tqo8+jyz{}k>-bQ2T`(|+){2?2# zh1#z1w;8@panv>M*&OZXEgcvbPF%XV{b2|FDpperz}!@3|JIQi4V`W>jEY(UKp7ua zNesS|eY!n{Fyj3T1)`#5CP>|9I!yWXboOdwy>t@4B-1_m`=m8EX;Vha;S!y{yS+rEAS+Y9L~6ub6W8C5gj* z(++aBy|N}n1Y6*djl5^5$@vaxcb;+GfQq#tx9&=sTdv$skE)a$e9XWYol~EYiV~nS z*Rh)7cp^1&f+cF@_GLairTykcnM(J|5r2kQ+5M)3V|$ zI#`mQAp_dP9x82?%gegGvXPrfcLHy*;_Hs2KnFP=TwYer1&1;atb9~?aa;Wr4hH_aT{pT>tebF^?ui0BWHVuPi}ZOigJ^H21b3CzzW z8FoB&3QK2E|MPM&aaG|JVEvq?nPVTq^1A2Rnk4S&_qBKZC_J= z(R`%wrE}+qV1`Z8aNgg+(C$HvZ?1^I(c5eg5jGXLchDok|4H;brFdE zIx6_)j_H4w%Xn-@|Jl&oSrW6-Q+`E(**JpOne{E=&3RtgjB+=fMsdbbw|ZXbM? zH<}MAPCq2PMNtjOJ=8GxnW<0Y)#?7}lv^*eltoaBNo<6!ZAwmP)>*Zxq2 zRnsAJX;+fPvHP=&^rFt6{}SRZ*#`{jckWl1VE=hoSgIfbT@3p(tOKKX4R|%M9)Gc1 zeoF)bY0e|lbUvWFe5Hdrp9>uF1S)uNXoRUo%Xw9`a*X`ACh-e~BR7WUFzqs|m-}Wg=BspHZ{(F`%6Td7{ys>hFvg? zJ8PCC-9>0PO-KQ-<8sX$ai|zLI6`4F+9$rf(jPZdTbgE%H+1>b0|nJP8elw<}8o?A=`8yhut z6x1is6qh*F?sf8(I#>3WLqXcgd)PR30a+;$p>L3I9ZF!i4z&{={GVPj#S4-=C-3i( z&ec!ss3sQBDQQ7>D~7NkK*Hm&b*VFFzTIq|51-dr>s+4gZ(OK>&W6xPo{F+~H>H-G z&|F%FdL^ByzctGj|D3sH->=Icc|LZVuee_B+74T%kx4sl6Fv2kACRE|tN3PIm?Zdf zC1z+q4g@T9Q~Lh?KUw#&QJGgX{cQBhUt#Ke3_~f~o|1EphuBy}i6`+hsDq`Id&c%J z|5yHIt}cjaV3d<3(z7XpnGrsbR2{8yGdz#*KdH=!Tj;;IIqJzxpeZVIs4X+C1ZHOb zlQ@eV0XT9wZ<3PVj;YyH6%;}zEo2s5ep3`)k3@5s+EjW#O1QYnIm#FBpQ~a1Uz-W> z2y%%V_GBYo@1x(Y7L8OvT|JjMKjl=_Zw z-O00xdLcHkXUM#+K21}q4Lklkr!JkE=I3upc4VeR7rm5jO`zz~2e@WTwC0%gj-5Mi zX_bbANNeby?{iH^G1lfsuCV|%S>BBoKcMOd;6Lc6{g$t7HBaD2nUY z-02rN@>5=(j(1&`l@KKDRK1m@5D(`+-yUDRb-vzr&9Om=b!)|o1Mmk zJLD=5i&X)UuLPw)fQ=G&W7V`gd@+L|mD@s>ao%-&vG8_31f;$rokpgr*(VQl15)A8 z?a_O@@gzBG_?H4o&1@a=v#X z6%Ini6k<6S<2aL)T9+?!HbX}4d5SY9aLm1V7OIeFaTg<7&5mx;IZzv~+K~V6aufs& znc=)sNyi6Dwc(gl1v{Tj>xQQsC(&nve$CVEk^ zH8+(CbVe-S(i)4Y$8w@9sNN{pDR>NOJAZynA$C9FfnQQz<$q!NR=WuRi&Fc$ypEGS z%}91K4+bv4mq%KaC_2pprkN?O(F!l*vGYe70eip$c#J0bU>10YJ%*!bl5)sm8>uZ} zN(akm3qyBH&Si2@8C&lkX?(*j)G}pgLpgurMm;Mrj#b1^7o#pTef8{>XJASaOd+-r zh1#(0%{8B0rwUP39`Q#QAPN^p)in#@SXmhEx&70&>L`Z}rQvPgVt#Y`ki8+RE-UTT zFpKZJwz{ct4wq(>?5wr4onHPrJ|Lv7SKw(6r)0&+RCRUp<0!eCO6j4}$i3P7x~F>M z4S9#*3$m?EqA&O9+C{A`tC`mYwpf#J@NvF|JFnR@suSkAHbfSLBNyAM;~uV;w^!yh zpu=oZ?wkC+w-z;l^$XH!UfV!vYwcjZPoLqn7TSO>g{P0X(<8J7FV5vKzE0wjoiCCs zGrrzNRfoPbaJ>{9fm5r5?raqOhjFjha~`;v)j>kOD0v}C_h8rY6MM5H~>W+cOWVD+lNrRC>Y zY+nay92z@{*<4KMv+xg9MHsk(fjmd@4e^uRE|ul7lh~25d0L6S-?>}d-G|Dm{KjyY zbCk69PH~wEi&!LYXl^Byx#P@j{^U$9opNqt^aHb}uMKg5l~RX@n2%-gr@Pm&j4Pea z49VJ;`f)^pq+4A0NfusmjoHTq)-soY$S;3w3aY^;<8@EVN}v6x|Gxa%gh%bEMW(5Y z;0DMoJl)s1>}24n4)1U{D%L7O!#=g z5yWV!G6ll(-dK_`n+xS9X@V=kKU`B-v+JfkcXlFG5iee%CmDN6^wIXdue}jq@NPv z= zLqnsg+!CjamVr_7RIkP0{i!L0SzYMER+M(pquWK;;fLMv16drTj)A&4Bq46tA%!`T z(Bi9q71`3^vu!%+d|Xyet+zLwrf1({VY>#kX)PvXf^SvEXBt;ynkAP6`(qdHomi*9 zoA-F8LuGt|9TYxR<7!~nvXlCcTRf2tCMPTSD(}`rf7E`3B3F^M9}eObuoFwa)vggV@7D#=DI;!e#Y;MESg-p2+rx=V}8c+xn39H!K9 zz9fvH%{b;(_pU^-?9DssH!i=ln&(qSQ^`IVxQtt8d*l)HO*1AeDB{V!D!glI$bK z`95M)XzLo~Bh?(148IwDUZk=Hh{gFk=zWZd0icKsLotj}*#U1=l_&CRmxX37m}k^^ zIZVBsUaSZ(Ex9v7yK=R`IsI5{VhZ?NXCXcp2M(!$We15Z6+HHZ>KFaDK5?Y%_A%6M zps9H%{rG-UMKLFaYw?h8G{X=FQa2T{iLSGc`9))nI*08R^_o`7`(F81P-BIQe}ee^5wL0((uOV#H&o(W10EW(ZN{Y8JL zdH<-P;Kix%cc)L-v;pHOj5NK@we9thxFSqePO~xY;qOR7!WX-h(i#2oU zUyG?|I_bG)a5Oty-~30YN4Y|tohabAO~3iTd#oUsvpGjzWFsNW0YZ*J0`BT)W>4Px zYWc9dt%82GH5P6BKm0IT=uIy0tKEH5%~Anvy#Hbp@4h@YWtjG}eLo-0rW{qpu{3ZY z5E^`wsh0M>H@t{p$R8)cQFsQX76KI#f`|Mz!<&Sbvs9Y5d}CbUz4t%8dx7+0IO)5f z{=`=!fPN?KpTt;$6olM%yy$BrZJ{Rb@<+Bkt+f9b^k0W0T*~uuDi;yMmWxp%W*Rnv1(<5Tn2bRV5)~ZWvg-_y z=GleY$CbYu+wh)GIhhJ1%Ui_9JzAac+icmRy3ZLnwYe1n7M6D6KBkg=W3yR z$A%GIDGbFpdJaDBgJA0Q9L&XtdJjj&y`@}Py)@HuG7>vkABJ2nb^RD!D8B5VQ%QSy zy?%V%;?=2Jd#&o0=cqiiCoeC!a6b$ajpjEJ5+4iXxa{FO$==7m(y~chwi7dF{^nT`^I}N&bW}Tx>92UZq>i9AsWeE|~z{?GT z`KeG}iVjtD>3aK!|1to&mghV@US`l2MefKns9 zg!6W}x~$e&crPL*0}b_cYR(xlTUEs^9;z9JYB#Cl*^kLii9#pVc@k48?QRwQQ-tMV zC-DmpQ@$7UAypI`$}V_Msc__O)->aY`YoK#`T%AG%ShTL`^=IYlTq63qOJU#s?waQ>?EaR5x%Kzp;m1C!e+w{7UY<90EjwiG{6nu_)-^(!m8GC6CH_G^`dILqHkETmI*CEK`cM0~R_0=h_3-S> zQ+#;(WUyBGRqDiOWjn8OLZup${?m^p%BRQ4UV-LoEB)#jCy%LhxX?l^%rD7mmBren zE#O5qxb>qW8QH4`y^dHV?(h_GsLRX+ogLD`oI{?q>nJ57i?dq>wKaiqb%Hi7aL3aX z4V4^zX1>c3q-D{6vlAODOVcO?Uk$uDKYzt_NYpgT0<#{}p24$Vu%3ItBrWKzrxW_- z_h1Ok@gJ-672rxht*a%7$KeMfF`Su#DJvIWP(*GYpx@Gt+<+)7@9(z{JaZ6;=iI9D zU#dUv{n{>RqC#g@nM!uTvZ$D9tz4>zC4Vlqy`c)-dw`wFdHUVt>$n^TEwT+EkqsS%%Z8a=(P}ks zvZ%Y)aqt1ho}%H%$V#CVj@)`Q#BpMSw!BVQC>DqA&MMx&zyQA#bCH>b=Ey^DQKt%? z;Vc8YleG!L?6vrhf~8#Zqwn6OWTi2os3#fc{ebc>8(s8!i?AZ)9e<;ZppH`@*C05kY%(_;*t-lkt3G>)FF8RU;ok3)3=B=>9)nUx6+AMGur*mcJxyTAx~y2T0jY z_|S6#ovzB&Hp}Y@f5by_>%(ez@1CmO_`uR=q~S)5>i0T3v{x2^da}}YroMJ^C$-B(DQ)Whs0YUYK6w*E^8$NCY%!q$)@lrmm zIC|EvR^2VBg`jWRX^T8H-%liAZ1CFaTh~RGW)87~h!<+q*VorS2a;g*wniZB|22)q zh;`c;zgj=^Q_EA~9ZVNDj`umau3XOcns1o(ff^jb4!%~CD`X_45` z!?>eYow1w4!kBB=aFiU({;bW_VTggIwGFC5z_ra{W3c}IPX%EqaSGA#d^dVn(S~UV z$yM^6n$5`?5VHeX53j6eM_Q&DmqKjn`B{!A{5MB&{@z#UN`XgU%8eBw)nOz0aRTk4 z!ETk6b}@NLa(sVef0*b7{cQ*GPK0*N`c9hy#dfAT%|c4jTQMF1B&Fp$TtVY;CiCTT ztJELnWl;v=%ZFyerZzWyl`h-VfoEw>?PZg*titAr{XR9h1n66TA53jqn=Kcey90|I zPc_~vu4f+DY3E)K6;G>4xuV{x{L|?-GZ1+&usTUKt%H%xtECG25vt2f2oIP3zAL$U znp;i(gVZ6_p=FVoB0@6g#R8MwP{r|nYAsb zugE zIhQe;BA<3d(X6>vuv1BUf0FPSq`0gHqt>kO*@YclbBo@9_klnTX{g}8f6K9i0YSq2 zdC~gHK%b#VaW$;^x(ra*iluV?w;)f}co$?*h;EY)SrSV^B{9uQHyRm}FESl%O7vG4 znU2$jDv@;lar)a_l?rio%~oH-Y6 zVpD1YuV=O0b^i=+`t*4_c(-0s_>S)`T6qthM5{OK>9wk54IWR#b82RzqrJY2cYfh@ zPTN1rv;e>SrAIVjl-DqC-SS_;;yU-(Q?(_jn73mqik`b6TRIML=2du>eirgyYP{+1<9 zpRMrGDKezrdA%8RoP(Rip(=PSE6pIv%9q`b5tFc8%j$w@GGWyQlCxcF)V+B`;*5&+ zX;@`UQFleL>wwc156P8}#T=vNyu#haY|ebR@_U9h_$5+q+H9dS>bJ1lBS)e7fh#2t zPk`N6Fz$y!UtgblagQA(%|R+KfTFL_+Hp5+QeNr^u)9j`65u7Wlc>rP6hL+v@rq098ZoB9!~Ra`W?AD$>(LlQAwf=i||h2vnvT? zXGyeArO_eRUZCLNQ1ab?rKZal{PI`v<>fr1ByzIrrtv5ew&b>}jR}pM*&4?Ykz)j1 zz25+Au+@9*yKRBBK)f3}`!Bx>(^oY3onU!8c{1ZhJJarYmk%ncb3ZXdn9ID_K7};x z4u3mcG^1Ro1X(Wqxr^(<{#o~sW2@K~KyiD%rJQ-pAoF1-P zWwX18u4$GolCeJv8=OzAG>vU%-2vV^QpQB$%c2suzWz3)E8S(=EC4_(B=(ZiY5Ll{ zjeGyioLNxU9J0vIqe@~YwEGh-#tq3U)|($r4fS!y*wc?hyJz*C$dFYC(#!N&yJUkT z35Zd^oOtsUL^`T{I?`2MXod0YgXUzam5W^Z%7Sx{lL4x3`0KbIWrj*!uE+E;8f?RH z4Q&a(&)-O=I%OaB<#*qvi1c_r{@Rcq2!N-l-2IodI*S=HonlB`ULsf|!Z+AWr??TH zb9WRO+h%t3*y6Cwk>uFO@I_lL|lQyMJy*|7{%9jiw=ch6VPu3|6w;es1Ic^w#y zh$3h_`T?*ui6b{;C)R;DW1eE`*8h6dY&ys3*gy;0OcftD#LW&S&?o|=rdut_4@Yd` zBg>ic$5zuSpSe!A1hB{HL~g+h;DRc5;`aByzoTpiPdw>yJ^VN~G>p9{H#jy=<51lf zxfieuoLp^rifx;zM!xz}sreajlOBvTAtErBDhIchnHok*p&DGT;+>;#Y0uPhD zrKzdrU+%na2nf@>XJLv_5a}Hm0g$dd(m(Nq*oVsasSNQkFUsncEeP;Z(zc)|F%4pP{VoeQMjFeU{fe zzP8moQt{P3J>4CC_9!LTdblW*dF#DChXJV8Huj6ZX)X;2Iu!{{D*-$>NXOj!r=6;S80hX~0|#Hs?po7h&Gq&^Sc0FV05iJx z)G>KmlJ#7F`kki|IDe((L2!wsrdfb&A>W$^_${9S*Tf06NXjbMX3^Fp@Pqbn#h{I> z4yQmUBI=tsxjHv~4Idc4sE5q_HlIGUjL^jPPjq5`_DWm`2-*ATp1C-Fb z`0p;jmf}c9gv;!nHLr%)ixHzZp47&;j3WTT?23P~w7#BflSPufFVG7Q?tgZ5&OTU7 zP|W3V;uro*)tJui|7D9;K{tIwLS-$-rz+k`MG;u5Z#M`kJiNnhw_`^Jn%_8HqVwuby?2AxT#j|704o(qF`v}Izr6^`G9z{|FR_DUvX){#JsP`vUR2&PjmMZ&D`q6iR~G9i zfAa+2X$3_n)|Y-QIjwGxP!a;Z|GY1fXZJ)JWrgAekqRA!ZKZL1GdhCWfLyp$tGS$^ z5*nT1M4Ps&pR{ZV$@_y7QXs@@NlNA{fm0L~bP470G?ojln0|r0s(s=+?(Cpr8w`VC zK%=C7$ptU)1&1^GlSJMdd*tQW$OEvluUdy!}LvoDV zON#xk?7p(vAAVn}!lRq=oxvZ*Hk#dC$n|za$)`#2L^IVGW$ZCY}*x5bLB0C{Q~yRjq45Bp3fLmYV^{gaBLu2?R-Ht+bw{F#<2O)?0-B z{++9Z9T{}$YK5&%M7v%XA;2g1Zc`Hg`X}1 zI~|d)i$M8q^SgcLh5WGW0aWN~4Oic6hYFf%^p?4xJsWb-h)}do?DMSBmwsOS(#~3?aGDSx6lk@@Kdh3wEDBbuEDOd08j6@Mr-{BSt71LgfHV;q}$C zlO%4J)gx|9g3;N0mVKpHG2ahdYVWMwmUH-To+@p^gqIh8-la3Cu3Xh{oB!AHvL?5K z^2RNm@%Kdr+ClCz)7lP$E71`e;>$W(r6+rpLg)7Q8Im;KzlR1`d$P27P3D%G>b-rT z3eG#S%7G;zF36&d8vF@`B%IsR|1%jV3;&U(aB+d%hthmmNai|ht!Ran(CH^ZHiVb+ z&np9Hs=M(aVpYP$ikyqf;d#+9ARH zLd_A`KF3`n{L7z8lnCV;gMxRiQEFOiUwF(ye*>wn1FX#^M|mTsq##V;p7ZOOg1cvH ze>`}`{lUrn{uuR~QCI8dqLAL~VoU!1ZR)J{pJw|DZ-_oNs_uc?WOo0?j8i|_?pf7g zsf+PuaO%kb6Y805`f~LeKpEm+}HY_&hpp`ZOD;Ta;|vHxUJxR_(Ovek}sR ztz^GHsQW@bVU5{w`zfrL z*C$=umH%XX*W%vx9yDX4%f25e4a}kfhstm_&eTI7->OZLfes5$ub^M8@zkW^h~7<)LDug$=a%*Hqo3SDq89w&^W&|L&*bxd&qeGQ5(L$B*6r=RdZNc06t z!>Bk?zUyl11&Rw>?$Z5%GwQAoa2@Hr_=zwMpw%$-owqo=h0@2@{7j%Yh z<2>rNwfkrBT;!tT0e|uB`}>8*r6CT9YmpVHySHhhCZF@VJ$JDVP4ho&wd?p&yTb!# z)y1a1c?CuVbm85&aZ+yFvwCs;sa<4y)0T2#&A5Vbp5rKra@>3**`Hd@P{GG^L%nlI z?~mV)K_NCmf<>HwGh~bZ*LI5I_3rl6{p-|fj_0{*M%|7Cdg!)P9kt#np||R+m))tZ zbRh=FNFGFl!Ee+b{~Wg*nL+^QMI2zt6xNwn@=1Kj9jm;9)TC?+ulz0nVRq30g14JZym$uAmdAehri>PC_S+AYsA=MHU7I;Q) zQ|3i}E!XMXAL2w`BkG(m>$rOTWlbg5pFm8?aVTgRr-!{IKx_qAOS@gZ6NI^%>oW4D zoDU})U<|BW5c;|s`22LSEGnUm)M4^rv9<}aC2RQfV$WI9kT}UZ2od2=W4=Ir+P?Y; zg(`=so5~ToPcykS{MQw)Xj`FRT>Z1GVXO%>N2PLJiM7#iMO<)cTSvO^7TJDa0kx9g zV&F6a5XH%;t|vIo%@+-a&jaFybc2`ffFq4j4D^!MpLq6)9E{vMZfX!N&h}zZud#G_ zV#a$P0(#aqtu`vSiy(Tt11?D%W5S8$f3F~ynM|b?m%NFycVm2sLM%u+I&`vrUK1>< z+?=vjI?w+eD8YO1lc}|?cp1G>N_lU z<0v|X&K5OHkJ0Fjl3QnX)bFbuCF&-RPIYI3$gWqMdJk7Hqh$82E&}A|Pu@fPU)FjI z_K$Z1s=2u(6!aKwT;P^lfJksZw0x% z=wPC!B2QJ)>Qb47EUy)SS%mM?pML|yBAV+(4oI;h&gFSle5Gi;+V;9BEY>y&@<&b| zEX~Z%LvBNNFa&brs3Ta#(@6VS%c<#krfS>XN8Z{6DMsmmodIvETCO)F)IPrZg9kx_ zT1FP2tYeZ^)m+UyY$a}Z4p<#7`cMQ6s`SIKFPg)YaJVNEdG`{0CwnBv-dj9>M`o89X9Gy*(;tfTi!VF*!=d_ULwfA);z{uM?|E-Sn};U8sU}6EhcZy zt}f{W7$(gQ&{x(F8~*AJ;zD9+Rd%cAtae!Az0K+w%3KJ~SwU%8Dtu|tv$L;6(7F$? z2dIZLO$L^i3N)2nuUGJi@Zt*E00olW9f;9OC(p@BG9*7<00*qWNBh@>22MsS8z0CC<$?kK#W?2uk$+-tXs2{1@?yS1EHu%eK~c7H0;YUr!T;c&iB zbgM#vtv4d}KXXdteDn&A@TXe&mUFGvY2UIM7u41*>xLG-$k|ark6nO`DrW|B4ctM)V(=A(%1$VoGbjjRLU)bs?#$e90_EeSpZi?VRNi zb?~dpTPYKEy05XDO(WWSl4)ZM+ZtgIlR1W#rtN*tc0$pkG}6BkGybs+F?AM zeK)oI>x?ASL4GfBxJIJK@ z)))*au!}?0+ET5jf&~6FkGf%?RW{EbRw*X!AMazow)@_^^l)va8_wNT!PtY`a(uRi_(!vj$ z-by*rTaAq-V9Un_e*juuzPs2H`fJtf>vM-IDROs--~{RZVMOB7Q-VhRBa||Le)H&V zuMC@Woq9#azD@wA_M;Cke|yMx1loVrkqq|F%HHQ#_F{7BWgMH~4P&EEd6KHMl-xpR z0sW`Qa0^!JOtbEI3gbBmP_8#}TtGAx4fEWk;V0_f8y>kVn!alcZ^#37leVw2jBlh| zWf4TaTUF8nfdYGOYJFz2z2}NNYW`@9&{dck58-Dr!EZ7dBSoHD1(*r#g2nxOV zF1B8S%t38!aAcL<=u7{2X0R~$8cg~ zlBgm|u7qk-q3Y1>i#Xzv^a$X7RSyt3ue#%$$>5IBCmct&bdyExVo%CzMuCXrWthrQvg@*9A(rv4~ z+40`IpV4c+Dt|p=89aVHHC#q6lQte*Wj7?Ch0F&2#Dq9z*~nXz(6 z$2+>pYzgL4J~Gm60V$LJFU<+zsiNh4P+S$9u>^_~c`^}raaR0R)W{AOfvD<*v#l?9c&E*N3}#|E1*0$jqkO>(h$zajt8K=UY`FhfR`*Nb zQkPQ8i`7z3%24UgYkVo9BXDFf+_S%aMmQsxbK`S23wU*w#CYQKM~BVP@v9yz{ZHlb z@Z_&!X4&IPVBo0ZNN z4F;uvpgd;FbN0}r%JF8s$l{{Xsg-ZsF>XWGCY@C0zGJLJ+M75p9&6~i;U^=LV6j{l zWJ$-dvf1=|^mb?M(KTIW*4;?-Z85onljG+-ZjdwK7X&FqM9mHC`)z?Q-y?7hRM^dP zfWn=fb!=JP6h>$vUzumCjft6I?2c`0Ru+Y&cWuM^o?Bc2c`4H+-BVeHa#k~q#3@CQcyE+4J>QV! zI7uRri)|+9cGa`7nK#1&yD1_t7aMG5NPa#0Bng~En^mnZ#76GxRce#e+8>Hm_bo%z zZMrJesUyVi7&DKm%Qd<6@DemTF^1x-p-t-ObM19!%dGM|{rk zrT@yY=Q%nX)&Dq%*uUjqethe;vbJVDb?-QmF9^wXNtx0;xIKNab6i<_(EtpZAs`e> zwyE%@@BaXuQDwh&dHfw)l33>4yjSb}(C+}!K2oWd)BONwHj|vD>S5oLSa~g0jr;A> zp!@*Y!`|*y3-%_Gjot9PzSygMo-<41^0m2Jt%pz|;<7`BxT&kz*arK4tuaL8V)2Gg z0=DJ>5N)+q=W+Vy>ut1Gp0Q<7Yhf2}7~0_pY2@B9o<-^fj{rn^xE4&RWM+k0>HXphPYv)?R5ZugY`pK%q_yn2{*Iojd;PnI%M@-UwQ zKD~FJC$~B`o-S<5JPxos*#D+*(Qdcez4{4UZ&4esTLA1y57q6!fpr?s?vW6Ud70t) zW}p|((d3ENr!~VV>mY9}?^3>@KQR|ZgB8u*JeAWVWC$It($b4A3rXxEhDrk;hrWOM z1W>v@Es{4|p9*bVKMdZUfRw=vEu@XR?T0_|PQACLPHDg~ZA>^omLECyK}wb0cw!B8 z<<*_!-RdWEGeXnb8Oqg~&fq9XzI+S8TZQM??K`;FU2b;q;WcHz)X(bg(z)vB#F zF-n$5&q%^K8@%p%!sc?RY8a7jtW=ooT}4U zFEV{|5BWpMtD8jCL(61S@&(F&m(TgvR9?l+1OWhfik_JB13q-|l?o2Fn6#>3>vvAc{uWMVes>aJ8#YCM0vha_9|$WfBq~?Ku|=z(TzH?4A2c)%z$djaVwFKz;@KozITrGg3D#&fCu_&c3ko?U;zZJP#$M?s@N38ElIg5QSogz6Yd*>8wi6r; zSSA9%u#PI~qmemM8DrNSDEYK;!4-`~BqZy1J58g4GRR`_0`bw$ET6oPWCQ8eL<^o% z+Y#_1tw3g+sZMh@*ijFIiUSARAC-oD!K4L$J;K*1HzK=-2jlCvJPydpKXGiR?8HP@ z>}4lcN05I2$Lge9S+w1KKPQJVm+UOl-Qn}{RV^>^P$Zd){U=cZ?zcT1-wNkVF_-_> z{Fd|E*ENNe`|erMLieEb38HAmh;RFI?!RtIx;#M|>H^z|7dU;4`Q5M{^S2!x4%36{ zKAZriuaxo9U!9Gv9)*Hl7iN!<_sTnOkdATN#`-w>3Irc)U|SqGm^x>Vc~k+c?KOjL{Wu#E+;H_g3s7oNL88Xyy zyN!x7@Kvx%0F_BB*Ex>B4lPhpT6dg5q@M9ROf4} zk@Ci^cY)Jlb?)m)cYc%JB7X=z5460bh!0j;z@RX7PV*+nNLm6t9ztfh!qiERcImK| zKR9?QGWv|~_xC~mldD0`aPnwhL;YF4#u{u(kkvms>b#Q6nca`$y;Xr|aW#U)MI*Wj z3)mHZbZo073D26Qv3gUz01zk6KXsgD^Qk6g5cUjev1K%ND7Sooi6;a+tE?>Kb&1|E zZ*%pA?^JOs}LY?sqD2UMSZNaT3{r_yQRzW7R?tO1$r^NN=YZp`WG3%yk&PyKMp zO_11yLelJj()uTd@c*D)K1Dey=#tJQ(}vIOC{u zSC`abM8`?|ap=Ec#gffU=CPBgthf7K{nj2lP%3uo==dgvI+xYY>?Q;%YY`y5nzI|L zX@@`IVJ6RQQ^x77nUrXaj*Q%z_w%FpQV9WH47?4N}xc7~{_;kglNTR@<< z_Tc1}n9h7kJakr%_c^^pVbp-;A9ic2XgEK90>GgeHE4M2aHp>K=OgcXbdX^;#Gr`naXgg)HaLRjpTo-7__X+ota11pHVi z>9R4y32i61D)Zul@Ryw?c)AG~-(QLSKmZ`s)j^#`O1lk@W(!|(z9lPQsD`=t{&v%r zp-Xw5UIR4aXxOsJaIXQ0&9x-8DG`UJG4>U{$>h?mb&C0}^gMVsA9MI?FlX$N1>|pnA7}omeNpt%PKvQs zZ6=Ntv=vb-sz#Rujs=e-V^KCnG-*p1pEd1Bhtn_`{Lc0DSLXPMeO&3K933!FtlU%p zq*PNi13%OY7!B3xL?oHHCm-YL_M`Lrn;ZUCFdi z^!>;c_Tmu%moHR10X0*D7T!@cuq>rZxpYll3!^nAoB{Fc=A zA>vdeQraNeNp2jz9xb*j0>=_u7!u#)wN+lPuD7bfSSBo0)^>EscFemu0$ve7UGePl zf%&j%)5&>MhRI4OXw51*eMj}JjAST?%3HH{(Uw3bO}GrcDD#Y29=0BXy!xBth#lgF z=?3si-U57ybsxKHbmE$s2ej@_Fjj3mRjLs>db#;&TL{CPk;2MZ(Xe<%X)jY~Gb6a^ zV;};8-E-$~+CC>4aq^zjupN&Sel$=YBwGnRYwhle z8vzX}Ud_ZlVi?*u>7mq(CwvYx~w_A z{6b&|?^L>cVe-N?uF3`#yiJ>OJ)pp`x3m5dGv0)YLnCRI?LUjBW*^#F>j65X5zJ1~ z_(>=Fm-qW8Zerm|}qvJJugrAVK6dzhQ(j}CrhZq>qUVgiNIT%E1LapRnK ziNL@}28Gz>{*Db^9aCUmDm^Nsi7PI-+F$5$YAv0OvOJo)z9TlZ|CmIZFF?)(eHuWP0og!qR8xhiCfBli5i1}0QDIfBg-+;^sXRBXb3 zwDXDMbYt9D4pB8bQTz#Q*TvWuCSZ$ijO|kSiC0B=0DvB`9jgO zyw)%Is!f1q*y^_ax4Pn#_;~jDLrOJ@yCVy8<{=cgV^(wdn0DjZkXBFi3Dg))L&5z|HlTI}l1_m9?Cauk>H>sTyj#jHk5Eu`A=m zcyfBT#RZ014m`V=@CT)|Sng)1s9~{80bYrut-eCEQ6S-B>O1v&b zFIvIx;J!!c=3B|LH12D#-|xWz@RGy(L?-c~z}mrk<79ojXD#0Bvcu(my{vXuvF)Lt zjY1t=J$&K7SK?Gg@w>6U{`6+Cd2Wu`W(;yCfbZqxmSqOzIK2pFj1_?85-+bAT@o4YyreF;MbGnbsKHJhX*S&ja4+Bsa~%AK>G3E*`_e zkpu~&6rLGD+sLse!3SOc1RZklR2U?Z(tkOSFbKP~$MXs+%H!nh=iRbY`v_wWL+_Ua zG<`}^aXugb2rG~4L!3eie)OuYLR|aGl7~y;8W90uvDC4S6Y7wpzaO2u z`Rd7bf9*bvL3!~R|GkJPS2Sj?V)|(1`850T?0Gv7Rn5aX<@M}xdaOf=)yV`}5OP4X zwwo$??@0}?+P)3fCR|V>+YRP0$cQ;rhuw{v6R(VaIW;#~9^piOmm`>2$ zOyEKx>BRt@XR|+PcS+v?XW|<0`YJGk1EelQZ)#1{4kjX`J1aZEPEi*>o%t#dO+vQt z;f6(0S^~uC#7qGIYzlk3#IQcgyE7qSY9QbUHF^SW0s_lgG?R8r%hC4(=+123kzBRd+kJzl?FRvGACk zsDDUt?zO-;V;G}ZA?T#NpaeI!oDb=?L82Iw`M>(VxqhKy zDdzZgU5=iM#`El)ntW+`-6EJ~RZ@nvy~5i%>)_{d?{o7X`e_tT!2x~C;Mhd|(wyCG z3OhHom^mF> zc%fQ93G3_QXgO(QGX7$ecUDxQFIn9spF(;Ia65G!Rgbz|q*I-nJ(XRRXr0h#f~3!i z&7hHuKx`URJto}_=zqg+Fx1c7M8IoYbm-pFi;L)|b5lXtTd48g+gpls?-NDW$FDlm(FJ6^jUHT&HZ%0AOQ^QSH}$N;MlPQD7;wF1&+}{931m*2bFkm5Gegu zPVfZ{20G#sHpC@)C@5v_!2iBiV{6^Mr4iY%s;NVvk5s7o ze4%r(o7v{@*>r}!)n^3Ea6RS zMN+GL-9D(RmQG&-enBynVQ&|Zf01&Q6v6BCYZlL=>IsiU;YCU?z-rH^dz zn-;ST)rKi_>f6t4^w4A|1AVzC6t@CAXk0dDhWk1CrSE<6b>jAqu6CRCTZ0~;Gr(o- zEl?8#oox#+;x#34oS3ZT!Sfb3v$E_Rma|_4YRC;4`V*qW#ycQ$tvQxEh-kDu;SEw5zxPstS$oMnjsVZqJ(-u_=yZE4^)FW z5<~6l)gY(`okgxnTPEMdgxiFZ6xSc#lS+7=w_>3>1F&fa`8~ln^NWmx=m!jno zCsTe~F_V^z)m1b z<;Yc`V6_;_U+9C~Xm7f889IXPNsB)JfB?hA%w#)Ty1+#Yf%MAIZrNPmrxn#)iwExr z4pwb>H2m${<~X=Ge0RedCEVOFw%s=MU4>Dw;KSg;A5F0@o~{;r5ZC)8^e>b9#J`d9 zgR3LVS6U{M#;7X-ByQNi3ya`~|2nASltIx;13GyH2dO>2ZWY;N=#g%y zPb?xqC+;Y%+5+7vpFV#+;n^izOEqpC+pDGM&E~{CamVAxq$BrUv!R&E%)9+uNW>$hFwafaf?m@3nQW?b?J|lV?KPl?zsHhQmVtt4qn^&3>RYGC`2I zO)9_Xa`+;Ccj8X!X?>gYh5ShtML2QNKgB&Z?42T-3ZHeZH3Q?4R{LCdXIR)@*9y#p z+VJZK{5fPu_E}fI9k&#W=TN}1nKb^yMlXVY(Q>NRhmhHbN+9==%yW&2UGbu}4@0+C zx;L+-Be!B00e@)myX)N)%F?W^-(l<|O_TygobEZNG4|)lg%t~8-SbhRvf)h)$d6#y zT5@AqMciZmBA&K@L5di3%tO+ z5g>xFahuozkEp4xp;qx+tN_Mg{#M87C-+&1dp{ZAQ*6E3^3F&#&Ob&z+uhOPFJGv% z7zR@W6knk9TX<6<7FbzPUC4%)F462pZ{VW+0B zV|T#@X}g?f(L)s)rRM^W@40Q#bESt-aoers9TK7q z8ER3L1WNW5G3h8E8%ecgK(|f$O%f`b=)>oKA#+Z}u-~nIQ(cS^2~yU=cRg*9ss|yC)!bq4 zj0W6>Rc+rgm9^I^t9gSaa`yE6zODC`J^1qVbTcO^%5IeCh5bdZ|wwWceC1Hls2o z>MTdGIHMt+rctb;P0=CaHsRzRWV9y(Z7pe70h6tFRj*~F zBlHFS)Kmcg@5>D}<^#&pV{u5V%q9jV`~&35VahW`pGBBgAe6E0(bTJVP4uzrR)@E* z63AfblgI)^4fMF)kn1Pgk?NlRBj$Mwx0Cu(PIRsEPudRc28+R7#cflNp>B!Yu7#TY z3YZNnTU6Y&Qm&VI31RQSJ)v}-S#6sdSDZ^J#cg<-%MVaBh=g`H*?$`yej^y0`?0<1-KMuGPTUT?gI)7~yg%wt-c*JKw|6w8Ngs50)({mcj zQwR=MNG4Z5KvH;Lq}|P?_gVD_ipN|;=QMm~O)Cq5QhJiw;2QJX zhlh-#^u4am zu*?ln_Z?O=B&Fr>>|%=d8I`VGUg2?~v&`h~)yCmB&ozcm^W5mUDQ0zO`~p0}U6WI_ zT(G|WOHk~K>GixDM|4A6J3SxlnbXDPulLRZX7hQr1Pjzc=bOI4q}G1d9E2>3OWeky zV>?zm1pH`I+qQNb5o1ii;GfC*Hr)MO7OAn#u-CE8$+?uxaqVZk?MbE(FRo-q5w-cn zv##Uc(X1~w-GWI&87KW{hx=!xer!u8^xYG&1(y(Gl6FY5cl|K~fWGNpBzVP1q^i$q z_Si%tCsPbw4m`2rOwY&fgZq7Uw~x%VBvVfTpQAM)vT8g)WwM7Z0KltJnvd__y@YR2 zYTsgG$pd>9B`PJp)Bg$Z z0;aQEg(_L5_put!E~GBxNAh<2<^CDOZENJW74Doe_3tcp38?A;CXaNE7p zncy3v_c5xhA!~25+jfV9^*Y%VF~RoDMxmorkygj&DQxVZ@O5mMh)yom6#i{svhXXq zo90DYq65|*FL694xioKCM*?BgG@Lh4BOSMwWl}^?V_EIdNlr`bZ`Mm+U}gY)|0Q(2 zg`uDmQ+aW2lb0I<$ET0iqB23qbE_(=G$JSh)HFtvsw0Ch69mCkOupi z*xMgNdx9m=ZkM;S>su13SE-${28l1Z0^#lH}CCZ z{55dMdI6M%2=nTNtS97-QGbWU?#Q+;p&x~*1h;K2?OYc!Y?1hc+}=N6HLy}q zfNkP4K2Sk#1fNKUl|55zOe12&;UN@$Y?8-8IxBwNBg-1iOkk9jbY!5DE1P&@wrdC* zCs6$^fbTb;j*J(XHA-_=pS9oRb0vuEV(sOdM1Pp(us0>a*9s;!6!_;(JfadtwubR7 z_cFUQeD~|C|I!NGx!!Ox)#c|koF>g|*PM7(9knA5fSVOKoSQ0xp^spm zOlZBfbyCEvZ(%`TxO6ZaHu5^oYic=Qa}C%eWv+c6G_E4EcF46$;y~x#axV>N2`f&^SVD)5nhVM^jg>NI<7|mHT zd)kiCYxg`AwWX0Psw^*=n@@}pffk#fOzPu9&X!#CSCR7cVIPs|3hDv+VWIlY1;`)YZFG9 zD~9r>ky4fJRoF-nzAzo~vKLt0V7&~-6p_7ZMrOCFdFp7M>Z|^&6-JN|PXC9q8mn5G zCp4OKTPEjN;dJUCq4SQ~`&8%mGdFlLk;~4IMWW7)x<-~(@i99aOL9P0X@7LecqM7h z=%g30{$^Rv+hR`Pe6@L>7qeJ)3|*8>k8a}Km4(%$ESj1wnr+J5x^csmC?|8Aw)vc2 znI<^5Jw>WR=1-pLnWuJ*31Fs1*F`4Xs3NvwkhYW?Gf7kU!7{}Cmd6?a;8V%2+BU6J$4~ftrHWwL^jE9E>q@LKJy&IU zrN?|^kY@Ukfp3E}xgy1O!BO}5rXq2G?_mE+!(V#Es+;E(13_3fI65<6<~jE(-e%bP zZ{M&%W=a>d=zvp^Z|k=nMJgluGaq2bj;)p!47-1C>54L(F#Vj)bLQPeT2r0gq=e=4 z+GHDS-|$Lhr%SVx z=+M>a2qPx|v}j|0uuGckn0bZFII&Xc_#b)Ile~RM{o;WxZ&6h++Q5{&4p$0F?p7 z_*Z=1%?Gs4JaM?iSSsBM28Af&ra;>V)sdpYKE?UwsXLS@hBRm4l6@+?ltQ!RkBD^A zlDga%oSX(POYMV_+WD7#epnnUxLU}HZ71waAL<6=F;v@F1Q#)vMPJ;mjiahZ6*7R~ z>v-QywiFw3!8P0Ulss0?;R}4hqp#|>sOBAR3KN2Mk7bx~((i^p z#n2F}{#Qwgv`!VF#lG7~l&Gu!mhQ&++Tk*_bRbme)YGLGa2R+PJlEqu9SPtMaUJpu%_#}NqZ z?>3vG=k2H?MdAYX0FzlS4X_78Je2*org1j*$0>X7{iRuG!?ElhZ1#^bjw34dGcnx& z*f`K$QmV&qt;*!^NU!$Qua(D>kq;5u7vi{eXN#@;8hgegpSiLXF*?ZRK^)R}uK&-_ z?iG1;wvpyCmu%^b;+nS0UETi!a;~A;5DSE*~iQQ{Nbyn1B6d zsxdL1?eBWhpXHbI=NmN>(#gf$y#Ek~O#(EWqV5AeM}mky zW1m4?R*jH9+%litxzT#}uer!uEQ4Qgn_RNI03So`iZk%5!o3flx~4 zn40va?w@IQT8fAk9OJcmbCFwl8y@HG5C{Wr_R82}MYelk(ce(n#lcOY0r)b1RR5uEzIu^p&i}H~-&augJne zI4+ig)eJLQ={Q3kP08|zPQGb|(z}<~_cp|bnLyv~xD6b6>D^lmoYG$DNi}d%&d+v9 zbt^Em9iGDOj17{OVfvL@_a4{;>|+?-?HMI<8<_Za{P`#ZG1JyiEdt{Hj9<{z;5Fha z<2d_CUQM&FH&ELA?Tvli4!cPcXJo%BZ%BK+pRLfbi`@OXTCG$eoAdVRiQ*{Zo}SEw zvzJcw%l^w%nuDa0mw2Z<-J(z4{^Ty@Q!7`eI=WnnrxrHEf4+WWN8K4;SzT5X5;@(h zU0KrTFtw^&1bOlQ36Qz@$_@qHFrfpc!>+!}c4?a%YO|2!GJ`t5 z*V-e&^D}KeL-q|~s_jq4$GyNcg^cVc*BUlL1=&|FqoCMmj~v<$ig$y)FGn(REbI+# ztMg~-$8G(><>m@w+1|wLy4%`=Qif%pp0r*ZPp_S47-lR_q`l6WVzWn`iDV{x%v$@J z?i@}=%p7ump=w4Ncw$#p! zf|1zT@5gl_70KM0!|!q04!Sj_V3%aJhOjE3LpouX%R(r>j=;7jq|dfOEs8y)^eC_0 zu2nAh^4^d;@LOieYM;ZlfMA?^ z$-3i6I+yCX3evm4+FN~VxW9l$#fWD2v0pBnPW1j`6X?gquFylTImjNet{v{VJy&qP z+OuFvZI%NTbUhES87^T@h+uK5+TPY#mgHpixxb3j*$~l zim4Qb`-n?|eh73+An>}}1oI{TDo>(rUu_#34k$WUTR&OddP zB8xqXCO}WDK+{oNY(B?ii+QnGSI@T~j*{NN1s| zuCUMzb&V>ck*IglR?GVHaetmu;6dF#HgBz?>725>vW2;-Rg5SyO%BAjk3AH`9^yyX zA+uNZb9R3k@V1i|A||T|z2`I5>~4Dt@Cm+`Tak{rKafC39$o$A-WkWdVeM@Vp9VjA#VE zA6R<(*D{iNBt(oinBR#74~D1krGjG~9=vK{xT*;XY@8O8WaFbdHJ>}ao# z^K)-ksehH(o6S5eG`yMbx>Wy$Q$Ba&{PlHv#;vDVB~^xpqd3-1J1SH{sVKZtJM4ta}!1aA4uwt5THzDosSn!BvvKo zvxGU-FbX8Z_(wWo+wQE&5~R@VB=A3j=+-c>620d%X!DX;x+AZ_W6-!>I}mhnciJ+# zA6UGa1#c}f*l>|Nr1+mZV97MX55a0pt z@z5CQdW9K%^MdCdCHRABKkAqgcU)MvE2eXPM)4tb*QY8_8}s;7r6;5^*k9s$uGI-9 z7kF|n5&nADd$--ai93n!xQ4eiF=l6>+4&i9&r%A)Ddtrm9-%YquhKn~Oe;Tt1={F0IOsV~saAGm{uN1Umy;$mDcWi{2{+Qk2(Kewz{b zlHj%#w?Q2l&497-F>2}|p_5THLVO&vcQS8W1^I3L*Wl-4+GsL#?Mk4dUY z3cJ|fzr1?iGnp>*7NPYvl8XBrhX|j7?9R9P!u8N}R%dL=5Y)W*r&ssm%k}sFwz}F3 zq>HALKH!LXHdkkTC~+vCLR{Pag}NE{+&ht0x(dkMN%w#AKz0>|czA4QKyvXwJy9YL zHw!w%af1%ujS~dVR+AdLc9zALZ$@{sqo5!5yNHwjox**9#M+dU_0%+Hi8Q{#GtFNn zQdVaSxqtoS+6`%_?Jn9KU-GPw_S;=zN$0Hbt}x&!DP0FlhL2Qz5h6aPm+u4^4DYw_XAUnry?xP*sOMlO(3w?JByHgx3_?dYX6uvDt#t zig814RyU2cgnx(ULlE#xd6n3d$vJG`S;*s<@uQVUK-cevcavY4ff0 zD7z^5Kk+w!uy+4;N0Fhby(>0Mk2|2g%~Nj6S@yeP8);;O<*Io-S?7A~(yLguL7-$& zj>+t1-a97r-?gx+t1vVAwJ$FKD&!6oO@B`_h+sC6>NDf%yglxcdvVYKCwst#!d zRmh>d|J2Rg{uoD|EY(4V+p>uR<1CCPu*(4O(PJ$TV`E? zCg^)Y<^HS>W>I1u!@$0oa31g-sETVHJrW6pFvtfgtz0kx0QWU5%A~0+%Z+PoNpc-G~z@TwJorgFvtN1?10&~=Tk2i~z5 zY|NBhi5X1aCMQ$A4aH?{#k?vCCY#kvo#_2NrQ7-Xzf$nzFMNY1+pI`c<1%LjM(>JH zACXm$n!y_p436oif%urm;mZ!T^1a?%;l9u?YzP1ll)qO`C>lj8+J?KiPGjAmItm3@ zd@#p9Q8T89UwlcyYW)zs={qJpWR*$WC9iNt_idPT2Eumfk2$&h#_)*P2FI*1M9= z`eUSg=)kCtGr+M5XoNXG8mA9ZKIC$4GM~r__E@{)_3a-fXpD!&-0cd~8W=Fv66`-g zjG}^dwC~>GF}F7+$ngm_?;W_k%r=ip$0g&Y`hCD7@q=ou4y4@aY0k~fp&Ce*3ZQzW zEs!1jm4DS{l0NuReoq8{JDla@v)C55!QNQ`?MRsK(Uui@lv&Q|IG9#m+GKM{*$@ZIeF9*1y5m<)hmIGcSo%CFFvb zVJv&iutT1d5pV95Wm1^iWYq;VjOE=6yFcC3PESS8R^Q^2=+6Mqo7eB%jeRib1g81_ zs@8fHFPyT?$1BIJ$zthxZgb+hodZr>6G47mJsB+;eoImK6^6@(CAQ9G&-i)Pb4qUk zra8w6C#@fk388PUWa}4#F6GEq!Zu<$YiOP7puJIYcCzT@jt@6p^Cc|LCRL#{B#)@>vnmL4m!}lt)ifj~Nj(^@nA5 z1ww6e^Wwm{zE|tjs#g< zxwwE96qKX~$#gQ9cdt8ToNq)+tFZSktNxbDooFO@xM*X%H&GBTKr;V!gF5ajtjI71y!c8hOFbl@DJu%uFIxB9x}Dt(3q)u zMlG6`XR>D5>3gmoj(&4xI1r}Ujo7UMzGTxS2wc(RgIVwmvOcFy&l5vG&q}oQ6U3~GJyU*Q~6TaBxm2S#6*LfEQ!4` z_e}eqII(85q#mpKVa#cF&O1-1ZT2xsf6+uX1%T<#`-M66F{Q`3L!g^j#&>B}%fUZ> zG^kKNSCQSRNLe5u@eYz8R}ZYhrh3m@myDTkXQE z*D3g438k6K4o?iUU1$D_r9&liXO@#mX+nj~A=^_Q;zxR%@QpAd++Y!F>~r50X~a`%+lc=`q@n%u{QnPjmj(5Mgww_8?DIrUK*o7Tjjbx5M-tXR3vcdetc1*TSr%+dMup+ze68x(-zy zC@V%?+MAmi$?-Ows5uuYCz*%|RP7eDDDR8xPHPo2AblNb&Gh)&SFZquUmRA0;f}Nt z7Ou5d1@fQ&G;`wFvpK3P9~abc=kA>-*}1Xk7VWF~+HHLm$LvdtW!{Rum`HP85K-jrm z>>n*lGDM*TJdV1gqOwTk5X0&mroX@ZT&MYRT;nO#tL7a%!){2Mh~~N;7X?}s7Z z|24z|_@>^U>zmK9u8^xsu*53v;xpFpLbKO3elL`6kASHbR4s-#o3>Ud^a-)7b z;xCLYb{=V$H1chDSS&IrCR=Wmb=TDH@F0`%6#@UO&~tIIkAJEcrs@V(JnBdHAMF9xdXGG%Ijz)sr#%(`_uxoBt; z=X#+&n^B*RYIqFLYEBRhbOk{^#~fns_4$`yE1M+fU6^Mr~!` zQyqsw?VcaPN;po~LP0Ygwp%>$(#=B-G{)Q?mg#)96aApWaYYM1%xKHG0l!2Y3NwyB zT7>g8itT@}n4*rP-#7Yz%}u)yd&~XSie8!{9Li&{ASqQ|%uDxuBR+p5r-Wjj zU48!)n@YG|?e>9atHl}wG`dNVqg4eSr8qh8rkKd6uYk)E8f?$}jg%n2rg!(!W(kh) zU5`ft?IYaA?E;O5)d9mM59_)_dI={*D97h_h{~oIr1uhR$cr8 z4UC@P8C)XDBO8$rEp0n@kuUdibM@gqhMc&n8JP4pKkkA%GA5b&cl}^nMT@BUiMO4l zXFk z451Hq>+O_X7Q*XH&efMRz?UsKB!M0A7~Ptqefje4hk-AK5kJgyn{m8uqXUICAw1Xd zRp12-d2xlGJ5!}$CJNf##>IQyo_ieYW9M_?aoT;!rx`E|!v(0-yILtNiB)XI%sY$d z{`RrVTqzirK5Nq!osF^^SD2e`@j)ZnZQaB3UoA54lF@t4l`z+z_=!ehh5tm4`Wz!N zMK*BUMB%@Y^=kC8nD{8agKrYS)MrPUtd$$Y9#`a!pFvZwrj`bmW7L(e#ujNW{{cw= zW!!;;|NVn|msC$PC8zdhvT`&L+bLJ!deE!ER|id44LJ@dM3&`eh2S zGf(hpDC_F?#nSS0T46Wbl{|be$}7)sG`t>)>(9C`o|=vFzm)w4i&+~0jrg(@W5{wi zRsjIgxO|IV#B=AZVfk>fT*RlH-Q1GlrXr%S)JH)H8UjYZvOdASvJx5t?KP^152 z?=9S-+P=r(QBhD7Pz01l=@da~fRPeuX=#y?u7LqbMN&e#L%KVM76Aq6j-fk-?t0G* zdOz3uegA~tdG7OEIkWdZd#}Crs=eZ)M6(*$>-@pSx_of_aYQ#+6@=5tVY)jyBEl-~ z_%+x_EBK{aRWaVo_PL99r#3M3IBz%&`8naq!YcNQGn>AZXopHCe57cV+}z`!adke^ zeO&@Q&j|DJNUoL& zZvQG_kZez7Ym>#;Ijh}l%gjnPB%+{d;pDaOoJ9{@CCOag={%T*E0CN+zURhA_Zw6Z zZV1&El0zQUSZfn~@Lp5AdU@ELU+_)&t`r%M3eo?Z&TJ zlgBEAl~V<2gosIRR~v97gEa&y3=}JvKe6;to9~WC^d;6OT54B@KVVZxC6G6+9rH6B zRwR!VX4M!kr_%kr$hCS=NiFN(swt4`e`kkgcGUcCWEf>FUHIc1H{qflz@QyzUbEVc zC9iD4mAModTW%zN2eLFz<*5#Jc|PdcwzK_~YM$B4@kKGe6mQNXLN;N0_`dq!OjNN> zOi28B{u!rkG)OsoKlU3dP5Dkd=9=W_9~;3k0$&)+HHd3uhe%KaTTa$Bs(7UAx3wr_;=$HWqNY%&)&S zlU9l)`y9y%UhTv3H0d{vQWIa2$jOicPo3#Dt5=jC=d}B`pYT_VY!etHF1EKAV~<5G z37|h!k!ndnJ8_Dmy*;dd1gm6Jb&VHX%pMX?%N@&3%e&yDrjUOmdCdR*TZ=LY7jl2O z&+=yki}~>V5w{4|qm!;6!lTK=@^T)t**Gdijb+&}x|7z6v&ES6iTaIJr@E`PA(97K zR^DRm7w5K%SL=er0a>YGnO^$opi^ckZ|nX8WezQRDjlh`AFMeDtZ{Cw)R@U4YWaaezCljX zYvyHg2@=B#c;i~$=O1mjW%Q}w8A@xH#&4eBnkAi7ZG=}RP}D7AO&xAHE6b$8oyMwI zXCjjqX;6M%XH`YC3Kt#99?Hx-LN;6=G)t|fRoE=5h%!|Rbp4S@E-;t&mVj7$_1FF! zxuRu^13Sw&lj1)KX=PTk^%)rCv=4=0gLOcFnSl}!ZIL@Ia63OFr5y#G*`vxfT+u6R z?F;=-zMD3_->BF&dug{5ex<`&-W-$=XAn#RItFHBiGx^Mu&SYk~Ty z=DngmdL-P);fgM$G9b^gC;^jpjhUmHr2r{FLrIJlSv4#jB6)42P0ARpM`l~v}m>9r?;u>#c8u%Zx}HljXP>|&*?i*fC0dj#KXc&P9# z<=n$J*VnH!>hBOhGm4(RV}>7`8rIHFikUl&C;R zubwVB4`NZ5IZjO+8FiClbj<~eG!UJJ0B)maZG-BJ<`jeJbuqq%GG8jhA?YVd7(NxW zZ5wzs$~k^WJhC@0=w{)mn%Ewj_v-9+__Rumrn=eB>qc&X+^ixJ~#YWxXfx7Xt1}qQPax2c3EM)Icd~XQ4x}u>YEw zpIOBZxSiO{gp39bDgOhQj^6R<^|mlp{O@w=`c9|T*5*529o|6{)sAkaG5kk1M6O9n zxk!4CSA*r|Vl!V6)dy>k=E!*w{15V8bnoc=|5GLTTV8H(xK{Xjfqrj zN=MtycZ70V-u)aqF-mE$w<4@LT5H;skU|&gGWFDSe_YIukSRtMmSj~cou}>#q|UWp zA90&`X9FG*)9;c`dN=*n^XmFKd+zfOhQdB2;z48r&bz}|*yOi%6%E_Mo~Z^u65GD6 zetuAS^qprCGuS6OOabQS&UW=s2Lb{$&eAyQDkv1>NwQ*o-{V@^q@J7}pdUB?R4VXw z{Z>VR-D>qDd9B_sUF+Mv`2f zA_@u$qR9J^)cFWPhLle)6KTz3pwUmkdLJT{!kK_fI!Cju7TUG=iFj;pg@yalI=@hf znB72py&l?~EC$A+n(5T6v^pPsW=%u&sLaQ=BZ^(sANeDWGF$x_)h8aO)5AQbo7OiY z#ohzA9N| z($eW>orm%Mpt~V#I(k%}e86{M46MkQN*5W?RKmOL?8|z^`U7NfwNH)mHy0@^G;6H3 zgq?-o)>Jw^=8S(C`^Z4a!7QDb9jIV5`7>hGj0~brtqPyEK$#KnK;(>YjZxR7GRynF zLi$%f)rdGyAm|>wso^+JFFn(rC5VQ$W{zyI1RSt+mA`E4Y!#X{31YCnqqWY0_<05N zrunLb#zRD7Bh8}{_%xxCnb|`G)pMVy2Z*~oY74*Sq2BKL21$PG@2YkMm>yA7>`ha! zp3x8S!ir@A1p7)^<-AOjU^G$TPd`T|#u1gs`y2`0R3K1(X}7K7O9n*a6<`<;=}aph z*AR^W&np1Uf>8Galz31UAf?uFT6#-x^m(9=_hyA%q8Dge1qg6h)gWPeklJAFo&T{c zdE`!$U=g<8Do&r6tBX~nxt?31ILsaddL3LiZmWUZg{J_H#UK!mu);-ti(Jn!^_d)l z9o@}CAC%ets?e>Jn4~fD{S%(%2v*-40`H57i}`vIiT7T=+NfEVCv~aou7G!m7OQaA z8V=JLBCi4W-@%P6Gv*}Ksv3w90Hi--+7rgwmT+)TUzx(RDHOB!T;Rkehwt2Pis0$2!~_uM?z2W@gA33{KFHQ$-0S|yy14hdPv$? zO00Lg+Lk(TK_F8?DM7G!*bo^Ci9pZm^&pysPJXvT6<0d%ZIYoxcMKmPFACX%fpJUg zwe>Q&2m42yk_Qj5IJ<^8*KA6Ln&`}e+%cqG>6{Ej>~%c^Jj8PV4{^loB5|uZ zY3&gQdvoCm?)ZF+@zxoqO zRJgDLmC$oR^q}#%RDnW!$Ndj*kcB2#A=W=xX|ZjOEn__8+#17JN8@ zW>EO3*S<*~+PzmRmleIS&laS=TGe0VR0));?}4}8KKUePkqwp};?XwE&YN{p(S~^e z7y(_>lh7M&gEyg%(NZ|4dH7lA9I+fP=2ekf2-Iqovjs0atuu~jZty=ebp2I5S!35M zS}`iODl7QJrDh)&zZQ9$?Buk4*(H9pbDJTQbwzgg)kaf`%TwpGGPjS8Z@vuLer;$Q zY&n@ZN?tF4a{x)Jve~_<1MHgYyfIO$>^5!WI$6ZJUca5G0dF?Xp+)M)XP526h#Pk;KXXVJg5naiy@ zZ$~=w$@Erid7#b|CgR~$(3^qy55sPQK5HP@bP-OthO6w&fCJO3C8TNm zTAq|&l>YVrHpqR)Ux42Dwq-h)AGI!bl_9sCCh8!;3}EXB&|60-R`+bkQr_cfQ^3lr ze1Ce&VpoY>m)EeF4>^bWePB zus~qb?9%FU%d~F*wK`CrDOEQ!w05H)AWsLd@gXY959JpqVl%udP$R*4diq5GKPwb! zKQTU{+99hxi9Gg78r*D^g>~%LvKs}`Z@uc+R_lNYme_WAg;$3_7cph_D~64CZks3e z#6JdsBK9DxrshB?>dO_Wat%YoW0rxuDi~paJPr`R?IYRH98zBr$OW?`XSPc2RK3bv zm6O9zj3Y_yYoUxOYC*Z-tg`{Snk@3sqFMalTFojOPn$HEx+X-4QPBECiS2vyZ;Oki1xZHVht0PQ%vK+a?^?7(MXwp?7PJ=BPR+w#(8+ZY3X3kbg+J!vW2WVN z;gia9Hxhc(IZ{H`nP4!+<)cM0S?K8H^K%(W2P{c>sG9aijK+=>n&^KVGd#&~DE9z} zu_qcg3-w>WKFd_a93LrZjXYB5VonFoyARRL7&A4CM#9#*$#_Xk_AJXcrnxiYfKH&o zHQuAvS#tO+`iQ-=+yA(($bX0;?%~3Ar~}a7_6$-&VT7HiAOia)H1%_98VCwGrLjix zkFAD`Lh`^;097F2QyA6EEJuRSd#-L?;^M`usIVe??-lxn`l`&d+WDB)BWGcJ#PSVK z@eHwLoGVuz>#h)wEzEoF0Zhwj#^*lE3C@1riUB(!#&Y?Q?ymF>1?!liQJJDK(}CUk$`VAw<#;Z#CUv zZaVV*l`=GNHp8?c5Ntc5r{n6dY@w9?6+gJh^XHX^XYwa>54DA1F~B^^%BBq*z3F}!lM8a|=SO&P+ zeW2fdEt_QZ;qBOC0DI7o<*c^Y*fgjgilM)R2DZ>A znf5YNb_Bk594{tL|jMu-%xPh-Sb11 zqPGj4R%p9fC;^1zV$!2jV$cVM?N)Ys!U6ByXo?(g^OT}ZA9!C7NDf}H_vOs?Q($`@ zYL(rUr`mPga#A$x#f_A3e8GgCgrSd$!e1 zoI-Sr4My&*SSPPx4x3qX7APH2E~Djn_nB+XHpIJAP(?%ccmn zjwe{pkKcyu4Y**BuF5`GF)McS8^<3p#{*5lq|_H&^nxr!G*2>rL{ZOLlu-=CGoe>r zUsE1H%E6=#vvDUwFa682@jcm3E9?{#gP;9e;){c{l!tKpJ`E;1@1|UZhk6RP%8dz% zwI%A=83Fq(*(%7aZU9s&@YXr5X;_Vv*_ArGmiQ43iR4tRYuSxgMg~`NXo4Mmw z+w(>LtON>$5;Pmfdqi6+bFKd53$h>Ngo=-N?#{&J<|t#}G5@e!9`U9ye|mHtckJN1 z>lSQ3*Tr}J_-d!?n9yINU?Z}rTM@do3j32d<2+HYlm8~6Aq{m!*WlaabgZM3#oopM67Kx^rH;z4vp}jEG>E2dU;nm|Nx`}94~6esUHf(hEbgQ5 zQPGA!`E1ii2KFF96?quWVFk4IeO@%D*Z?0-a|~xzv;s`BQ0~;+sTG$55c>Rpkiq!{ zKLTN&UoMIbnRV}JkL|65vHSVj zjIk}nAqf|qiepa@5dOodMW&3-k=a>#hBl=Fd4Uo{QT8jQP$U*|y12ks)tvld_617( znM&+TIJ=-|N){18YVR9d=|L8(%AzHqsR#4@M6|U%k}w5#7Zi5$AS!@#QwkA30k0nV zQr#x7RQj3ykLr}Ss}&|OE$34S@7vfG8zPMP?02Qs$UiCNa4mJ$I5O3Yex4&QGRRgb znDMUHeRd3FQf~gXPFA<~8IBJS@sjF@?41pHrzqroG#EOAA+-gQ92a>%tKqg+%|uaq z+(=y`bj{kTCt2CM!>&syOSV?wE8N5Dt8=Xr-Mac#tCzsd2~q-;O6YQLTFEL7x$9d? zU4^WoTdG`uSZ>@VtJkD~8oS}bQ|VM|-TiutEz^w;=!`ZWWzJ6pnydC!VSp=clWoTR zBR>Kb9fktrYhCr1TQjxaJJw@i$T7F22%*Uz&PO}*?TH0ej0mBo#N;ODk@}YB$Hww# z;a@OqF=L1fB_eFSF`RcFE&nJ=p$kf^zE1?(i>Y+t zRZe{w4OAjL_8$RIBs|gk8-l(VD6TF#v!!Pw8^>$M%PM%jKtPpGosOUNSoD1`EthS} zuzyj}h#EBmy=NN4a%>m~3tf^04#!E@nLr8>%?Lq(A=`~KjNT;jk}zTSJTzr`=Q-Dr z1I8Gp;)Gcss2Y5qj;coOYU86-^~6z*UVuZR=05cVH@`ODqEK}Vz=A>|4Fc4PgeWu2 zA6KkofPrc_Ydb&qS3*!tK^H*sa(EH>`70Qgdk5+xz$tm|T784{DWfRN0t6bSnH%uE z3)e$8=8Id$6C~^i2cFpOQ z&xFZWFdJ~66*3b)f8DMX-PkI-#aPMzX=Of=A9RA!Wl?Q4ZiSM+7l)|>ga zuS&Mzts9Q;3M3~8f)1qyVcn=QAI`3s;;EAZ)Op1Sb}6Zqz)Ps8>1J z;|4Gm@QcDze{uB1IK6eL6G*%b7OjP6nED_o(G%$$q^u6Qc0Vpy0fyra`8{jT;%v)8 zFaI|TfYiq-1<89eHZ1Rg>!RNz?1Ad!-f(Y_wJl>d#qDPjkRy)mH^7CZ<(se70THT_ zfNUCm0$IgzQ|kx}=BT&Te?^N}Mo&+ZGQF0KiQH3$J|BFg0rI=2$epsL0g5Cr6(E1L z@0|J}JXUhF_5@QGhEvWsRyr>^Cr;Jmfo}Bi2i#>Gip|jb@N1~4Oc9M>lfL3npYYX% z;{#qYwU5M(wY8osR;2iOwT~f-9>EpS2ch!i=P;K%^3iz%MB}w{w5tLLk9vhdT7gR? zn}L}Qh=~2j$)e%c)UKL4Jip3T^(b#tsXHG1|3PcRaU=)%AHXA9)`@%jM+c2M%OD^kL4<81{wmu%Tbx*)%tih_?z>jN6`~QWU%gIX&6X|Q3-|` z7<8Ip=$hz#m|l#eM*j^gnD?!dz#F(_AeWLc<&Vt}6fgPs@+Ff_g|5?)HG=ndGxt!@ zQe$$9e4}F=20KjbL-ZvoAWKV(O;oJMk=*Hz|1$#~>8cDF7L~+oMPeXJ^!W=ELjd6^ z*+Ayndz$IImt}vC2#TY1i8KuMidTU843N=H!BAooz&p~`+6RL=csSHyhre4+@l(y8 zC_Qz^RqGE-r~Eg>B(UI5~{n14=t`zWj=+ zH3I^j6Fi-1(Ki*x$S@;`h4a>qdixyVPhg*G-`P4V5M6-WY zZO`HMk=;*13l;$Jy+sl|ueTBC6CW!N>;CgXEp|8*Cg+=wfy-FKC-z=2nD(%+z8Tnx<9SJ%Q!84Og=x#0kYAczjNx{z0C~N9G=Cq_cb-aaPrajE#fX;zFNF%= z_e$JLc;U65Iy8lO#oLt4JE5r=s_&-yrL+p_rY~K&_L-YbvRZ!)FCQ#}JutUrkQj{%l_ApYaPnI-#lB(=wA9 z+x2LD;$p6!DL?_k-_Ml7C9dKy}{&W67Q)tB%B^bYXkGNZ@VFKwQQc!@kAPJK%aToX~DnaoV zY6M#4{WA$b=l*(0-~V}o=Wt1P|9O!_iU#68e}lpB3kK%jYrr9a&D@@3si zey1~}0abF7f{~#wF%QI`)bvlVF%wf=`Rr)H}W*I7e1B*&H1SxrfoAQn8jYZ;H#B7j_Y#k}UAHV3n6zu+VZ(s>@J`_oYiGM0R zODaTW-c9|RE?RjrS-QYlPg1@mlH%ooZ7^v59$r&db|YmF=hwa+38Lun1J9Mefz@IG z+4<58r?$>s@2jx$4x;?-hmtS;c{*Xm>x?=$1^hJL$lG|(|9rc~V-NR;>-og>>(E8_ zHzH^$;ZIlhzV$p9kVeghnLZngjq&jBX^|p@(>&^MLoCg6k^Fd?msaRMU4epG;2`=; zse9g|6Fu=*AF==5!Os1jw=_-6WJ%z=7(}SchW|ZQrL}36*$?U8+R7uUD5DC2s+9kG z+*4|kGFc_Y-wVMQu^4mFn&6*br}W39vX}s;b4eH%)}#Oaro*UdzaWM9`F}?AKy*AP zuqZ4gQe5i9Z1f=bi>HyA)qVpYYmkS8;)(tTa)mTFL-8Z(9np(NVfjv|F89q zq&PSQOonmyKTuo?@esd;PHFpR5Flu!kUlLXttTGm<9{$8Ct{*8<;v5)SvAjV|K1*Y z>5mte`sklwrrrQBsQ3>mHohh0C#L+*HhUDky*KXnH@n9K|LJr!A(UhGdv5j1TM4f94uB`YrV~yiW-4rbI8<9~lYVjbF-E2Jt$W8*1c1 z38a7hXDHwwvJuMDuScMC9&avn(LcYrhh{O;DyYq2Jh&9t|GaPb`I`MEYq;>Gs`KY9 zYoRevR*5Z}bk#{qEsSYn@#Z4=P`JsPcOiWT?0;|W6Z@mo{AdxSz%-W6AI}puYs!_b zHL+aRD-0+3GaB%J_s}$X9u;*IQvCcri9Y2b$#=tLs_`~r$&<}54zssQLuHyQzlw*UPAC_Rc5ktE=%#>Br@W5sDV zFS;Tb2h#h`X2ih1QL9LQgrs$&@7OPg8h<-#NgkVgV;OK)NcxecXe1X`@3@#;ZOAB=}r0O*XUYaKy zm`-7~oY?VoY5Vq*eE>77>`R^iX|{onKF50iQ-EP02YIXA7Nw4rP$KU!#UCNJvisZ< zTa|2x>{IopLpv@zB8HM9ZmUJC!J22k)!(b!mP>&RhvMZD!T*USaaVoGc zR;8c4_4BemF9)(wBGwKJLXZ!p?kHau%f1x{QvBDhFV(&TIxDLK>e+MV0)yfC+6pM< zP4Sbwl-#m$;Li7YvPd5HD$bP&dF59C=AHWGjsLSY(4l^+b!1QOud6(5A%3xT-XJyr zII91qB<^havd@sVR#`~;E8}`9q1bQ{_X;I~`&py+aGrRg$8x6(m4$&=t!K-TSm*a6 zfZ$?QYoO2yVBY|=z$h8GNpjzhQFs%^rduc<-4f0fZAIl*0O#6dLeocg%06#9MVaVo z6&QwF+o&SYn|-bHPw(jApE5pKlcKAE_zgOS_Fq|ldfI%VAHnCK&OnOdX;#wwkFYdg zI;lo4+qr}wd9Iuq=(U1@nO?se9ex`>Ruc9Ii}hcK4BBkOvNd(^?TpUQDwH6w^=tlObg0gp!vY|AX6>-~Sl>o1TEg zn&nz^Eis^YPNO-(!~=&aAo1P3EU=_Qhz4M-0LWO^Uou5QUV5wJ03v5E97NAOnpC^& z#haHYWy4A!258ugUH?LU(3_r@8}JLL2(01xt7=~P(Ky|21qOEBSPy}=z%l&rx13`d z$h@ELHhvp%_nOdpv07j zhr<8HqC#rx(h6~AzGSc=r4QmYwXuI(f)>pAN%C6~E}*T^Uv2e!bS;BklBS^AveYve zJEtWhH{ZMzlMnWrp>4qayKSkbNC*`34n~1zNcnidN+3?l(-%klqS^lN(C3AJAt=FC zUoB*z`yN96TBB)QYM!MDqNnjwTwM@eG8hws&RbM0{&%35A1n_wfeuZo7t?*b;2s_fz{aC*xc)Sms{M3xFi@jb z5jOYy%jil~mRT5b>J1P_WJU4sH9J@i8h4rBE!Mhtu^LE^uZ4R8$FVRV6Vx)+KlnVn(k#MXy zvgZeo9_>R1LRvd52IAAnCh%FWM96nV3QFy_7Rc>8|2W6{EbjvD)>DM@xFrB7JW)?W z;)}_x@rWvGho9>SvEsn7erF}wtMUqF^@M=}SUY;Z-I=I!)oblm^TC3FHs?veO$z#P zf6lJnJ4mGob?va-Su2UQ6UW7%>T19E9CaHttD|QWxDIIFg(+w61-2-P3^1C41APx( zS84PP%lNQbj_(aS8;yU4H(`GKqTig#4A=8etIKylQS<6oXoKR9coLISM4T9N1s=bUBn3zs0Q zjIPTg>Mhn{*cC#fu@Ls#mj+~&#Ske_;c0hI*hi%&gf)c`uuNkKM)Gr~^^lSL+Ab@k zFF<18Iim?o;ND5>D%2Zv;5S)+G4)f=C@@~)i~Z*g_0-qC$<2?TK>aq?&1c(nV1lW3iE?=my@pO zRhRQqdn(b_bu;s(0uQplm+qFJ1D;ap-oqhU3oRh>af^d*MfM67Uj;vRQF)Ei+(Fh8 z-}vzdY5qHgIdI-7ci>%4ex`WXr>CFM(?1eODr3ELr39 zXfoyq#}Ua1c(^xAQhQ3=$Eg(mFi=OT^$K=~C0tVv0>$NzFif_-Bny6&=X29nGMZ0g zka>hd@nGZXVnSR#7^AX1&2Dut54_xmR}sNRG(DhRI`!eVsZzvOk0v1Kv`k9lW#j=r zOda~99!c%~=CNZYhZ4-}Nk>KRBY-%fXC7y9qB}2Q_$%a@+t+WN*q*DMcgWXGonOJQ ztb#suFb(F7Wf<~(of?VyGejczV=}-lTUsJJax(>ptu`nN|6je$izC$s0 z@U`i5^gITD{EeXqHua+OK(fb^@eqhpK?Vol3514vLlNuwBjdGu+ZPb~@cXo6>I$kb z;^$Vt^$sYEeyy(u(A+Lka2|s2=JHuw3*MW>$^*r%J~%O($Y|a3AJ;k)ioY!*sAV9f z6@n)mx0bkA)r9h-K|NO4Tg7Bw`OeN-_p@lu^mACRfI=b#J#aBIJ`a!ye#Aow+&+iK zK?dfBE;Yy}n~`MZ7JwXx1DhRFDN>$Lf4hS{-@@&g$d?6HMh^%w3K_VsTy69$XlWrN zP;nM@!^Aq*o-DpLcjFG~OgzV;LjKwa&)X5USGE7xhuaK*Qx>*8^3eJ`YO%9WxIn8X zo*6xq`!#a}wei}@mfQJ!i$1~;$<^|M|R=)>`6*i@im!aXSdm zJuZq<`-gmgUn&C;=MNWY0xm{t@~X{}df*&aKnGiCl|FgnNkZrgh^Z%$6Xz=(Mom!h zyQTNY>+`@EQ&$Sk!Y%PgX)Z z3nmM9rassnobemM`{m#oG~#QG07)Ohd+YLdFqfRvKg-(Zj1#X z0ODh`z%>;A3!*h#0-LOBqU)rko+OQ}etv%S`mH&f9x|ix1Q(|RGC|h`+3k*HTO#@| z_0K=>%QB_jlHEeZvDhBYE$fqT%rR@GzTOH63u$Cp=FlvC{|+t<_Yi-AlC0fN%rm!l zz2)H^Sdyv`K*#!$8@h*ClMTK+_WhORHd}rykpi6BBUQEucpJMzWT~owtgj2VeZ0%Z zG%9Z0RjIS69W}A=MZB)jA2^OBCzgv>rxZ0?Z;>fp6{IOAaZ>Fa-kXFhZ6<;foPwaT zy1iB5B;1yQj2pJ+r!Rn@4Iqy{I0N1rowz%1WUAnTpW-W zS+m-r>G(_{gq(=Yf*w;OnvbS=9IiEljhI@J>`QX8hbWrG@z@5*CsvydxrSw} zrwoX=#I5${j$jv%*zrLOBwr5TtY38!^P?V-wMc6_J)w(^`L#Rl(izPR?*k@kyA#PW z8LkgMnV)a>^kLSieNpz{qQ%j;vDjd&;{v<3+$0=t+8}2rmvD8Ghw9Ty%?hiYHj;(o z3H6c%4fz`FlF{5a4BK03tkQ4kxG$@w{v1_4+R3nM#dBuGecHnyGhou}cmJy>#yQu@ zaA|2>5L&T!-`Ee>93K?gFGLg-DRRZe2&pHq!?Ie_`z1|l=MF{d9LjlJ^A7C?fH*O6kzx_@EfqYg-5Vb`%wx3A zhduAWeQ`KD+l^^5Sdcg>XKis|*V%@#fm>Z-zn=8v?XwkbrRof-R120E_MOtm*0u2? zyJPRsXYy7Tu8XhbSc-|d+lFeQ9yw7^ea|35S`M!tMKMiCTNS*pbB54;XgP+9-=`JA zL}qAo`37N)M{Jr zj%RABkJ+Tvw|!gF{Z+6-4P`cm!`f_hdqXUZ9F$Y7GdI8jI-Mpg-|%$;1vg|a#_(yC zTylz<`=*^A)0i{xOsbXST!8?_-d3p$7frVc-sz>FE%F9u9dn% zdpqNs6b4Q9tpvwr0WH^fKI-RIL|_f4g=R!&5W&GScNYo`UX$4uYeYGSdFYsAQmF1ia+z!MGoP@=#ImAS53AQAfbiJWaswUnwY^1 z{8EdA%1_)Pw&j0b0S_)o8@xQ4**JL>2?T7-v=qqAGhS@5gJ)~lv(+29T>wk8FqXBG zYvL(x&8lhn6X#dd<> z=7jcI;hlJUZZ6IKO9_t-zGvPz;a$6wI47nf6QN`Z?`*SHon+x09n%Z6V-?&k5C5s6 zx_UoKPEfXv)_Be2*!zM*Qsa?EV%t_Jx9N9>h|;aH8ar{Va)!=Y7hC>vg$_vj`Wdz| z$u}BS@cL5t>Yj^WVA0g{jGl~Y$Ri$tndc&S-)nWSt^7!?69YR zu0>8iTy$BT`k+s;n1+wm1U^-qY#gnt+J7gq@~|kEEOG>I(W|_>uKe1S>7I5e4I%a zMM#Ud0?mmYkaK>k52{~OXc$nHonvcps+6;a)oh@WL#!H=eXKLL{xHDLEvJwc`=TUE zta&6`TiJf+X!SG)TwD}NQi?VYM<1pG#weQB=e^(pn%$()3v2`e8E5HUdvFmNM%7~bpi|m^b@68+HSE96wK!o%c zMvg_a>_v_}-CRhh(uSm2RMwj3oEb{RRVQ}reY>mi0_SbUd!?wXZG^4MfQ1os5o3|j zWQ*rkXp-2a)L>?PCsOUq0h6sGwA54fS2CEtQcbC481Ogs%M25yZuX5;?Tm*Q?Fp60 z<&^fvqn%tq3+pT8o!{gGS*2rkmEtx${Kxrdf_yFN_xaaPG%-#5O^tVWw+cQLg|wUw zgkCsyzTXj`C_S{&zDTz^E~8l2AYA(Ny zNn-HgsyL9fE~EJUq90hh`y-0S%ykOX@TtIVH&R&#rxrO8Af_8Vg^L&3L%HP=%pU4J z-Y}KogT0@esCBZ}+_&#eMUvbCoQctAyQBr8YplV5X*q9yFwYj|UsBgQZsV0P9e+hq zvNXT!C^@Jjqq$(=Cn3hly_v6Ha{xWi8tUdo`-SIpkH@XkXyh>RHCwB|Ab)wEmwXp2 zik~?Y**_(%qACb5a&?qg@BZPM`9elNnaHbQ=LuVl@0joukLphZ^lCNwzQT7CoIdGy zYD!`SSK7|Eg`dqX8B5m8M-k`i9Px znhxag+;a(Oi^54tr}6|zC8RbwJBVAfad1iNr(JW7dbIyI|*SQ?uoM1 zu*1o!k&qS>a@CkX6DHoZ&A0WQiMs~ZVf{1#j51mwPG(FO(K0~mxXhDay~&WTiZ4u^ zT=akBf~_!sTJl#xm18w84Byi<`%2AxTb|7bBp;vIYmpIlR;>s?@_RH2ON{kp(@Ml^ z!(s{*zqS!Dg|o{C?rt<`yB@6#f5ntOaLbVqL_}ZCcFioMLj~7vMa80;gjAJhbZ@YJ zV0Rq8KW)n>vXMB=8!PKK8Bon)yvAr8l2^)^osgIenP?)L7hH6b0sL=&ksK$d$#BR> zI=HlFzCZX$@bMaK2Gfe{Fi|` z+v9_eL}5^?a(+2~aNWU)?BHt1C%mr#MtNDL#T#t5RBh0%YYpVBCh7%JHt%$M%io&- zO?*t9zl*f*F8Hm6h`tT7H^DfGGp?Wamew1S8O?s%W%6VEA!ZA*te7*?A z#XZQQUuGj9I#=n{?Bb4dbRk56%>4p9HkFAh4z^*cI16B9q}b6P)A)JrJdpwm>#|E3 zV3^liq11RHQ63tLr=^ce5x6U|#0{>CoANexj@aDAuW+Wg?ph4*rG@;m$y|^{_}^Eq;j1s$q=P7-fm$QLdZdVEg4Jj}RfhGgMD#m_F(C z5YB-H(R0SSEpi^~_wPB_&fp10rW0zrvA2CcRHtEL}@s&-+o8*)BWk+^SLAG~rR%D4f@0rYZN=PUI$`IP? z3(G>8yVeY;_xc+kVcdbz@pBXOlaa*H9*^neXtTcQn_{mQG)*3QgIGk*1k}}nyKN0x z%!}HcP^x}Ww>?+y*8M9`01zXEsrfBh39Vi2^Z_mcH9l%&XQ2)-S{NoiM2^xqQ+&q_ z92m&}V?=S!@w%y4C%kizg?+OkWa?TM1d5wuy2@bQ+${v9Myia|j@{tIzfJhd_D$hRdcinVN~(a{g=41J<${x|PhOGJjSwv0WP zP7E9@s-%~NZ!ReXFAIw~zt!wblPYh$2_zd$Nho{u{o!2_K)=??^r?2)TjAXZgmk~v zWkm2cN#x#t2ncR6D2oY3ZT4!c<&z#3;|6N{+BXBy)d^!ZD>yif3w!Mp5A7tPHa`OQ zYA8^?oXG3smOhYS`{Yx7F<9BBBF#6_M4#LbXu<7x56Qw6G;0amrW-zZsQwC?s4#AE z0@gM1;;hMr;71~h9klITu+{wNfCwgzL(%=NhJ43Ur=t?$w1W8BOF>4Kd=5#6nHC;b8VK${p{A6_tb0pN>? ztx;jAX=r_u_JMludj4|VNQ?@T&guEsc5t)bO{y8y{HUV7aUMwI`##OqsO<#xd)$tK zjJB+7+iZ_M;nC;;s^NyCagkMyGW!TKInk7)29Fm(=%t6S4`&~F{M&IR>mM2LYj^bN zXv~Y?9wOa0j||5oJy=NsD^IS7qagLXL7o5QAhCLl;U4jYdIFG9TaJe6`@o(QQ9&Ke zC#!K4i)%zqW^KFgVlf|wn*N9^h#lrx$gnkRq1e{^aB;Q;HR`Go=URQmBw};NIF|FS zQA^N-p<(_{Hl?jDiIP@&wUlXD3t=c=ru3D!C!p1Ga;N};UNy>d!+VqDBAE9)c}jus z9TCadnm)t$qt57OlIq{j-MZv!|gQW95l#B+YW6oGqN(#7nU-5ai`g3Gtmq+866)u~tSLFuelw7AX2sk4p4YH0~Ku#tII{7p>6Jt-Ocl zk(NI4XqFD_f8g%2wj9gI#AxmQ5%YFRpWWGBL;G^Paul?}Xd4h3_)9EpI6ShyY|4V` zyBKbt)f^Q-oU7=MaH#UQnOAgo?<>wbN=fH>mA=V}r)xKaAii*xb12e1)>1YO^S#1+ z*!|t)2*@2@>|$jme67GDo^Y*tbM3oq&jjhr$mUmCaLYcJKQCG}c4p4;{lrn0z*7fX zthsxm6zqL@Yd-iMpQB0GOPgbk$^xq6R~HHi){_9I4=eQKf%C(uC}T#%B?JrmAZ;(- zG|nOEu0ZBLD6e7RitmUf1E&k!-sHqKw*?Qi?{YkzJDPh_uLSR_92)w`3d7&}b#7@B z&BG_wwH|*5OyhFA=yp&WZD#xOBu}xO80XQa%(5B$S!}gy>wNOAQ>!R64hs*FDK=<6 z9-$@5YTH6gb4zPJKCg({pOrm(tPYQiLVAIXu^;nB|{DmPcD;O$Z)_0Ews${N90AhZnk71G&9iwxiZ(AR&x3oob+bFCTGH(yznJT?GbiCw%tX0|=ue4gtv2X$Oy2Ik-r% zuq`l_6vqe!QR5Tb!J*N5lJ&Xj-fg#ydHV|6xM&M4`}(y3NU&S`faQT@Kn;s(Xa~Vr_dR;AIZsN%8a8a??ex(8rsMlAe8LHdKIfvRK|+zSwWMVuv{1$cb6$g6 zmaed?j9WQ?IilV(F`Qy!*gf%xBh;y6=lohxY_Q?)TG);iT5@Qss$MPU8>hjBhW$wfJKAkUBsLhXMEa zjDVKUAXb1YwgBIgGp-^pV{ayX!!TwkO!u3AjbLJMOy9oXqM|jv=-Ud16xOOmHxdK$ zP07_&;@v~NR3ttqpi_ukfDJh>)6?Uitrcdh58R-|u}K<)tVps31ryjg+)7N>Oo=(hV{~ zT55DC0s;a8(k;#Cl$?lk$6&P5u+fac*x2tm-=E+2|MB2F@B5tV)OF5n_0SA#<5ZZ2 zx>-RzFN_h!tg$$MX~g1@>(jOI-Hd00x9*Oaji)>@@*H%Ke>_&wbrSwfRd4w`j{qrS zY2HxamO;!cJ_To7X_q;11)g8L0@Fxlz-%@T;pUvtF2W4Q-k4S(&Me|xvkro~g-DV* zjQa|)laIGu9pZNHlTWh%eO~MqpUYy$_r8B((qAK3J+~;2xqG-yd*eo&Rl42#(O1>} z%LIi0w-2GX=x+(Prm9Xm+G`>FTcU!dLow_-Pq^PW^?GIf0A66~vYil1x!?ayb&uJ< zvmf4=Z`K{_6xJ@iv|*ij!LyziLOu>-6gWlu&*dl~Z6W@K1wvi6A!~D&%{D8~X@Byy z3W^^#e7&yuZ|dZNXH~mXNX4_~+Rq@F-o_7bUv;nGe?s1mOvBXxXGzI&5coN9r611= z=W1{}cgHGxJiZux&+lH4&A{QbR5M*s3xQ3zb48c1ihxwt*yFo7BH3;dywl$%Z%PXr z`o8e_dJz<yTgh{u{=>|5+zt5$jB@)Fe)zYRlC7>)pY*RWf%-1-!B%=wp>XGJQzD zwja=}ahdshT{3}B_2d7}Gl*JGVjFn)<1-nar|@Gdq3ZwkG(5iBQddBd@~k1ei^CX` z)Y!P_wiLVQJF#r?qCKfmLqE_A|JLzies#gw70Y}T?r1H>!^KNsrfwDQay(u?6b)#A zHzbE=_#&!Qx+7!d zzilI@b4M>(Bu&Ry*vW_@NXm=i-TzHvJ^l(+_gQ$zdorV)M9q?7JnK)Sr9unYsw@w1#Wa6DC%4!tme!UbXW{_GzJszdkeI?V||y&SN!9(s{#X>&S(H zT>WrV**hmDdfUg1a1>GOxSf`m)0(uf|(_1po)=i)yf zwi=7_jmp#f{1?Fgap7yek3r^xo|9cb_Um`Q|KFK>rDQT6!9Ha!7@BKmUdS(zYJ*Xq zSXZ;OGV0 zoNrw-SN~u~VZk1DABzpDKD1%!{CX@oW7nRZkJvtN64 zFCXjH&i3-k+TgDA`R;HM3Pg8Z-bh=$|H)rt!!A|8ldlC~d=ZC4kBKki*V+RXe^-2Xe9YnvW z=&ia#=GY@0!H$;s^?8=ksb%g)PU#088I#6r1#~{6Jq%ate8214N3H$IO%}WP?r_w% zTI?|Mh%U4gvpX+d9?H11B%x{QYxnQ}FEG4fO!%w}xl1OHXFh$Cd{NjtKXjr{jZxZl zcDYqZ6f#>UtQ?aj=`CJyZZ+%~r7*jXg z&sX}KsNeUg{Mdkj;9J0o6JuV{5J{st)c zUHSG)uwUfzu;Cqu;Y=FgtoTh{w<^JRd(s6IZ&W#Moycn1QeJIuZ`y^(3y)=xg8o{y znxy`M}8RlW?J~UOm zl9(Z3MyX5R9Yd-)T*`EQ)JR=qKEX515O{9Tz#)tjor{x@MjifCPNTcI_^7-{i?<_v z-rmzfE1ua?JI5PUz}F`1GeOUA74M1lpz9w~N~PLT*xN_mIa>@x2Br}*&XJAZNj~?(S)Ec&FJJ|*8MW2pMO95X4 zs8hW7miuw4bfpM(p)uTF*8jy`^k9bcdODjpx@q_&LF#00a=dy!1lX!am0t6)f0=LT z!m+6S+-V+ei_R~|SE?!%xenBs*!A|-W2!mw9UCu6YgBj5W?Mb*726>|?tgg`SvR?4lp1&W^8f z^G;5(oOI#(vggKBEJ2+2D#2kaWtCfseH_-YG|7>4 z9rjHDyTHU^aE;rq;cA-vvKhEm%4&+awM5xsJsSNZ5x;pfrMIHQRbA%zjQ87@5M!hP;i^h$uA)Enr%kXq99qS2eVIJ z>k~n>Y%Q+nDjm^iFj-aE@IrSOg@2q~Sb>;*g@n^x-?dhrJwNZ4@rIss5PQ*+4hl0f zou~tjm-CwS9qs3c?fBEL3@Q$#0@qsYjo!AOI%|K`9mj43u?5yj!i#B~TLcYV-~m#f zGg~-6F(st^Pvs=+b)iLN_=nNjIkBf|>mw*G@Zm&;u$zh~^NnL)PhFYV0>z|HLgug? zHD|D!PO-?=K}6>GXMF7YrbWT>2?H)KeVgK?QEBM2cB#X5O-!&{Z6=SgpCk6!P?xa; zcid#fOm77Ec|M>8NwuzF-T4Qp-1iYJ>$5LDIAkxi?VcFUyf8^ysA5a^ohuJE^5_&ZPg756RBXinY_^~V`cg#&wUgs=6TbFAK;wb=Fa?`QRkw(;XGCWEX(;eD zUH=S70vFKFF|4YFKJI>+v7UQM#)>3MV1Tj3{B-CfqGk19X zDpBdwomKv7^O^hyajdlh^%|@z&5(L0FERSFIQONWZoXEmn}J3avtI zoJTGOUekVblYc{(1abH~Ff&;R>hz-FFhVP8#Lf4HL*I&DnY*bFod3~Jv_<`kq*?&1 z6gy03d7&S_VOYNo%eGjH6m}VImDL-f6c1KBrg*WLY01oEyb_e(9<;sQ zrIM}s_eWl?Ld$+*PvRU?q8+6aclliqiBmagfeC={yqfdj3s7r{J+MEQ>=Llk9nR0hbnpf0r+g|9Ng1I@O&@&y%B2zJ*tI{)E zosbJyLtu_ynD4gQluO2&s7}Cfmk=VrH!51JEM*KgE(l9S*$dn|Jc=x>{uf7lL&s}< zM6ZKf-D<3M-LGiyf@KfTZ4GA3Fm$H3IesEqo(gRjn)uuef8|haN*)dF95>2;@G%+2 zqMO{96hkG!y>N!LY2t2|HYmrbJc{MI@;9Te00W`0V#sc1;Dv%@6rwK5*1Pk4H1?P< zKAOx8gTAYJ)p_eP_#ixFzJ>_Lq4ua5-yvJAj}p@w9T&e_y9brM{7$mziGquG3%RxK z{4LuB9TddH{_JD;2u`-GwN|)&_d8AhPIUSBQHO9g*tJ3Us)_qrSaqXL*)Qd2yMOBb zsyw4;?`w~{iM?%{V_LO{U1f}2`8^q|?c}e!GQV+cUgTY+G7`}{v#wf0U8&f$+0Q3^ za~+56U2gAtKNWpkEBA_K`D(pz_fb}Q5%D|q=HsUBS&s8=e`eYUjIqXuvjwaj_>5_H z9*P)t6Y&6Cqk?0gMzXH22WqxFoTi6Tg%p|;y&c%<@NJF;Yp^LaoCud9be%bdy#)}z z`zEsq=i6!%nenq{+gK@qzJMg_w$=kX`Zc^r-Jv+UPT4l&Kb0y&My#DIG&Ez{%SK-^ zDCbWj5JfZdj1Ex>=KS@ZheF;K;|;JW>;9|c7pz8)r_J~MJ|aqQjC((_^R{rU!WSXW z4D>KgA1voqj_U05AjHaUqqJ*yGx`YJkNkW+9&SOxhR>1KO?>o2;|$NY36r*5 zDv0S!DLD){+2o-2r<+1gy|es{dwyqofL#PH>v*~W*fZB)Yp-3tz}b23$Ks{pRDKl& zH*cjmIrd5A*z zxU&w9A>98Q0Dpra7I}RhYdT0w)=3h=6qv z(xdL*QOz5Xzm^mfHy+YA^DX%`2M-tk<{+gm$Wa6O>Vkb>)S+}Vn6s~eFP8s>n3oT1 zSGXeU@!#~I`{LW<<;v5na(*Z8KWWKNMgcQck*X8#eO#fnR)6a+JW(qB7mphKq%YW#Aoj`zg$T?XTzgV*$hpb zC++=F8r|eS4@EOlblRR2z-8HF>na+5SPJS#tFCK3JzQlCUGf}K4+H(0%|E*mRH^9X7KvJ&{!yfakXc+! z;#9`Vyq6?wZb19F4p%z1<4RPc9`x@KzA-?q|Ss zhdDkN>B^6k%;kck*<4wr>z!IDo{b^7Vcq#omOX>n@P+hjANreYS)5=kL_P2hDGa62 zpGba2{8^!E z(fUm)i$9G6jIJ7Z+mh@jYemQY40*oM6LUf`ooVUhu zyYndu>r4Drlj%N{&e5rDEP}L^5baFAhkM+zZcR#Ve(MQMciexeR2(2AJG8RrNge4 zrs%+XJ~KLSO{5$je%6!-KWfC<(|A+3Uu5!32dvwEL@Y~xF4l1a?!0ERK+&}kh*n&q zqrrU^B(vlmTDM`H^j<-V99jR>K>5po%kh;8C4nRI4j4n2231>a;%gGZSKf{WV>45f z%(Wx|lt(KFALV2S%KA=?+^D(<7`!``|Mv$dyu(Ql{%9XWysjrf+EJsKVdQ)p^mMjC z4dbrkWIRZv<5!kuf2;@@pN>*lRZIEv0Zf=GIsdIj)h<-$NEHpvrHaqr`asg?|J>kWBDc#X(1#a>T&fELUzior5Nh3Zn zJ$W8Im``ND85PeqYM}iUodg_dLBI#l4$@g;%d;^PnH5gOB7AH0vj~&Yi&FPyhqb;k zzh?+$D%IEVBq(fqt7TS{P;@MRI8-ni{iTh2p&eYn#<=*1+ z*EH^%hzH`o2G!kvziw0wZ0S;51l*$HwwALhrNoVbg_KE2&GdAPz?&;BZgXt`LfZN) zm=;A$0}bnzkt(72p7Dw2A zvNM-!*(0-bJGt3nxbUov`O7ThnQl(XMt6Qb5QSQO>*kEl|4T&;EacH%K|VZMJ?v^4 ziHj@%GTmfO!KuCJ$|a-b1ij}Z)8^5JXoZ{5pJEr9hHuM@*iB~D+DjO>u?9@-BEI{; z5*dZFMEr)!sypS+%Je9N1f{=2&H`>${!pE<^WHJjguBN&o3?n`BWvCqy}Yq8lwECc zyuqOyW12?z&$a@WfJ_&<>?O}ys+Y+EV*AS3H$MjHiD3~t85o<%o@rgp#xDI(K?BpZ zU-e;<(U}jNP=)>||IOd|+^~Dj<Tl0 zC^|BXB_dd2*FFJ;DA|9sEN3qi9l0;SE8k-4s5&bL{VjWjOF~{xk~&A|C*-RUF9=e* zbfDK`W26EHLtJha3bB_>V2^srkKIO8&%BP-vzH9o`d(S2%5b!`Y7OhSnqYYDpJ-Ly zNj2vd>!Ee*WJGe{caf3=00V_MVOn{H&kfWpLOz zi7UJ)l{q$Dzg{0ZM+m>OCGg27xn+tq)Y94!2$X@R%|rF!UVk{|J5_<+m!| z<(78E-V{aeTps^U)rc9NwU^t(+Tlv78$?|9^y7yH?z1c|H}wf#Z{N~?E)7`ab<>bh zp*8J=K+gT}Kb!ZdL%stj=oxmWr7I?dhsf7${H92b;1TbEUJ6>dV1X#}asN}{5V1-9 zJ||q4a+tAF>C~d{K)rAM*0s~ceQ0P;Ve~Ml+@oGkwqgS zDvRFuVaH19^ct*#V6Ex#)R}~?5H+*Lk&bURq#1uOzrkAue0b*0=v2#Yy>awLNF&m< z$Le6h3oivDueV`4h3+QPB{g&@t5YY!E^dP!=zQOfASnf5Eg8Z+wS4o(J%hujJNoxV zD6D{nwr7AP#Vga8y&l4=JVn82YOV{-V%H)dV#&JCR?3=+I;O~yDOz7%HV)J+0xKBa zEp<-pcL#SOw+iACIKjW1teDpQ4ir}sXcAtS+o{-ekz{;v77AnQ-37tfSlrDU&MVJuY`0vloE2$f^4aSTh`bEq7%(5V3BQGG zej6ro3%V4rs6_PTi<*%K0fFO1VE_jFx2MjFh`gTreK7s8+iGtdN4TvI+SrC@|K1uc zcZp2#;@eULIMh*fJO0op*URDccM(4CggM6aHJN}Yf)bDDtukYX*8cgCnqSd@f!3Wt z!+K}5x4_4-Lt=JSGwNq-HZnNby218>;>KhJw@*SmEz27oV6RM=Rcnl zTpA^r1!LNlZ0dY_?|s4sqsq{UoPYA4r2$=3nfufxQ)N1>y{a$peC--?!z*>}QE9`{ z#e|BpVSJZkA3;AeZ32>Oqi>#xsHzWwTA|9WO3JN%)fXCGMix_4$cmjz<;h^XEt+QT zRg*unP9b*nzR7zT%_t#fZ$6PuXrx1dzo9vm{H=Q}x;WSME}Ikj50Kaafpa$lrD23umkUlgbi(FXKrdXrnT7v8)N zZ8a0zsecv?KGHVhXLF`vLFw#$o~K9V&LI^&EixGsUWP>mOn3`yU0dwX{b%V6tiDm~ zd(q$zE-dd<*#Xm^DYo6$_?ESXyOrTsc{{=h&*H_I37vCFmaGo>{cUlGmrRq2bx6~t z#Z9PI;bQ3?(SKt=`GP&2dF6DWFdsNRI*X_=rwUnTYvMiG%`@~Kyz=)F$_62Pb+Q8=d*L?&2A#Z{ z@`9V266aI!7%ncASmxAofE=y)ZM!ix^MR+`9^uu@Dw#Th z9(}-V&`VholrbD-4?eaS$|wY$TUMAm{WUUTpG4q{J}EA7+aNb=^)I5&i~J}Jli*6q2)^3`q-l>B=!P(T~n#wVN8H*~8u{d#ez>xfA} zzq(u+W??S_59JJSz-ip50w#Qak5+g)m%dh+__lGQO=>DX*dZ~vQQ@Yp_K!ZnPEN5s z*ub{}x4Umj#5LnMtCo)9)A%`CP;B@qlmNTUbvZ*_(O4{?(ftLc-G_E)Qc~WK*+9I&SW#hMHl|hY}WHqJUvgflRDW+JtP$k!L zdG!ugR6CBlKgVEh%{-2aS=fGjFoI+KdQiH})zdc3o8D9$N*$D7_xp7a?7R^X)Nt`( zC4_uEJ8g@s+D-i6*iZD9^yw<{VXn#G`RdBs&agmM)N-%+PV#}C3Xm?pU`%j}KiN_( za9U)^-3}B4%I2G!06s)<_#u3MMdVs`>S|rj3^VMA?Oi9_WVPo(rW~6LT3sRL(|46@ z7b{Gg$d>-r*n^ERRg+H+ZNl*dOL59N^Gpd9Zsfsx0Rj4jckHCNJ$?V8>u~XA%^WLV zse~sB07Gc-ulMT~QL0ouY61e9UmSE+_s48s3H1ax%3I~_2N#JpY<|n!f}6^%6i%Oe zp}%QfEmfBD{@W2?bfSQZrwHrXR(V~hi;hktBm34Q>Ztn2s`e{QLK5cZu_k8IgHAf% zHOC-8dxt0E_9LiJmdgl*yQBjP5V0~bffS={dZ-lRo;0j0ER<^DR+=|ec^8R~#TeXd zu-UPnS-$@yRj9GfDd}$&k1*q=ReR~_`4WhDF;S{5{4bnmhJQW1pAGZT#&tv0=Yl3D zPs1*O+7>}YS7hWS6lDKMrS9$X^J@!jd%AX4uKLMUYoRkVXA9x@%50~Z(&=_M-1aoS z_f5rx=t(CjX4$+Agx-v_hlkYB-~r0T)hW+#4?07iN=?tvamS6b;Z@CQZJFE&%}1m- z1uSZ=cRLC;fBJI7$zH&z#R&c0=Mah}YfAAON~35`Js0O91*HDA2Z+>{j#G~jSG-1+ zIlntD?3)$dSuig>udj!-|L`q*SR0r*YX&%T2A{WKmw4o+WO}$}WdTA5lWPDvTvHJt zOtpz?v117L^sRA6=W8~%GMB!>0p!_Z`4rJ1vTkUN6s!{h^ z#yW14QfZ)!zbJ=BLbA#+{t3^z*nJ^9DYf3t861H8hN4{1kBquVWtEbdY6-oV2o^ze z`3RN=QYw3Mj+G;jaNY+%*J(eqrQ3?J+Orh3gVB_suQv1B#sf!127dlj2gsoY&me_& zGR+6qyfdAJty)J2Q&_FJTj2N%QDGC}LVXildkR+)9fDDySKd>+5cJu~kZ5S(m_Yb| z<30S@8?{SwEY$+h8h&284NEU#zr=#wYVI{!0qXmEyH&9G0R zJ5wG|Svj3*U9w`X2}naZx$8%6XqroibOv)%m!(ZyhRLRsMA>h#jn7f_1!Z5G9>KXY z!s>jh9ExSn(vY#aWOVSON)8!kKSMow8LWRn#q`5xSJKb=6P3#+>_(2*hL7oW{|+@j zgaRG(UUILvxcCC8&{D!Q&^Hewe}*91$p67n*n~yCnB3PUDb7v$y{>v*C|Tr-32g`7 zj9GC&Ts{Jj<#ZGT z`&VjwPP5DS+h3bj8e-D0OeT>@_77q2s3x89d;}gJnYl4(2 zZP2G_|H*WO#+<@0%~Q=B&Y0nAXC7NqP{bR&z*?D;K)f_Na} zjNby_L=|#(33nE`wCw_QLtFTWi9&HyB=j=;o)0^qkBXM8?;nI0Y0Ybewgh@t`S(ib@(E75j6VDj_#r|n>+U&tvTtK# z$|Sud$JbZXuRotpyKwR_XC=V-^^t-RuOCOY&)S(VB)s>}L4M08?dSR|Nw3x8IXf%qXd{lU4qY5*GyolW z10S*aBsN(gJp@mAvl9AdsAl|<{pDcUAE!-Ul+ucjDIRYtq+o&@NjH;C8r2J83$~lp z8D5$strtF;MRb^tCGI+8EgR8?SMV^MJx43Q5onh4YG~)|?N?6T8M9eP*yW38&tJ`A zZ-W4|2Dec_6Z?N>x+@`QUEEaSIX?FA-Yi{n?3n-m)%Cl)$o2NxejonRzN6;fF^N(M zK>jkYykff{56tNS-v~fS-vGT8Yps{B^5(7^H0>{}viI?yevgZtrb7(F)pVg(cS4H_WpeU-_E zJ!Aobs@dJtb*)V3bzK)@gO-_(%I|33bZV5W0;-wM-h7oez?OI_)+-lu2c&Z`_?hK_ zg!w#BrF%%aTHq&tDQsLfSN@g=PVcVk5Ge!Q-u<{psFVLyHy!*w;6TF88TQeXP4@AY zEk$9=?0V6aNR2O%gvXIjvy&@~`Jh*M1GSxzZ9~Jv`!t}JJF={#eO`*LxYKe?%&3RP zI%T`h8G@rey-bHO@HH2yrgX!SBG^$J*Fz0I(Ag^$y_m@Va?#Q%g5`_M24Lt_yw%`v zf*AF7yRkjWbW{X!N~B8GZx^ahyoh^vnqw3g9C6R+ek)Do5tm)1*VC3X2NjnHg7`A( z{o1*4*D%=&mqR!d?eUAI0Gs?%yP7m%Nn5n<1=eos69k{wv6NDkEm%c8>+0URI`V>a zM51+ZPsfl1YK7AX1@s+|7Hi@g$hfk*B@Ztd0PbHo6QHc=UBw9~TM=GTK7u+N z6=c9wUod;YWs-fYSqg&bV54v75*HusVDxaFIo=NFqC0c1>HPzJo7paZI;>qy4Qa_b zoR3F}Y%dSRs{&JtUtOYHsCB22oC}CFX4+DDk#^`<2!8>SEIkQP0E_55?L2H0L}Sj8 z9}Y{tFea43KWFBU0l24lc(9&rBU0LTP$KB<6QXlOO&QqAZHTeutMEK+{)@wu?3QVn z-g~s``wDj>YrKAa*4Cvvkok>g`}Z%8gw#ewH?j#g7@h4_*Ms#z&eu;>l6Fwp~!0XHWp7z_h4?!q+gFWEF zlw<{)5lXgJV(1?yc7i{qhqs&`bSAIU=ldMG5TZ`5Pi3=Ab1e+%e)lrFLCb^}qvn@9 zQ~Gne5+oT-P+XqbEDK>t`j4TN*a%Xo=K~TBP9OJ$|49V;n?AoN!?(6p%Jhj*;cBLF zdeg@xTt>FrKJzycB!Dv-RZHHToz4)Aa6{CnOnl>E`@NbkF-Z>dg3ynbfy7p^!1!=_ z$r@w*BF`v*z;xW>;k7@;)8V$np=Ii{C-}@%tZ&?JSk=obaWhTxU>|W*y*dWZ)`9Hg z@-NHBylZCmJq@cCQylZ#)7R*U`I?7?koZQt&l0k(B@vC0;+Sv_l-14T` z_y@?Oop-G=O=w2apdB^nkqlEj+PzMTB615mNXqQSGdkqSqnXYkevewmDm7rk$gM=r zyrh!w%2#Wf2JZokwDEZz6WbLk)pC)N&+6=tNEhZ(tgR)vT=t{zXvSA@?q&-ZT!}Kj2iWTZLaQ{x%Jhr4Fs2ll6|q z3;0_8VGE^x8Ne*!=)UD=ZU)Z_;!)ymtT@<<-&1)V)&l?}ndYafT~t-AAlqrn_nn&6 zKp`XZ0ft%e% ztvw8~-1)$P=sk+d-~@*ql~bAW&DkBk-ARd3QWZ=eie`Cu4<=_OZ>tarpmEN#w!=NY zb%f=qM2RP__!EJ(Oj)`z*0>A(7t!iJ9_s|!>0QaVlcqr}Ohp?zG*{CiX{M=dH^$%6 z<^Lc~we4uw#*g_&@*-z($9MAnJRoo3E@vclH5B7g-SyG`DIAY)z^vsYPoeLe7Viw# zYW0ERt=@T^TN9B7IilsF?9h+m=s@FiAY|#(btcovNyTPQLQv@rM~H>Le)$cjR8A8M zgJ1MNu4UUwt2t%dcXTw{S7l8q<0Rgi)RTGOGSGl*U!Qd!V|{7jz9&~VklG0;3TF4* zngAGJ)^2FvWXQVK7gMWg@R}I4nb=#Bc-pb);10dyO3NaMPsfrjjb%{?WxX$&jPKq4 zx$>iYVK9&$+_UNU%A~$fvvX-WwgdrdHii#ieio*uYn1d^)~hf?xB%M*^wd?2B1`Ol0cUw8pTo0}%_m{E&P zjXU*U|1&o2?osbKGzyKRfsn*_2_!0WYXk*dRd@_+o{ZONZ)(IIiT62LA7KRr&L^+X z*-8ZZU|dx8!ltjD7vTRhqtu%)+hICa(84~q+E?A=t;{?8v2Rv1W#DW3rqf7O$EGwp z0J@;CV|)+vawbjG8NHe$C;5&RL{Sf2`3O`|@5b~1vKcHEv-|t)4cL11LEr7S;@Is~ z|51Puy5c1 zh5o-Zfpd%bk-h52Cz1kx(^=D452pAjbal+*fj{ZB%1fWXqufy6CfXQU(}ff$xUJK$ z2-$L@JKeW#(0UD^#y@oDQ!mSYu{`uxQlak})_hsYwp2N=rIbWS<$^2lLwW7359R?{ zL@g)jRgB=}!{Zd>bv>)UnKLm0i3y)SO2dV+nI;F6P~0Due;~JVo=NO5fu5RTS}f6m zOdIlQcBGEO+cs9`tYt?*saMjAUo9leqrvBT2sxUkBUkKoTh=|de!@c(B99(N_O~A4 z;4~nmCWH5oCAo{1{cwfz*mKK`?~;rj5t$FBpEV5=7FNe9peLy*G`6vv0aMGjHjVcPyFEzF!g`E3Ceqzk2|GA=>L5e#V z`050fSY?BzeM1U2zv^b~rf&P&Ev?cytIi6z1dX{cJQ~Iem=EX$OOe;B9kzH3q){uT z8a*#EQLg*55k3-=nY%jF{$s<1r{ahBaRKsgaWv%rDTeieqymtk-|UB4R058N>Z&l{ z{=o6a*X}6{L+Kvqf|91dn?pfv3n`63ZNBLH)g&2$&4jUFuV3X_R8O3Aikqz)CMJ!% zZKTW)GZ~|PRA(||DB};pm6)`El@m4jSeD$np(Z!XQlKeB7or88sTbFHZ5F5ZzrZq) zofK6%8-88;iFnpU4ROgkCbiwiK{_7uvcJb9h0|I9|d7uLUh4G0e0itA@ z>NxqhlLbRmq3qJ=p9SS=#svT8`NLNMSeF8NTCjF4$X1loci9-3xx?MGM=G|Qwe*4+ zM~Kx38gAiI!f&NUU;hwfI=`vPh5N;C&4p}cu7br|>BEtk54l+W2XEYL?SML}70SCQ zLdipT?%V?sg8lpp_I?uNs~#58J$L)#UQJ__*MS2$HF=_teBVi#ip1>sR1)6^GS{h} z=BhB0O9~tY_w}S&*pU!-K_#_~zSX`pHE^{2fhM8-^S*%Fm>`UrRrS8i@yc5^^%BG& zO`~7&@3gweo|O$N?*toP^ry*wBkXSdV`!L%$CrPok^-b2ibGdzW>RQdxr+eTICbq_ zxX_8<{P(+fQ-CSKF1eQS`x4Q%qPO_U znL5BwpWU46O(RyjgGQYpezqqAO#!JJ(+QLhKbD!tSz5OA=hrutQ z=pV%tciuDP1mAU5?LSYylL_=GBlZO-3q~RuqnV&@m&$rZK>G#AIF-?3?Q?6i%IimG zA9u#<*8T`uD!)>K)s2V(2_COCwOVv$j!l$HpYyzoZtnIU~WJXc>T=+q$j^Y z&*x&i&P6ubBKm(2zy_evwWewr*jxT9OP1b3CqnJoE<2i-8RUV%A})71s(RvS!7Kzb zzwyd2syxW`ylBF_>9E+-EgM$$Pc{ReQJPHm?6n>(1ra{vCE9WkzOfV?os4+nIErjv6DEfc~GxLs7D%6g1X zTC-CB(G{j(M$F)Z5b4+DbfqzUz&!#WcK_&ienHn!jGCF#!Khe3Ed%yo#F9sl1zYB6 zn6x)oX3A`?q-Bg+kUh-Mt5#aIT>0M(GD-DN-G)x1%fg)K9tj1=lcd|~&1bK*D}G}8 z9__7Jl16w4{U~Xi6}T`UCf|J2n*HO>gW{*V+GL7`GyC|qBWSN>2$WCbz9ZRo<}`eL zn%QjHWYW>9_=)8*Rw1k9!8v$CV9?EC6JO47W=oItLQ#4=UFt@R@(Mc# zWj(vhAOTMVMmWg#6lV*A^c3fnUXbdwWVEr#N_(eVYQw@m7sOrUZ}Sef3&Y%ZrAivb zH3Lp^@O$i_0OL=LU^GMMHH~*rvu%gkHE9$Ft`(IguKk z*>v!-Iw2|ejGkCPC+Gq6*i{xJq&IWkNG)6#qVIdw*r1TWxCU8dPjtt27Fl7QD8XHCbe^Y(>D#`1tZ!X#(VaVyo@I>Wg(@c1BTPRmoBq50(hdm_9iBYlmT$!Z zAZx&D9PQaJcVKaff6-WQquJ1sD;Ox_1a1!M=UNuY?s9gb&8f$ARIyZrWfuiQo*IySfPb_3--g&+`Aw%A~fP5)xSnJz7q%h%?X6BLc%e97$oMzSYNggT)nU}QwWH;(_9~c5f}0C79MGiF{glm= z4rEiEjzyJ+BW&<-F>ZoBDAWD1QI$r)dh=Jxo+J$3*p<$;N6Fo|%Z|Lzk>iC)|H5`H z8GQ}-rcFxp8>sd6`rVQuZ$CjfxS}1uS^7 zFp(<;mU;esidqXwl(f^hFPq8>j|O+lWCFMXROO1tT9KD19VVu|h)*U`6xdpg&?zr= z>R0T28nJh(X%fQZ1BNq?<~d?xqcb`Dq8mm6fKv;06M1YPSLOQj8S`NjP>>1{D$ed= zo|`tmTfFG`;w?0O#)g0BrVd-`q6~1e)#}($JFFM6-oW{qz-7h+-m)pIQ)x>XEwj&0#aNiK4YIOH!alrx+JKN>EL(%AM}xJ{UB<2&Hf}~exo>==Z<}>}2Xg`~2f%SK72TUKf>v~T32lYhlt9Cj+Y~%gZKLbSY9cVz#las{q+N@&q z6~+WQYlRzDPMr?1CF%j=FBkky&@;9ABhYFueM!JyYR(urHm~U!O9)Qdmq>Ak%4^Zo zitweDh?EFLo>I0(0um2tQ^?1^?M=|wxeKx$^W81Vvp~jVfn5$EkcB-$T01cU|5lDa@wS+S! z#0S}{;?)1lJxDw`(5GB2W+*C>GE6sX^TliWL#SSNx1ElwC_yN$+c&t7>aAoiAP0gShq)NaZ;IcbkJo zhW?#!D%#IzQ|?=GI3@x(TQpMK!+4UA=i5zXApQ&(aA`S=@qgm9>(i8#I{DoXTd_c5 z)#n)qoeO|Sf{PEy056>vC{;@6xoDr(YZEEds)$8SX4vr@M4h6i-qcam7xqBMdtR1W z@#22o0~(ziWz~1^u*M};S#L`;r-bxRHD^HdC0|Sb zDu3@>w>sp;iK1u6PLYjBkFNt2wGRCSY9w@4^(xE}=bK{`uqFXaX?#iYo2M@pYC4QW zUW$5|BVyOb?9%m>egmoyXqIV)EOwY?U1%oJ&^^(D-{h7q0qqTzjD?Ncvz&sAl6FQx z1>7up5ogp(lS~O8qXkN`N9tM&856Yhf5!?E_|u}yTX-b<-iILog$s1-HY7*wm+JNO z467~HEkR;A&klDwLYA_U&aFyR4!+p}7N|vk5gE91i;`}Yq$Hw`(}7-4HvCiRbjEa< zMa%U$g~^m}^Y{%YNpdBCU(pvGcU@**KR1?qm@vmh5?0RmlhET7PeP?7g#cadVjhF3Wl^39CWshMH2!L* zSxYBqB)L?if~_!Rv=-yBBaP{WYAdXrB?(dKLL|9$|8$w#0W?!9pv_#kAIt>I8@PC9K6Ln8sC&l;^JE;}!H;F@&h|>RFc?@25o%^L(zg_i<%g%crk$V`e zZzG~i^pvMcB<|(2OE*{}oXoE!5`FZ-k=M`6Y6;HQ6N!fti4Y!vyF29dTh*O!+S5$l zAJ*%unLf>ZGbaffgxQbPSSL(H1Bk8ezzDLpCJ9@>kGwQmWfn+Jy+~UmQlh@zL-mu| zQmyGT`@cAVDFh+t zOZT`x7zqA%f`-;}qVhtDru{v;_9%a3TMW}bLrBw`-vK=sc=8aLB96fa0Vc-@XhH%c zJTJo&w^9j=FowFCbAh9P$=Nz*V4yY~SXJR^pU&AQ$N>pg0`T}-MG6IX=!SU)aQ_1k ze#!ES_Mj?x>`4MdS%4iud?K}C*u+1DJ4Vj%RlP)&C2;m7v$YZb@^o&z9CR%Ktpc8` z9di=i;dY7CCK~b!Z4Z%M`%7MvvQoVC-;!O+YVmI9{F@;v89@(_fg9#J;Fo)`4QA&F znrCS==iTZC%z(V+-Bijx4h_?0;2Li|6}iVRct>pcfL3q5NXg)nccq)?7Vr=G$Izeb zqBh}TC}i@tj0qX2_xH`_xu(W;F~7-`Ado8x`sOmaF#xUn&*T4caTAv<{%R;X&*TM> zboZF&Fvv0%;Ng}~;50DvS4Rg6po%)Si#dCUnPJ$r9nOEvwcfjtoZA_HUx{?OTn1{Hy_zzG~+I+TZtkD`c^ zvQYnJhZe;3WI0K z1dGki91=KdT!j9`jld%_zwVVY%Zu_!^T7(6YNi_khw3#T;pFTGPD-S+IO0Y5mS{D6 zJOc66s+U42{`9EdN@k17tb77wja1o-C_h#7DQ$Ei6SK!+kQp-;ebdJ6t2qmvJbIt;o@4T7+2Zqo{lZ~-INyGjef(d}Ek5-$A#PiVn@MmPH#_vF zt{k&JYMHTe4~sPc-;m>hpuR`H?sIUK`@K6~<^UNvnza+MRzzIyNUUvzSFr{O0n9${o>Mw8Fte4MmwuNwt#1Ml7E4! zVV7Dms!aj76?Ql6Q`&^fOTdJSX~T`AT6=^Y4)(qc_oF&=af%W_G!45{bSs)AZjT_@ z$+WZqX9c|#F%Z-A6NWx{089>$X*O?%U$9pWAH{(?x_MY6J(sKRL`6kGKmkEY2uSZuIw2}eq)87gp|=D=3!&$~6TWRd@1FO+^TM^{oa{1t_UxJ2 zGoO*4D;BQJ=-D17Z5!CQ1K`?}cltOEp-NoN`1=#b@_f4hXCUpWt_3V&Jx|paF-v=O zJPqtj*0WZfhB|YdFBHL&dogFjzAwHU4l8Lm@{DT6o*NL?Z(nEDTfftE2f1vA0XZN=!4ZcAmI>@<_wyui<_xkETuM~@!-{<3XjS-oDAMeHq7X7DUnw=Tkr z0P(@k+Xd$m;x^gp?Ph#(F1NE@Dp5LN?^eSLazxwAKl6Qk6xX*$(oP6PAU+Y3aM#R` zb#v*Mvs3hDGqJMVP>z2>!VDoPuM3!V^t<-s;m_>mJjP@OIZ%h46Q%*n|c71B$xUqGntl z$Alc6P;-GlzPH$lwRRP;F>^g73&2J827(AHZ8#7Zy|blcP@=r1V6MIE{QUbnx#Xg) zN=_ipxFhi(h4i0bsywm!F_6aUx?b%?+R!PtdmW;C0{GfJM;arHaw_O0c>`sO94pR$ zMlQmWqVcURM)TI`oeB8|=-?k&aA|)+oK3S z>aier)!#u>HTnT#>&?l~3UpX;C3h~ll2hzMRdok57+V1jCn+yGjtJy-jvCXKW+lM~ zn}e7nOv?Q_xU&oE_meQIFD_DVSWnV#Qh+gYPonqL{@-lTi`T%3BI;8UTCP`I^L$#S zr;AT8dasU!a*VtG9 z)$2nfsLt&VR4lpqpDw)8TgW2Yi>tdsaVnTm#-(DiGKf&9Udi<@(OV0Th0Dn{yqoiV zUL07j7qCjkUtj?mY_R5EEEQuQEnI-=;|AnZw&I)fURWV8DCL|FSG$)38_7vs!-TqO z_^)i`RBLrlFJcl?>cm~fcHj!R$-a$SYUg=1*c8A4XeXaG_+%Xw>1-bI9x&eTk(8&> zKS8#7&(?SLJ2Q#E!s!r-bFaVF@Q#vKbDJ^Hh@QRQZO=}-qwD5mLerpa`PAMlaJ1Tf zKhx!Kadjs)vM_n@@2fXzyq`sd;Qq-Oy0!97KFBE!Q1tIZidqa@C=tz3!v9nV^GFfR zxn02JrV+|161D9>$&;B=>+G1tcxMOa&IaxV?M~gJ9?z12!}+{RwIt^Y(2IbGXLq(b z9#>NmbRVAi8}Q2ZhTD)v>1vLVJ)6fuoRqkh^iIp1d!WjaMad5Fmc?~4@qK01zVV+f zk$FF*-+G2`ou!fztr{H?6^gwN2Dp7%m%?lmf=^eRW`LSqYx) z@14g=#rs(Wo7q?#IBt2*G0FE--g&@1;<}U=h7!3xB-{6L#b*_(L^n;n2LTJ-oW7U* zWy1jBshhT$y6(%@sAW|BlTXCR-lnG`G2r7*AtTB6D3DqL3O)({@Yq+LYRqM^Ag2=C zzPPUzwcA)=SDH4g;j6vn?s>|!+6{OyTpMXwB{DtE^XG!|9!%H2*WgQUMcZxLAJ=Px z;zK?=SPVII@vZl*#bg@((5fxNh9VgGWvRmV=kS}*ZC8y`$S+J2#xcPsQt6~_`PBUG z7kq>`2eml1t|jBIb*h)6*ntoZh68C$oA5nbN#wXbIPqig)ks;QUDtWB$oS%3B1>kp z--=ZpCCe>j$R)X{y2p|jsFEqzSh~^uOpa2036Uf45cRS^jM2Y_*x^_N-TPMP5Oe{y zJ~SkuZ&uu<2h#eEQ`3#qAGPSLhJmGXiC*{uG`J$Y6iJzIt$!B38WhWj_|*MmuUH^C zYV;CHG3Tym+6LQY?N{II)6H=`Ur-)#3vfUXF*5MzcAH#E zNzkbfsDT1%#Q$hH&x~!ql0iJ3rh(cRxtz=o(P^vG_p_9{n(qQ|Hzp z(_=r$%N9MLLudaE@P!KY@#vV!hyyv&f8|j@oyb=@((cXAemBe{HnqTbUf53B{P5`A zPvfDlyo=hk@F^2V7wBF{lONq^Eb@2&B_W-c)*mtyxj#1z6H*Ds929ei{GIr0|3q!f zPxHt3+>n;`VvC>Z6*vo>WpG< z{qMPOC*<2uxv#R}w~9@&x75HTuzRnt0F@?~TPr@zKdA;aTsZC~}v=>Z2E--10L?KHlaw z3-m{cA~TFbffb%dSaur*QWu-t>yw%|!YH02IdcQsad=aDi>lpv*5jjoY`F~WPYrkG zqv4*7@+0CO5a;_3zuD)K zxt8ZloZFj804@u|xZ`he&w5#|Pk(qaAa>l0;PAt#VOMHbHqm(2(x?9ipX(>(56>dy zb~LUh3w!A_<2rf|wz~#QUF%kB%twjGn3bq@MDfm;%8A^D%HO!(6R=6M8AH{)kWjX0 z>yzkKa1&DZip@*i1ev=#HC#dlQUh|W6|WpTBMH0PE_sP+yQBt}Cd~~;(m6;hA4YdkxxAO_ z?)83S(Ge~NaS|8m_qS|_pa1N;whdQx6}JaxDy-d)5?`)%s{K4t;gT%wcHv^pvPp^W zv1t|R&`T|V>qWaPIdk)srC}eQbq;6`*wjh7l3s)S6^AH+h3^x6h0h*Doq@B$#K71U zqgKDC2eaL4_gRTg?VXH%IV8y|;rDo5q>R1#@t+iI2(dD#;z$c>Z9~~IqY}5{>n1H* z`zefAlQ%N4OYW)&aq7v_R)}ei*Aj9rfRTS~9u4D0_-snTmP`C&)6k;Zq(KXIS%pnr zeBolBUKvOA<3|^SHCjO+cuFHRo#WvE-^TTXfaK!ybsagXWiDA(eyD^K%g5QF>J3I5 z6V2&g+`E_`ISp3vsHG(esw*g&EI(bk!U(a#AbNjvVnKItcS!aj{|Gr=g2CE#G&9E3v?s-1T21tm;!9HX1c zE_9j5+VnK8p3j;Vqd^dKgPH)E4iBTQ=_UIMs6}Ot)p#xSJmN#KP9sfbF%|%&Jiz=wE(<3!EOt3Pqv5(kt3pp1YV_uG**%WEkGRpa>8dw>@ zS#-0RW5dutTB7R5J?g6HoK~@Wj$U|IwVJR5bI#ry$}_c->p$YlVVKvM?ym7=#pGpW z-Bd8Ft7t!uSJOZ3J1rPq%XpzmX0JkhHqc~^rQ9yH|9DmtpzNnAL?=Yi&2Zsj?ko{M zyVB0yLr*ec7WgK^(3i`SWB>(1Ew`4+sc9*Ws+#qjR}idvm+mb3A!}g4+vZJR8)) z4uIEqhjEG!Er!My^yi=sQy3_<58$1OdO5LXC}&NlapHAbd3BqxS_M2+kFal>K@pUr zk`9lmb_CPG55iisAWUbdjNc#dPk}{7rEp*|4Js5hj(xoJ9 z?Ev_&4rKv|nLG7h-&z$CO0xr9C#K#XB*sZJNL9PC<8@;~#*~|Qf&p*b1-#L(KG~69 zQhCkv+IoY$LVi`oG95a?iz< zPQ?K>^DTdAwC0!KSh5B7n$L-pzqdL;dQXLc2I4n#=OMc0XmR3Mp@*FsgoX1F5Y_n`)hr%o& z(Kd}Cx(o~_4Mp-I5Ji)tOgG#)pqALW+EuZfF6r?!aQHO*8x`0`Aiq9WQtD6Gw=O|?3T?i)I>hXZ+nxgL<~Yps65Bw zrs41Vbdf%2Po2T<*L?AKToJcC3)C{h&+$=Jy(8hpw#SH}WxBjW9K0C|0#+d_1?&wo zTF_>OEd^G#bSHS6Y1B1Mk%QZj=A4=lV}cp+YzOuLi_h8H@p*RS#|-DsBUnrhq)i;N zJ0Ws|KgXsukAYqODY*21QAL&B??cD_L!zl1 z6ePcLhrt6INBj5+eAj=Mkf}QDURPDtPm=PYgOoOQiM#&cGRhY(?o8aZ{M9Rs$=ma5 z56{bxG_5qnj!G&>k5KIUIPudCi>E4Dd%N6{am=|DTP+wm_(LIzw|&8?C{eD=A+t>t;^^kD%jju zj5_#s4O+Lk$F=SJeSthEVj)*>SAoBJ>Z+w#iDs*}{t;RTS_Y{1>g_hXf1IU@Ar?VN zEW2uQtj(b-lC$`0l7fgCj>qSF-Nn)&!D{WbtIp76nu4T4N_iSc(zNE=(|TJw>Sn1k z_@4ZHKgax`>*a;j+KD2rftw_{;-xYXV)UYv7ZkZaF+P=$o*eD&LY}8z&Ob@PWr=SS%1eJ`;)a3yDadzUw{{(ogv8OP^lqhUSDx%HgQ*kCA9sBp)b0^V zicYv8TZlEAd-$pm@{^D2;+zq?#F!D^L8d6*f}n%tkCp`qJ+`C)1#(l-vV5i)HYDF< zecl;|gl_ym@4K{c$+!Id`6?Ox6Y}C$&`#y!?PgEI2kr${tPCHeFK;&R(e$d@IjREMI8{yEE@VfR|yofasR31wCQ{l>#>lV}2XRe)J9Xq+JC^7VH zb|!JqyOYzYepsHASTb-%w*H$4s}uJl=cR8_hV1=<$cy>DkL2uYxNl3F6{3rEeb)0I zwb?|l!Uo~EM-S&tF1i=DVE5N3KIXj*42fQY!6L$i>&Fc6%Ozy{rXcHk#PgoWt2}a^ z0sAWK<~sv{k?@!)q3|8|^8Q%CteTP&FCFUaas}UP_Gf8>6Z4kCqLHO$ybQdx-S)@m zIK8Bh{;f;e)Lq_+FC(?3u6@Oge#V+OgrGNEE$$*S1gy}&5aeOB^fn>9X13nb77M>E zp6IClTaZq(y{(S(gku)CfDq^uZJBmmEH4VHDcdJ&!#k%UMa&L3efURB@|yQEa*g|O z9w5nB@)uc;;IlboDYrHsrsqWYy~FNSJ7!owPr4+N9JKSTh08CM!5!O&uU+yntrXPn zm9uuzxCyktB^NT^g4B%b}+b_ z91B^F8&H>0U@PSA5!fu_r&lnZn|i#TR1k0{{hwUzUmHI9XzQJo#{z{4-ntgE1v}bV z7*lE*OSbN=O=Q8r{B|52{1ZuVk%WC5e5UeI&Ufh%j-cnaHr~YH4(en^jPyyP)ED>3 z?VP0pORvvIX~-v~b@iN%6nYy7fYcYCrY(u1HU4nuZ~S5Q9C+PdM3W!+p@SxNla;ZJ?%kKYAVN1gMZxs=XF zlNH!jx8GH>zOA4I8Cb}{=DeVn70=Qx4vSi^&(Yzh;C?nT^oTw0s`>_%67GBP7gyp| zmZloCYMM}w{Cx55x5A%zco9AE$)P8(ZQA+>^X`iTN1iQksoo@?b zvF+4A@g82szPe{46|N%{?jspSq8zrp{vn)E*W%@O+MZ4E1<3_AZ#0#$036A0g-(A; zt*Bp?yQ0;*B7g@O^%h@*1YBxGXgqnI7cS@7++H2#0KOG>O8%BR_#~rZX}H35Fx7Q# zv&8eSX^=Pr;Xle}DI@ZT+v``MqmburFzbmV&RwOLupO3VcCM$UbLi&IN1I&IZjPCk z>3}A6%Rq$7Y>=KP<`|Ty?ML-fWu&=|oUu{;rH&uKw?rrwc!6N4BZ?d(YM7_TpnSs* z;eORfHLK5z@K~$wHMLDa|Jd0eJ8qq>0*CkQ*h1$a~pHAn1a&rFZtDU~6M@|RH3*3(Anw*X+eIZ8U@z)7usR=%#iu#U>65J)K%RO7c&B+~xk%E4LI zqKw~nS3P1K5by|x(Vh&k-}50k-$L5OzDhU`7r{YfUv+ z?5sZbiiKBgM48PN$xk(FC|4Y)fy`pVVTV0Z?!j0I{d)ZP{!yu_tiMO102irnV0Ycc z)};2w4}wcsH{oDf{%$xc>jPf&)AfHh{FU19%tR$ZEPP9o!GTv;Zks#)Z6Es9=2d<% zK0?y7Unyhtor8=0T?Eub;JxA47{FRPgk^{D-(7w5@XBq~p${W)JcjYI@Pi<~t-ZaD z`d;Z0^1o<7J*<8!w}pu@RByE}%4pS3SK)6(NLw{vB2(J+_p=O|MZ3s>vLeo1)jneg z?m|2<_OE!qrbRl`myi!#WHf&sY?95AZTDol-9S*>+_Oyvscrv5iU@phXM!lk-*)Q# zpj;^Hri92$_Wq^G+LFIFhha=1c-3B6|FQ~878fMFQ9UTdw;~&{ffr&&Yt6fGXEc2~ zD}9G18VD-MKylsAvTd|y1daPw7M_Cz(^gUOE>#E6=&P;QZ59o#;I<5jR~X%@Zx1ef z!m@iL25H04C7ZdkLqckMcONGcQ9Coh4Jl`uCSn4c66DK}9NVRH+3|{19+Vc@#OkeW z@cOyl*;SrpKS|v!kQcXT%-7^^?4@2;KcQTn>^pAXAjUYn{tGiAqB>ZJXiCwA64rH1 z=nc^U59f|@S+K!y<+rxl3v2h}!f;<%J8J#f&MbFrx>cQ!vRytZbaId=EsX4SC)Z-w zskR6N@|7x}?53mwfd{*;OB-F-pRN~i+s$oOx1cZ#wO!gbnLImm8unyA4SnCHIu*TC z-9hqm)oYDx(x!aXF4E)bm?S%PxhWwX)w~o!o&;g4DFA^ylXwT@ z!TpY%I7C8Ic2NXn_YKU*PRx>Y72UcVRXoKQh9Y@*kKZ#k`xAGq^_6qc7$IFbVc^;4 z9BtVh+c6XW(AK>yq*ksW&Z}2*Ft0<{SqvLA)xlyv=#isU8QY|!$h|BkfTmAE|EJ4O z)FbGY$8Rx8hdoAhx6pH7f>qln0X~S6Z+9Cir<{dN&EN--4DBA%?CwbtkBP2j(&En2 z(U$O~&r$%q!`>uUVSghw{YS3zhOte!gi-5FpNVX3h28lMt05%!CW4nD9CrREm+aSy zGsflLrij+=ho!UMX;Ph?(d-HbLV3@)DH{Z3Iv1`j-|tbC%T*F1c?Bk8BSM??ZJ6@& z++9BN8}R+S?FiU%x5UWmgSYjY!+2yf_VLbz$cw9wqOJ+o`poyGDrYe)C6;TL7?nTy z0uUmkTl1UrvH~P#@>-`9*ilsx>qh$yy%U(v0yFX_b2 zQSlhFlByhX2FVTc^pkL&|1)y{pL)~3pb@b80%Q8%$E)*hZR@8<#CZ-_G_5~HFY5lw z&-dQN8e6tWOdae-7Y6R+qwFIkJJ^A5M<`h$@F!n`0_*0z0tkTY}%DZ>7RnvuyK9koe?Fz)G#j)%W)L<;Mj{& z&+Yi*rcRMC_GYZ>y(b=&YT#hGrWQ;Exw>--TkEQX9jx+7#MJ(4ps%O{g&M#`^vR7D zWU2S4p;Nk)9{jf#_XcNML6pHSa}qtpJc@j8^WYxA^>AM{(e4yd=@0Zj?q){Rp`Q^D zh7sqvEu?*3t5+`Lp^XtAYcm+@KT_@)qN`8e_}3ZSlR`Zox{1VJ6kQdAIc(phO?koA zLZT}d^o|{LEnLDz_5P1&;tV{T*S9N?A+T(Mv_^zJU|JFsAvp!wa9=e#Wp0^t*9$ zo`v3Fs}IVBge5)o`uC6S(c-OgutgN{$TH$u1gz-_X6owFW6}J81{-r5hx<+E!`9Kw zJ4Vg_ULjfPCaHE>BaRGDJ1#b}C}8C`HwE+(6S)_SG0YMvJS451jjgq+yY3rV+m>k^ zM>TESsXi(YR6%nS2AtV?5(#Xf?vc4|zPm!Oz`d5A5<&R^&8kI>*r#42=s?#I4C}*N zw`ysNp#o2e6q?TyDp@PG(=h%CCFvjb^h5adWHpx^0~u7(7gZooN{{`Cl)%NkN?4me?aA(8eEU? zUBm5nPYpICbN{)vX$U8L@KvZyxBOu^LU>u}^By&|5m0)Y2)I4#KinQlWg_>2q5y{? zrmT_aAy`cd_FU@@Bf7@OfNRcj=EIIY-&)gn8p!AL4GX}}R-(`-A z-69Hl)s_VjG!Oaf-aYC9*48tkJ`HTk;79kH8A>Wa4vkuAlQJ?HE3Tkd6fmuvR)nd` zX7}(<1~448kuHcqiQ%M!A!XAR?2{V#F7jWR%MU1v_YaAdo)J(@53+(K1GmE4h?Y_7 z;v)x>d?pEDszgD!*!*KPk7*stT%<13%;{Uoy+=FexnV3qMN`#if46bvvWJO9Kt>ZR z)LBRpqd~jq4}J&RaVi;dM9C12Vh=*c%#W`_eiq{nEiKq9v_^GYs4QhS@3);1c{;%Q z8K)&`TQuZbDC%fXzEcb5oLtagnx_XcXQ3IuhiOh>c5_h6s@#YVeydF^dQh2MQsFKE zE3;X+b~UTBQOM<)9f9*-1f>@5Xj(>Pq&kIRR)f;#1|hx>q7zA=GQrp-w)8EoJb%;#YxInr>W)<1tXF*Xhg z6oMzWfx~|2GIY60ujS5N=Yjl7+LuJy#KT9P#flHv#i1jE7W$3e-Y6hFfEHE$*uj(4 zO4bEqJ7G(oui2bnJQ$A_DW!~|KAdoND_yY1$B@w<*k`>rRmgxrm1rHOY{if(Eg>(s zok|8RTBoIOL9nOIFhqiTacgtpW+)<#uyK3sm+df=h$bKWxn~?+ge!OGDj&2&D-%X@ z7O{bpYw=#Jh~2|f7 zt|J9KWe!ElcCaPG^@IKBYdOhVP4nGpE!09KgM#u(IhrFCoVDJ|!`|g?Gcex~MsZhB zC_I{b_dj|)&B>Ro!ztsE2sX(yexWz3=T33>zqkOZ{40yIa*JKYX#W3Zq2z#$CLIpRO#Jc$PR2+p*|6+cn+ zS_pHBY1&>pbi5q{{Z}(o++|2ML zn4A47Uvrh5o3Q`Tn%5aU{QHxSi=WisqY9f;7e6)pkQy`s5oqKU%#s>ZLPw(5X@5__ z&}MZ?7oOFZIsEuB02ikH9nz!)b~Qvl6hu5be$`@>IE*s@6P>61Ahg7&K|j;c%cv4V zO~U{W4b23SebKd2(=H*e@;&NM^-MV?PSvv^{9lCMMzjS+mBHCyhh2A{;W`Uda{O`@ z`n@u_=W_ICruy(=4r(s8fGR4u2oZD9caU zBt|#n6=6hu4oQ`w4}=Qj#qXZ!PX>#7!_ivr5!9LxU<#lH4j{nKjeuNNPRr^s1sjJ$ z<5ZpMQ2^--c-i`g2#Y~{^4pTMLte_D9{dpfq;RB*UWie7K(RStoYt1&NvgFB`Rq_O z2OZdvAi0@J`MA*Dq{Ps=KlSb4LEgY74}3(>=gHxV^g~L%dmJuBh7}l!+@5O3e46X|Sqw__m5UnL0C)zSJEe1?B8;3gwJuk!P(uVjVifX|_1dOKSBAw&> z^c$4H4J@db10H@k8eOBj6&zcdS>Nh&{t@<3r@cuzcF1f4Pw~Aw$I(LBXl*2h^{~B% zebne4$fd#yFxUMZXqZ#3q+FE);RWr7il6{AbvqT2mQ5M`e0NSgz!Q1|d_V>ccv8fv ztwN$MjJU0Dt0Fu1C$!0<&Ch^{0FNT);md0|i({|_jP6u@5_w5m{87f-30Lc^!#$}U zM_uo6c9Q?b{agoaWc}0CulB+wKH1#RLz%79lbdV92U=Tm`w>N5m}vjw7Ej%l_4G?~ zGiee2;6@t&ywZ9E|Gbdp-lk)#U~5%UCmlsPHRbi4;=FK(T?j3OHgmqv=C1xeun>U zLG?eAjJW4`!~}hi*^|0il|+}Cw}1^aE6$y$ zs1T_w5@c;=$XVBBVPAV8MRQT(4bN2J_!=jzjKF|i`G#sPibO<=?`MskYa1`GI;NRAQ4i zTl~Mo3>}p)VrjefQO>CPKc7}gRT#&BqRkeVTbo+h{QvXu@Yis8b%(FzI9Dc^i2k|% z`AvD-LjXQ1zwJyY(9uo$FE!g|y(lsTIfiVt4+&#BO8@)jM8-f|Ogje?OiceA9~C5l z_Ar&zJC1>5jaC!j?>)mz1@1h26wk8bcshofy~0r30wDk?=U-1KrYxs(6QsWAC{fSA z!-uKFR}Zm-z>K86q8{sq55IM^9>VqE|MyET_UInOnLGdeF(k+NAL;@95q@>HSxaZw zUrLbR-_PBQedd_A$bP7IrRQm$?K*LpN}H6w>TVWZ2#)JaDzOdfsq@QwTVlf!K1DzF zWkZp`83!^=solpU4&-!ZioX9zQ$PaT*XBjgNfjH3+=I?IP{P9vPAjMRPI%1l>i{r} zkJCQe>-wVoR@-!zaswg0uoTPgVlm$EiZ+?8m!P@X#%rgjRvtlvj!qu1}sE64lHGA~x>{n)^S-G9=%MAbe;=awf3~D6~$j!NJ-?%
RX%_v(0xJHV=AUSjd!$6+((Bxj~Ai+HSZjP z4_~)7n?rBsJwwW|L9bI^DmFRkDKxb%7I1(TKAxcMsBV4qYI~GW2!ms}CgB_PD+qIL zP{_#z&4GHWf3K|Ko1yZ>5$+E3_%^|Eb5F9iNz399^22+?ID3I)BqHT*os1wABox4e zBDJnd@_L7&SOuupXproii2<QMh1nVDy>84-AUvboM0;t5tcqZlkwVEZJ z#7rrmkDLPZ1Da+wd6UC3Z97d98FMKHViYFIhNd);~xu z^j{%M)3h}^|G>zF@_?ofayWqv7Fqy1TYzFjj=dcI6J-_PCr~Td~WNPye9jhK^KJ}ueleZ2xtd3o`Lsz$+r@{TIS;Zh6V}FS79Hgg<~CVre^>nu@1dHz5P{#ly&g!L?j!C% zx22A~X>M81xv*o6Q}G2+c*)Xpi4w#NH5V%TOM50Ru1TvU)TJ*qr7e)8Vj|{RWoi}7 z*cuq2Pr%&tdDXMB@XKqCcBp)|-53|QkFOcT7g!T%yXsP=#DLJeN5jKJ$0<#Ewt%}O z;=Ck~$_i|D(1?{Sg zs9e|72mTQtw-1;2%eGc%bO+8MfUr;NT0hi3FI`+WZl|R3&OMq~VxA)LICe@-6yH0H z--PH~ugMbEuEemXmLBq-sPFxnb(EJ6fs?kv`k~+0Lct((&d^|kPEGH>xvsqxd7w&* z@YDGl?hncp)|hVRU`}3&NB8b&C~L{f``iy5rfbQ#skZ+)YBqeaC`R19yIwhKb7`an z%cKKylwiv6UOQ(?^(z8{*;fy_+E~5=UICtfr0L1S%Rd4{a){d6cphtrS*qy!k3)W2 zHdRWy45-2RUWf1jP!_

%CgcH5%P6H*0AH{@$iLF9PcD1dR}jjngo?FEo9rW3jMF?Upw6otf1++L_r-sp{GZ*Hry?l9^d7YHWRd z^TRyBQ>3St=q;xmh8L#>7TIae9i2LhJ=r`f>a;CMA1}|j!A6zBZRQ|OJ>HMl%DnRM zWaSiUC^RJFai5-cy|lc~-~7*}*2IZPD7xJjR6*5e``D);nSJc4&qILFy0G4b^d4=^ zYmPXQ|ELmNC|SD)pQ75c{5}tmfm^L0Z}!El6}x)ggURd=d=nNpp&(2-@nm}`w}q5- z8`U@N8ry9%A&6Qn0#i&TJV@Urr{B^#M38gVRti}COg>V{v6`yKcc~j}KP<=($XTQB9b{#%|^8s=aATO** z2g{})7xQS$r#IV40kc73hi=QzZg_4Pmp@!yLH}5})P8$Gz=boR8ssYp$4jYNEWcJ5 z#XXwO+TlfM6i&P94D{A6*_hg!wNSmpZiy!`6mcPFJUqN`BbJfrvsb6gB5)e%e*q`& z$J}nchloPE;J3n2u|d(0e;SI@uo0XuOUtIqq*Fc8>PwE!8YkoK`OkmFHDNDP*8$PO z+h@HJ&et44uW*ytKIiVl3_Z4jvUkmzl~+rQEvZy`)9v}t;>M1zyuEp~a_uH!xRQu* z?zm7Q^|xZvR+r zxuug{VPm|RG5v2^l!mlrH($XHFCgd>pQxc;k3fq&@7qA1R6%T5ohF8 z$spUY=ZVHw$>wm_4YjDw{fc3aXqA#Oh)#2Cl7~5H_&p7=LGBIX$C!{F_{Rk zP+kglhSDxj`LDPKnYFQ;?)!3A)MTeD_q??Oq#lUSb3o$Nuy04gy%bieyscXxDWiMa z!JsJ3` zwe)n^27f3CgL)%;HaE}#>*pDrIiM#XGt&d>Hhd{}!`WqRS3b6u=rNV|8z#gPc`k6S zMUbi5&p3Q`%wWVwsD>0*qTCQFB%O<&1+!I~Y`mua5QRCy?^ncKyZA=WCIpfaa2lE_ z<8w^C>vagF%4n`|_h9>3pqdg%@)w0|icaV~?M9OS0$IC=^uQ^w`5aU8ULYDot5Ylb zJXDywzUciPby6U_`I?8+Dmm|92amZN+OcaOv8&28h*BtCzFNY4N>MU4`6dVkS8v-e zDwK6X7;M&$e|ldM9rLOqaSk3n7X*-a03mdQ-17Gy$Oi$x;-ivQI$>Hb=~h`uS@RhF zL!<0|1A&6~%W=PY^yAw$%lC*EJ*)laS(XP;9Rm*7H8sLDp0ovqYi;_sG=E zN3!B<2Sr)W=YHq@g3sD{p36?L1PRE+5K{)^k#fA#=4=N|SeQR0)x_cE8rZ+&%u&NIs4t)JVw zFN*onH&uffDX3kl2t&NEF5SqisdH-H2l3-tLry){9OLrAg-Ddp)^wUtG9^E@h%yB5 z|LOG%e!?-z`qh=pjv7>pSjC@f3Cizt45B{zkCCEMkc51`<^jw0_y!H1;Kh{{voS50 zPaON3KhGPk7VUbqYwk)Ec7!z}IH8g$z^0jQy!KFh3X@eRJfBkqthe>NGPVKlj(%vl zGcGeXr~|&_^#R4q|Ijtaf48bm#G@g$r4dW@J>K=T8MD~jW61*wMaH~OpKk9mYAJ(& zjnRy{R=wJ&Y3*9XWaP`l91Jyo;y$zYBM7ypt#&f|EL7V>!A=aG>%jINOekPW>o_ndE z51;#Uwait@e?J-H_;Q)#nUoSl#+ar|f-P!Swpk1I5k$S;h?PNO@oC2|+-4}}Idw~v z+>MT1)e#krxP8`f(5g=C9jR(g|2rvLP4p#cdX58C+ZitIcfmCjN8>=TbHsTsMCEgIIxOp5dsI{mA>Ez}1HCb?LM3WlL+Q zM(Ls!EHLdLjp8?T@MUWKx-ZxE#jHcJ*2H%jqK8oCUTTDN5Za**ICX7&O#x)%C|>uc zpmaz?kp9E?yLDD%W;d_vUWoQ#aLGG|iGr7tx@sO?Su%pcVejj=~8h`-C!!96Cho^sE( zCF0~~;6vj94u@^gK*~0VH`cLEwtVPWFqaA-7^P)ayCwY)@a|O0!>jMcXX}#*&K+bB zaP3&GJw8(@6pA_`ptlaIwdL|M1;uL?WF*=aW;A7*u#nGLN(2bgAKsBc>y>t%{@&>0 zdYM}BCY4QC$`a0+$nv6RO(VqzATWZ$QA>LR^2lk=15s54eP&oB81p|$q!h)~7Z<20 zE#1BYvbJkBsTDlG5+i(FktKr5;oWl9Ew6tY_S-zUA!6A-A;FZ?oUUHlk>TyvA629h zzC~D%RIo5>8#FJW#Fj{%R#fvVnSHo_wa3Jkf|VHD(AIhBkAAk*u$@Ht1W!5(3!`@V z!@1#TQ(FBt5@Ez@x&DP6sJtz)aY+cr`=qN`jany}3yrkG)li3yyDQN<2pQMpYpqGX zSbtKyaryJHo+pr?l|aIELKrtee@_P!{J^vdvQskm!43Q}gTLdI8*z5|gD>)HL(~ zX>k@R2Fb8}GVW53vJOcT`i9wQH)U&L&<$9$3^I+D)k3d)FR~$0uP;xzb;<#jCQ-=2 zX-9)E;Mib{`nfxl_UEO0>z+0tuTKp^vy6%^K;@Z%(pvuK$(*37e7*ZXi;Fn`tauF2 zCskh#8v?ARMH3hA<__+z=L;_OuUz|JlM8m1n zitse1cox7!uDA4B)=&N_-*2eoHLWXA0yU4Pb1}Q%^6$kR`myN>Mw7UGl%)r1g?}=TpzF`44WdpNg9A0M?K*)#0L@+wvD45$3UQFMn z0i1pSr@6-x;b7rmwSS$5BA0{09O|%-pKPn@DbJ_L3LJlK-n`K_dTjgKtXsUw6OC6@ z{?luk(I)`IQ608l8ESA_iwQ#?65+;#bkM_DiMS*|^#X~J$!|*B9nWWerww#R$Ar(4 z%@WW>^cOf}p_>O_JyKFmoLH7{_xeRva6`i$N7c?YV^1*SS>jLBp~S&7Tu4S86HRjL zvn$rw?BSqjOC~YN;&W3mdmziH7cQFF)zfCWPH984S!Z^h&gM~Wn`l22)lXbBZCfZ^G^xu0yt?+FGguTiyU%4PB{@ z!n%TIv$|q#;fV7u9*V*YJIXDhZTXP}hMg{L#J` zB7aFh>K!Of&(rMdo(;m82o;xlzd#QzLU|w=m-|4KSfAUWhS8*5623A5-kq6#kipKS zz^9;xCS@tKP($Gr&4uFQg_1w(m%IJB&s$k8b?`%*!`q@GSXH4?kAT|y)pr)Dz2~upSrD_= zu$*~-*V3=A zqxa(t&zO3f*nP%2=MTwQ@@48hmSYpn$3I}-c*mKnK3!z)Av&I;G54-sD(Exj@)7=% z>wifg=N=!w5y6=vTR`sAWt_E}%uq$oJyZev_?iZ6X3Q72JE^K5NAA_86^Y10K2;&S zE7#lqAs8GIP&yr=fO<;60F5@i#SrR(6Dx1xMXwG!6ZhtCVi$V(PCo$WXZ>pIh}+n; z&7-YoUo1USZ&)fa$T5irR?f9aOD-0PrP;BmUq;YY}G+Zqr3?qJLX`mjdGr8Z)X^(=sSpc{8*WYeU~OT;7JGNk|3s@lY5YEFMn<&TJ37b6p# zy5-hrw07V*u3PJGSfX<4YnN+{KXJIJAPOu%J!C9UZ$GKywe>=^@Ok9Uo09+%3}R~& zlmas1Z)aaJm@D*b{1BkAhw0C1#uC_5ADWwy)ZG6MPh%%2uTA7Qe|F>NRhzR@4w_KK?<5!=Ujh;)2S(c`@Oq zrZ4hKF&!1|3Qs;Faplbo_+@1Le7NxC8chqA7U8-q^8OZzk%G%*a7tHhI$Z3{s=izJZ^OLZrD=9(GS9{=~#%RWZZ(kjhA&Fvu#X=#ym_;h^y!jHzc|0I$q#*@E=zoy3X<`FitJ2KMB z8zX&ueMDTsp7pq-Z$)z1eRW%0f*MQ4oYJ0N5wvCdd3V^b7&-&W=Zjd8GufMECGbUBc{{zGVJZ5GHP>G*_ne2vjGzvcUG=XczixyzcX}oXKjT(*0ato zX09T~_Ug@YJYDZiAU)KF+Pf?a;ya_ar>f4KKEqD)7i3oCF}fl}4Y7-UGTRzVHV~b0 zV5*wKm8%g3m#;7o-ZA%)m1QLT7Of9u75_b+rAUnnz<#b+xgrQSPCy*Se05(c&M;?@V&+YK-3?W?o zMVV#rqC*IqiIif?wlkPT#U4(s!+#%`vD(cJu4tcs(7vZBV_4|uw|p&qan+Rj@U>8D zhs1o{DIMgEQd;*ET-8|@E?Q}6K%#&6MOGr7SJLHf2yG-0r7@Y+2yo&I@R?JmE$k~h z;rN`yU~rF5yf&s{3N^NL=L=UejCqw=tUE)`7|M3ufnS4KUwgGPI;49c!>*F-YHyJ6 zN5DMEkCc#w<=fvg=%iu=<%%!QwimxZ=-@^JQzIhqwhC#JQ5Y^N5|50*^Pj)ptufqP zdZIUXg)l>C&8OHjD`XrQMwIILyG>#lSlH2OVH}!XvZ4bdjC&8mLK!`)A1)%l%U> zUY4{7x8F({^Y7aw{3{hAd|0T@5wwGP{#xOu5xi?WRoja6nXhV#fKYmv)UU~;_1CkW zyd28F8|s#$^n*_oyHc&V?iM*NSE>$2j~`;h*Os_65x>&O{WVv8SgLK3F+W*$>V8#& z24>-trPSaL*rpbVq7hQ-sF%dfa zhccV>?XZ+qXoS96`iH+3-Ak}_bvlb(-OKjS{`)rqLPgVB^CT8HvdX4>oQ6?ey* zT-xd#rF0%Qn)fumma6-wxHETu&;6&*TL}6Yme76eJJZ_`6*wFsh8727KF^ zvaei5HvJG`9jPc1LL|U;jB8Av)Rt$*VL}=mI{STL@Li;)@g0YAz2!oBOo7k2^>OAe zS(ki~iL01%v`m#fR7qui39sDkq4S z99jmyI;j+1!p~d_iI4HnLjSM9Dx>DiQkkY$1Y6U)j7PsU%07u_QhdBS;#7|9sS=$>Yyo4NHy7W;P%n30o}e} z!zn9zQn2pN$XV(x1=MwtvuEOfMhdN(b!N%yf+Pg2O7e*{5}zd`NG9rPP7}veA?v#^ zuFZ)OoNeynVRwgECI;_6FsdA#Pn5@R>R;urfWA*t5-_pCFZL&2_{AP+`9v6jr2_h= zG{%!|2iNS;xrQl$>HdBk0zxl=v34ja=k=Ed7nu~Lort31Yn4e08m{t~%HQmUT=heq za*Pu2SUNtbN|pEVtWp_I%}#J%X-HfZzg+AR^y3=+$ppUg5NIJI@(|{{Rzx#q)Pt>WODdZLn|mmQf*S!hPmjoBxf!gzFJCGb zNF{QM!YJg+*HBSC3C^fO*m^aB>^Gyj2b4Bi<`!~}mr*YMw1z(0usB(YO1?hJ|*7mscQ+Qxwjc-Uyt0; zN5&{RYL6AaK~O<8&8<*DUuK~NH1K<~3+4Y^PIn?eJcV5H?2m`do=|)iz4jZ<<4V^M zv}6v`f%MP8ZJJ-}t>N-{KG(BMp{Ajh%wa=#if z82dRL3KJLu`v=PDwi5Ko>K4~*)9Dmt%`VK>|Jdq}c1mPkaXWA-|3x^t(;r*&g&oU! zncrb|df$3(QviqmgY7*@lOtrX^xhpIJtITN33?cR(69yj#VNK(!s`SX4HbU+Qs^r6 zxrNcWGe`}Y}BeW@OYv_)>`#O}uPTiJHa)mQy{eJ|7Xsxi<81qu+rW`* zy-E-k#cIUnpYxsRE65mRjq+%24tM8jy&8)~J@oOlfE~NxGo~dBJpfi1kE;=$5(2b(SiU>bWR^Ij-*%&YXm7EBRZX z-o9kLRvs()*aT^>;UPAoH(R?JB{t(|&HJ>UTJYqB{fgF@MnuUBy|!y3N%zLt?ntV; zw4431M(@j^ISZ4ia;8Xi<^@N6r#M;Rq94+1{E&*~QeNmzhM)-ctepx=G}L*^*?gcn zU7kxK`JtSz*=35k%rze9S!qXlL8n&d;Z8myj}~QwX}4H?LAW-5D(EThxl^WALGknk z(QaTCjfCnl%WnfPflu_$Ak#z-Rl&$h7oQp`#OA2k>a%aQdD@?p+;p*x@wH29uFy+b zXWw~8YFJx^k_LBDanFQw<{5{xXjF!{;}el9r~3uE6=At{4j|%}=tZ;J%iKhXhcwW@ zGs>#*MPQ>ubWtIzn$fQa$*kAqlD_V~&hy%xG5FW8s)r;vR2s`5Jy0%}%td=ybLVuu zq~9VPrtdJd{>>k(_pnxGy){pEcDm0W&Xl^X%rQ1fY{#VEtZ81hSW{;$%sAaB%k8V# zx@$eRCK;fG6^W|P0~Dbed-?3Ga5hA0q@f-P9d|9I@I%tpjzv7$eb(tCigO_47jplD zzRH!stnqHXRvL+A_3VC`{FqOzhW)Gqxd#7u8=7DP+p3sfkxtN=zKPlcdje%gTG^Rb7+PS@p(gLJ-T%`uJ$0z*_np(PAqDNZ07=@uvFT>rb@IQa z{drI8$*nbby?TD-LSYe!*XSAqp(_J*=HW~CD)5JP)ev$xdXImVYFS`4LJro!r#T{O z@3?Z^ItcTD0RZ=$>8g@I)O2=g%Oz$cF#-N9G%!91jgh6T|A@R{6L<=8-bMsI{&Trs zyyV(Bg4Izx=!*w@lXg7$+3w7NaS zmdwVoSL7cnxd!YqNeR`zQcQZ!Z<}>EU3le2=lS+yLj8^n5@vxVE=~Ssideqq42yIs zf6fLuy|5-J%@MWX)SMhFYT0<_lKqr6SY2+$(mya}V)(T{ctC(;bgD2*O34VP(_fH- z_aIR*ZF@85t+$T;z+ZS=+jGkQG*7BK2`ssCtu(DyAA1l!miqbpM87A8n=)3t`#4=p zD$43^EbSPz-qUDP<~;is4ee(T0>_28M~K)$Q4&)Jv=dEAjg=0Y7n9q$)DpW1jBlRR zi{@oC1D*W7Vg^E(xn?!s?h>{_l+dtC#P5@Y;u7a`;7L*Vu!eEr^v^g51kUw!O(Y0RAmJxy+Vc9MjaA zy=MWE^494IJP%vqhR}L$h?Bb$rf!9uewKPxw4Fz?pGqM*8OqRw%4s;7=#7xyeH{Ve?#p=7T;3Yg ziF_#RlWcYOkmQ2)As(yzbeb3GC}?$fzge|@-=l*8_~E*sSGJPkA&5|P9MpnK7t~Or z;fjMSwsw?go)0ChOsCc&g=4}Md;T06$ez!)F9o05htG3$Q)Jv*bHgvfyv=-wTuQv3 z?rwG8=qw)M&hOsX0B4r|!<6#4OB-Bn>n5)4~sy6Z-q1;L+y^`7QXVDRYJXOsxCXe0ao3bC z*es6-GD*z*>Es8QYt_bKD+GrrgeCNRiLT5Olg8 z9tgeke?7yPZ)84}`pYrw97XcoyG{Jd+aCCSqIC5-GuQG0BYlHk(FY-)WL}E>u*4e9 zec+<{{2+Vncr=WQZ4Hc6v%OcQai4l+d?5UOqHsr_1^DFs9hpTnRdep@_i(pBU3r2^YnN07-J8iAMtOlMeaT22GRBo7GI7=9uY1 zM9!5vkC5?Hj+^*n9?mAHtS=7Y2xv)q8rgM%6cd&IIL_CCzm3^HY4XzQrC7~dg);QRB!PM7`AwGOmcIDR93k2DF zg-rH@?8rfI%o*=HGy5XRTR!Z_T_Ev2P*XE2ms+e|`Z)9&F_ZH99NsQ`(#7#e@+LYH zD8b1~Uq3mpT(`|N`AKCYR<_;9foJ@vTR$3W$w>n*NL*;uBtK%?_2V={+1#_bL2 z1bomPUz;>&@(|bi8Eu^m)rydgy;IRH>kT|02;8R!4TzZCjHQ82GEg4z$_QZ?7+i6? z%MuKt^6o8DX~FyPHoN<@@W=)|g^DzLNiVaqTU)$b;O7DRzbUYx@^nAz6y`jaKd-0N zO_cwhZHC&=T)}?&Nw5Xu*(Gk3TVE?e-HwAkxtkV=vz35ruWFsnxS$+X7XZ&WDV_V* zzD;MB6e6Q5{jZz!^b5=4#EtgtHj6&D>udv&uYho~{YiZ)@HuiM!m(v>1~A-im4Du| z$~gQzzJ$?u?3yuI8d&=bw;pV+1Tyv5-LW|{81H?75O8~U!GY)Gb#xi4V;v5So@u6) zYwd{)GT=DE1oC4CNZORtcINeX1JJI^G%BQgHhT>-NqAG(u1z5IM-O87k2ZD{TM}a} zGLIzz!KlKknl;=;hj+(E+BXA-XWJH@T$|U-G9HVEglk_iJp@5_O(+E?%e*dY-A&Ae ze9s@*Scr~`BFF+lNbO7I7lZo8F7u3wW z7F51#K5?Y7#UW01ZS_{NdbdUg6D@U3@*0mu>54HO)&!{vwGQW5RJqV}G02W72We{& zm4K(u$h_#m@m!YV%FuC&NggE8f(Na=!{E0Q?9C{Ue#eWBVJ0mhNo;rEx`iw zEv&_uYlWMZEdXhW$WwaFbI4jBsS{TEba~bcKmSwPkiz#ZHC1mN@mC-f!g|wQfs8Gl zg>}1+%Wro=x2*q^2R`7&KfQNDoVes7dnDf}+5%VK!uSPe1zUeePslvlsHTA(hMF`%Nk7O|` zC>qtt{PkaM^v2mRXh=b!4_zHto*v}(W7M@?_faT(g^xyd5&LHD)hcgGp}i6``i1PA zJiebeK)Q=kh#achNxqDFDfF}l zsj`$j5;TvSuw6Nwe?<68YcxUkr^FJUWy~x=o9?Br0*dXiEuQBMeUb3hSsM(-RvWE% zpKYhCiq$j#zvFs1+{LNy?lylqFLwDokm#=GBx~E)gM?Q+CjQLG+YAIW6i#PJ%XyWI z@GSX5Fs_hCh18~U_koQs!l9^6A(GAP zCzGzSXk_V^i!E2|DtEBst(cq2B)$=F$<`v(ScRj+wlmB9WwhfZZ=DHpZiPT=fMi1n zdd&4AcTMA=y++W`z@|vvW2#;S=dfObm!B?RK3;ZM6o{b){*Q?``Jd%pw$Z^BGw;=|xb?2=G<5WBJ$;5PT0u4v+$UJZ=ZWblCRq+@qs-iCHLD16aTwYXuQ=d+Kz|_@?QnLOm*SrRvpQ<)V0D&x3Hf4(o#b-ylF;S5A-3_spuT## zpXY-5cgKzKsb1ma%wKau80~~UhX>SDw#5x%96M=VH<43I!3HI-mFD0T&6Vz(&svH- zgG&gVR^@CkjW+fsNv?qFIFF%=2>p5J>#vyaR_h;}niz(Q9o4UB{$PocLauW_;8EfK zE_g!&?Px_Wxl0?Sd~R_2-HZY_T>U6)%i2Gx2I2&(OaU2PXf8?td@wluOLSFG5vF-_h84 z;;{V7=OkrCk8Jf}+7m6+_gE|Uu3MNsf&*FC-Q$&aN)2q$9&OD*e1}UETMq-bb8G5X zZFiD9g5~v7xBl+jbenp3_H^q>>V9l9_|T_uB+gp98C&6%+PO_) zw~1f&0$0U+Z}GyFD=<&%Cb#0)z2&gM9F&|;=(*pzoav}bT=wy1Td(Y;VNCw)-A@&_ z@K>sTs{yvOxnck?gW`c>KI$&*3pkfurLXNsGG3wEeKQ>F#J_@{>~=|PpFEwugD08Z zva=$)JGsfU$52Rr^kYUL)a9Mtb5^i~Q!7@a)n^sYD9a0wV6_46?a&i8GNZ5BjRp@a=wh7kq8KqMDjh3w^Kquu(l5)QSuuOy;>EuTwoavVCeFnJKyP z((Wi7tNR_M3T9i+Yj}Z8MB~d2_m`TS{fMA=6-Z&wq^$I8lj2zsw9JnKafFa^ou>g=zhw1ammh*#qci^+pkjz>;4@(2 zIg4+L^RkyKdgOa(RkAK zQ3`0D%tP&UGknSTn~c{f|2oM8^t%Tq*1XlO4=?Cbk7K>B)+?fiBDslt5M{0S`?ZAL z`RTJnZgp_W=lq4qzW%P(*X@ODMkiP^+OLE>9^Bxi!8nJC_QtOPBhLBF*Sz^Ij$pj< z%FuVKCJCz2Oo!c5oilmSDYDX%_6bp!1+Rx}l11C{Pd+*ro{cuReY8FH52q}f|CXs* zKvu4q^nSwa?U=wzk|M{soOpqi<=<*t?Ct7Xwa^hik;_%ub&SpdVA1MtM?>jVx(wzF z^-V^x67GZR0ZilFQbCu#k}j)%@H}g8^;?PZJBE`sM{%;*J4(K`{lVwa)~g=p7Ggq8 zP``6?isg-%Y-(IYnTw01#r8 zu+NSb#H2!u{7^JXC@_Cw!kHBZg|?Vo`gx7xz+V&orl6R`T9Yt?+vAhN^~llg0LvmN|G@HA9m;u*R%t?8AdsZ2 ziMqSGM_|6O4KL2{>B#QtXcU_LdT@K`IeS*HF2(5nu;GN%MUCfSDX+Z*qpMTz(Q$Ly zQb}KmK=_j(>l5d{+GteqMCq3qx}bQc*e6PF0^=}r!PaDyJ~a0hURS6rZ&=yPVa-Pq zuK|fPoQ1)vM^RQW*;UKdB}|GO|0;nUA-~DCuCz{fl06=2*8AA?c)Bsr{>-4KV35<{ z{K9h5%y}_$=3ltN7`G`;U7?S5&;8R(waZb3pqY1m?M+9=O;jpvRQjw`tzE-`8r%O{ z(iYYTv3!1Y_Hi5*O~J5_S2{&<{>0L0kBTwQ_XWz73Y;UE^a(i~Yw&If&X|z=oiRf+ zvD&8o{@!|dE!io%SYD&GS7$NLBlMZRg{J@3e`|yh78kNMZ?*>Ia1+b;azr$xPSqh9 zpB3f}boeQPmL0mJt&u9L;P>Uk0Pk=lLqc5eZ9B28K}axli&kpQ(p!6jJZ3sWrObCH z@9@aZKApFXPKEdkQ(R>piYXs0v02!IqYv5QZoAz4N;~uV_eID16i=#sv`YnPOfyV^ zacIykJ+Ch}rX&hk_N}=%sPu`O_#3BS`2&QURw_bi*`DIUl16<7>#D z%Cz-tgM^kmG4w?@Mt>6VYzyhWPaxzCFt5gW+bdW0Oyz`-Bu8<=#q5E~XN5Bys{4tf zz2aJ*5DV*uz!;UlcwjPrEQwjS_tNq-+DA#uezy}31^ z3fjn4;iu4CK8eH#tL2(h6EPzv)Y}o3GR+3lXh)DN9Oxt*73!II(V@hW{3)y~2UQ0s z62BZ=PsJQ=lDok_w>Of+D|XuX9!swpGEJw);uO*33E3Tq?UUD=<67XSz9j2=Tj88!J-tL4~1euCeaE139x_ub9-PeexU!y}e=@ zavb*^8xuCbevO&KQssdc4bze~M!ZPAq?AbFu-Ol+jH-{W-;(kgI z^lnBg*1Hp>fo%qa7P@AxXPCJb@>WLNhDE-Z%^WPtTf&voh3FMQJ$*Er;`%t(U(P3) z_5|dS(CP&0R(o4Dck`KmVf_$xjq1ErJbd-xHGwv3Sn>qGCCRpCV*}ihn zf)|u$7QJQN!>iuF?7Nnrzi~^&2HAmXso7bM!*B+>sU^IQpqrW~ypsYk4fQu$b(pGu z%;Ta^%wW{4Hj_*pf38qU3L5vE8%yVRxot1tu*ZLSNrMtQk0=Q|h!*=LxKm2k6Y3(G z$-O33XASXr7&=42wc@%RUF5PRKP$tU*i;DWW(w0U=Av*v{`W7V`=2Xbbs>8%i^lPpWTyckzT44?S+w!~gjsZm(41>R# zjOtNSuId{gCkRQ^a>+*SYsUrH!uEQ-8uR7p&Y;WZ;i2bvsI9-UTf2VAh?p`5Y&Aaw zD*NfI8dn0jqp^Fr^==M`m?xe1QKb2ja4Mi^_22#bNolGduK+;tljQ^qm5u#;%_ok@ zJtw)9n#>ZkhmDL!6HVK+UqWLw5!nc>J~F~nBwQmb<;nr?ns2GOorli`dBiFvQcYj% zHgNU97aitF7jg;N66y`Whq-lqd?B{Q5$_g)kzrPJ}#*U3XqZ z{moE^Q|0^krFE9te+($)bDV{tm8)2Oxh?NO<*5)OKdQLk{t2DgO3I5mI3qt065+K= z=L0|1^~mZ*KIdm70VH1)I$_8tfc12%DecR3bTccGz}HB9I+&?PF@W9iTnrOaaj4_Y zAif)T!>QGIABCegC&G5E`mv(qu0i^{m3i}_$7r&M4C#-t$BsE$!A)~;V7xt^l;zVcy)2n z?+S`vm{A)a5d)2mcLn!^fH%tj>Sh|D{>Cb%~_sy+`7^Y*S?NfA99lJ}~chLp`)b}^F8e6kk z6nj%@V=BQ1EI&xY(y!Bt;sOOH2oz?>u7ujHxH4I|G1d73LM%#GeDV!+XEd8RQ`#2l zJ6kC5iswv2px*4ekDhi@PTTw6?Myh}5%fiXT7!HC*L7i+PS*#FR{Kzt2r#%dbysrZtrm036W~psbKox+6Jer#d2>Ym z-Rbzq-3e~Q!v~MG&Jz}JOT80oD9AX*71L-Su=_y{hej!$QJ3^`_UIB`QueAD^)5e? zjnCRTKB{X<&}7$I#k&`9A|1M03AmVQ-VNa=Xg^FmI2o}f>gdm1)~nqX_*DiwzgRQ* zAVCGZ>5sVg$`lr@n`sMwjn=FUc`?_x-qsg^MqhlFs2iPG&bVPYN3?)_U_obANvI#Q$p=MBb~Bb8T&r9 zU$;bFZVKFU-`%MDZ1ddPO@8Ag<~ux>Dh38#sRL(kPdgiSd;${^I@)B ziefc2Azf2OI!SVT+1g2Y!Nr8awh|b$jM{DX?l7*Dba-K#9vimWHnnEKX)HHxv=M)z zq)ZwsB-{}%UR(xWj}Evl#aUqz zGi7mRvQyTa+Z4JsM=b5fBkapO4T)t*yRaD`q9#z(5k^uv1;;YG26Zx#&EddPOvq8k`nns z>UHDmpvZJR_3B%5kUpmmXeT?grI6!xZ~IjREHZa+2a}l7&^d413~SN9RXa09QL8U6 zxQ*wg{F*`aM4O%a{ZwBMHTdT$q(B`~+=2@AboA(LXixLwag03T`)J4zT6|*J1eH9mQn1S%+J?AS5c-v?U+B2iMK2~*0O zB{u}-vIf9KW!ZHH)n{Q#F#kr{w|ZAQcoAP0AY{kog?;YfWzx04Si7f8DA+%Cn|FLo zRPg@Qm?zT0b6fX-ewrp%wf#ux|E&8VFRcVtQf;8`;O!@J4(;cylt#L^bII{*K@#|w zun745hQ=z-o?ZWZyP>#sYWz5IhTv42x!m0Z^;y%nBa&LRa8C~dZ|jzE(z+7LsY@&` zK6H&+Cx`xaP8e{ON>#uiYESR>khZD&l3cK`W`pXp!W%eRm=DF!0!-=u;O^PjRrX#? z=e>Fyk-@q>PQIyaDe<}pGp2V_mRVw0^tU2SDr=w;oOr%|KS_kMsM{N%_KXEde0<0t zkM(uMIKglr9g%ygqRlnMUP#DBK4Ij3=SmDg@_AeY!Ujspa z5$_qBxBMROA?l&zFje)j@ZvhhyGlB^=e4%R&CTX;$cF9^m85FZP0^M5sq#Nn z^=V>f`pB3egWi_x%Gg7Lj2BaVAT3s9f;~UQ?RRl`_u!0?!klJlFBCi~KP)YLv&L2u zkv`?6yl9tFak4)+%Vk%|O27o~z%2!|gm0km_-|AF7GU;GHL1sp$?)BKsc9K-(Fc^+ zw6F42f7!)vaJI-_E^+D*!Xxly+fOwi?U^S$srcOfQR#sHxe%Gc>E>Nv`wYn>%#G66 z=>bEhK=u2XViMO<*k==0p^KU*;Gv+-CxL_DX+VFuk(Lkr*5gr%i3j=C#fZ`feP56( zLRGymqd@r7%D*Sc$Du)*5-{{Oxd3Y{ zOXtWz1ODBtr-w-n~yUSy(%7L_{a(FKQbCEF6Q=7o$&n12B z>JeC=@RSg0l!#|Z)R$XLyXdLlEPM5dAwdrtzqX=(o9in;vN4%KS!E_|-b=h}<;CZU6jJ ziBrS$+@RL5AV1H;!EO@{-T}MOmhQ~hKTh}Ow~<@ESG@h7jS7l;IQFF38h8^>KKccA zANJ9klqq;V3VJUpkbfn=RsPazy#M1-{N?Psuasl#7|#|4<`Zw--MJKCt$JxvbgPhSOVn5KVmy7KHYrhlzABs&wj-ZnVy5qg!{IYe=#NQ zrCQ^hhpv1r^KaUJ(Jll@ee-m6BpLo9*){dvldG>h=JKaQ-yIEm{&l&I5sj4Sih8Z` zLDRJLfFOm&=d$&g(jDRUgn~(BaS{L`FGIUlYhU%Pw&Ph09ja?p|c?H$jjZBI5TZFR!dBiSpeRx-mf#oh%;TAb(}} zI(l~1@W?{)PGp(CjAQie*0h(DmfPTf*Q>O?XWf;J@4*q_a%br!k7zRU@yK&g9!VGcT?10wTQ1kAj0h%*v-6(`q@1^OsICxKdZ zSvueZx;Gd7>zDW`U^WQY;WED||^8?}Hb)wGYONW1HJ1<%wVJ zS{Mri1$_S%{6bZ6yogIZI?EfJYGv+~rp+~{wMOY>Ql!8`46!2}VWdUtC%Y}DqgiW- zZK=B5QxqK}9-yO%2a#X2Adft&=3f=s*v4=1UW4T3>+l(hEOwS#FHVEkG#A8CKjZOe z>Ow>QSekkw3Q9>4ygg09$9Ekjz7i{3?5U-1J~en#Q+ zJ&U@G4tW>bG5EF7tn@fU`6-v}>U(wD1P%RDds|W69A!bDw8s}vaqnVnE5%00;wfK6xPDM?3#Di@xiVN_K=zhtQ4qM>q($F_Oi`g<@TqwW@Gd}dRADsm zVoD>kx$Yl1G$6dfecEMN$Hl*9iL3kk|99?roff7r` z$O)I6)&;99eElrpI!bJq0~ZOyoUEsSWr8FEGUun4}9t2%Zq##>CoXacCDE{HRhfS z{?CC`jHaP@O!T#!|5VN$1?N9%ksK2uI?X1Z2(scUmnN%!{c6IS3-Mg=>5TqL4T zDv93Psh-s__Q9s~OGQa9e-Fo!ER7w8ZN5k%DupO=@7y03XW%``Ypw8C+W0UD7qoVl zanbnkJu=-R`oyW-@~~D1_u$}A!%L8P8`Lgye{K#vp-j2aGDRVwzXT3 zqSZ5W8dw|I_Kr_C6f-!p@GZr2E08Vy%{>6CnIRP5-nYC3!hDJ&W8GD5I_U({1RXZr zm(6Crp{7aJG2AX@BBJ!!`z5`&iPkLf+kY;&NZROd3uh|G;&2_QBop~Z)@0yABz!T5 zWfxlmzw}2ttf`T)k3Bu19Lf4^F*^){uvdS_s3CM5;^BMw&w9(QseHh-66<4p|Vtq^Mvv>-)3KOq%HTqyFYiYyYqY6 z9;$7m2b5e!vZKcGp~E-Be!w?=GwTbw5{Ze=b|9lwW&)V{w1`!CPjgCfYym z*r2Gtxzbxp;#Iz`(e)Rxb|h-%NlLr0M}_qSf#sgH{vYdBie+KF>A8y|OhVMRmw?kZ zXMuJ5UZN-dMiMfr=?z?J0mY*~PtQ*`92fyjR;E2FLjNA+`Iz=>JZ_iSFUzzGdSaY* z(nHERI;&!ESv_UC8*Wp3S_l!}KzP+8?> zVH`$6)QqVLmYnQyf-6Zuw@3$h;B1pzzXqj{p!8se%V^?^+|KW#4kb89{LQY9i}43@ z<+|Wvh{4#L4kHKX#Td_f8uu6m;;XO-k4}nC^3@jL^Qssr_21S_dPYn&u(}WueA!oA zxX$LD9Q$lDcMKYYO&8;=!m%Adn?rmPA64IXjw7}vIkQEZ(>~Iz-_6A7JN)gmyfn^A z@#g|vD@`Uh!=@RWOsH+F|bTs&IGwet9LG$gJPwbEMUH*ObATJ{4w6fD$V(@G?{mp5>0Q(cWEZR1N@s zFr&maqJPk@^~0ln-=NYEKNPgLmt0++wC%dVlBj9@E?mqU4Nq+t5OL4?Q5rC@R6S1c z0>AQAVd4k4UlTpkov7UJ5K=qVb1-ndM#DezpQs z$#L`3+Y*#C#z67b@{T%3>?;13bJ1Y}17+b8^6^XF(mJL>;H7DFYv;8ql!a~qmff-s zCtYv>0*z@<>mV_lOI$A%FRMU$*Ph zzin0at9(~F>uHL%FQL|v-;lZAjhL@1^})khMX+ekFdjHPM_>-OnZ!bgIXX04S_%=r z|6bxEg<_*w$DZQaAiL6(M(Jd&nfJEgOHD6@8C|KO8z+s{;_J;Z9FM)7H{l_-^xnT1 zr^F8|$+3pGFfE8gg<@6P@SD`oOYn8KO=jegcvPePMV#vuQfW@8=ft@sQZltrBtSuHTQ`7 zi~0*Rc6q4fF{6KEtQ^G5%h7*oO@Y_T=|lJ>l#z42=XD0na|nTmzS6`^ zH`!u_6(?4l%VTRr*cby;DbPTEJwv=J)KYYO?2q@Km@sZ(WaBXJ)KoNm%~9S+A4*Z5 zh_2(2tgWxHNLLG_v2hWZozjH_eMQGV7)NZ#vq9)%-x2%VMa$mwuRkoj@Ge`l+v9VY zFP=@!?3BW%<@~Tr7@zCmeZV56&h?B(?E34Xo+cXKbg4c zRp(h|BsW+_UMo-B$|4ESeQRBo5(6(4jgEC~uh~DCIjNUp{|O5)Vce&!4kW2qpUg4O zgFlSZ;L#e@ZK8lqDok8}&(You)I>fCeC?T=K<-Iz9u1N0;_Txo{)I@=0ot07DsdWz z=x&0?h-L(#$}(>Y+FK+DrURIjrK5B=i-=x04bjI0^s9)LS@2**)*Wi-HIU2uMjtBi*%>N_Q3Y+}B)lw4@0mB*1E|w+_Z5vQzsbV+X27u4`gU z;4bf-z1y*mfPPS+o#XiR4OLev-2^i*(^h*Ohn9*TKZ$R^nuD-r1jXDj{Qy$1t;Eip zL7?x1F^8f2J_{-Ju_%9qy=mrFv3r!Qk14mmkL|7YYnZv8Nk_yW(P*XO$Emraa6Jck zd$Dn0Jf^AFK=`C&qeUcbPpwMWT*iI%h!I-?L=DlR%X zSmN{Hz?Jj>dmA*YL7K}LL>VuZGVAj?<3-JVM?RvRDE%GB`5m-Hy-vj1*@vK3J7%q^ zpx|^9Mki0Lj>jPVV+o4d{R()&(^STh+TA;nRtjzhOs5hrC=M&V=lcuduWu4F{*qtb z)x508=$m=RRxuHEv^t)T*N6whTBNfE_r@$(B<|kGJ8RE*|Ge(V~Flq+SM}*{6?d-9;Zqw z#s!O&yBtGiP6rQKStFqH$0)e{+_pKB3D&;3gvz&nJJZiU zSn2)#ueq(9e$N?S3^h27nGTnc%(;|GbdX%Vv)np2o8}Lph5Z6Sai6pEOh{O|jQ%e6 zZH{3tzlSuna#}{uv4yLvWaf?eMu^}C#Hv2t3_7@AFIUSlsV+w@kY{*B#;*YEVGrXr?rhf(QI*ev)5XzQo%mZj5qB{Yt_m?Ee9a z1D3$;T{}#1t`hmj%9BxRWfj4^A#^7?@0;>pKWYlI|+Y^-fT9 zBn1rjPAtL}+aNpUQKvfjtwz!VTCm%WTmgi&ZL0p-bgkC+tocyqH&0lQGqRpk7ltrA ztL{z7^~|v2k4^u^fBTw50-#$aWG^;rua`V-GDtVbGK+X*Luj`VB?`ZKh%Cib(l{x3 zHyp#7h2kqwfVObB7@|um_Kyx_XnKnssyTm5Y3*o2>Z_xeRU~Zg$ijk|n<)YEPF?%w zx=f|wx`R3uDQA+#XeA@}ZUtjGAUlO$-DVaU7@u1WeM031xsDgmVMWs0=iwqsZQHka zEPn+?Rz8`i(vqddk;E|S$b2yJL@_K-9>Y6v+YZ8+wcSl#)%JKG%eic@IfxZlO!nDp zVF-cB`%O#Hzb$2zn(Jal@g_74jRNvgSGs52%DCgi%5O{IRPX)xiM$UXoCZ_Rp5muM zd=jO)Fdd2ioCUN|n6z22N=)F4gKmBEma&f32P!{|VygV}$}g`Zsl0h_CRpRa?Rv78 z*5uFmgB1l8X;C$Nt(vInxx1w^LedVOo^n}9aUKcWHKHDJ2}Fe6dNJ_ckL;e~XBAGA zoB>VebIkU5)Tq>*f-9~}k%LXsH&^vbE;^93A}gigWrORhhFa+GKSct>pf?vqSg~UJ zp2j^?uV`8f=8@|5;B*e%N`B9Dhn8DO*gqu%f_U-auvkJs$z=U;wmMyULRZ)M;p^$IZD7RiqssSmh8^~vmHQW?KK4KkIQof>Th>}S8&OPu-xpf)%Ow8e?OEt^< z6z~M`>u-0|LYfykPOnYlF6;)3)vl{*|fPS5=?llU%HdJhU@%=R13tpLhSAGgi=F3PxBRf1VxzelHZXl7my2 zQckRtc%FC%s%x2z(AQR0Q0yW$ifI*)6DtmM)#~EiiWFE>nTwnDDc$(N&YR0E_~jPYo*eYTXHj%dW9sQsX+!l;i$L z*|`^n$t-y;aR8SgwlH$wC2CCdP=R0cFp(i+X4Kw{>7nNJdAwGu$~Slq{}+$f_<8_W z93jovMi%Ny(?r%*$~fC?6n0ET!9T)?Zzb@ ztZmuwO=h44YR&4u4%|ZDa4D@qLvn_YOkz8()Dm=hvxgP_)62oH66iy2!Kk;|OZUGt z(nGhaU0K&}1}V@Z3gtf}yoE~Dbiv7seN3Mi>r9g;SMmKl^-wN0LgW;W%9AtuzCDb^ zv++9!dsGG?aPvi<>o2_Bi}cvqR_eOQ06I9J!$X(O-?87jC5&itO*4t4AK^4A-^89e z|0FPCifIi0m290PDx^1Mr--*h@7?cgj2Us!Jn`9r;yU4|Zveun#Q$@bqgzAdmV@O) zE?;0knL;fyvD&01u<5uK>dxGLV4Ubwh@hIh;eEy2Mm~A>ihFG2q=)a1&-(^cDlGcH z-AT+H-d%)1-c4L-(G?a}#7p59eU$fEGS8(vlRa4Qut}qIcB@#rQl-u6M2C9$5jn|9 zQ?3VM0)a4^(@qZF+BBf&L*U}F>VYHz#ayJWi86XKxb4vt!ojubJJLg&e*jM7PG0o0__v~l5fwps`yiV+qqN*L1sbED8xeiGwPB^G~Ko#*$D|)pQJN}$(I~?bI5N-y91zf>WvNDUxG{1Li{li6ygo7`- zVR_%#-Zl&VPjKo*l-=`its)G$q6unGr|X77m*8UZgu3XjvDP7KUOpNwB{ZHwbV-G} zaKysSbwLG>93y2%-78hT>=&8x4r{%plFs_bTfjx{Th8}+I&5-04<4Qe^ z)@0P2y%5C3Uo03vn|XHvYuanPriKXnw-%-Lcmb?1Y}ns-97I6Tz~A^JyPQ)wqgk^d z{;B9tZZ^7@Cs^KD7gg857}zRphHokoz$YMCu$lr8VMiw+aG{l%a}yWittW;@QFu$S{b4G`y2|oVyt|*k3VRM#>($=Bbk&;Z3(_wCY2LWx+fazFvAx z|9T(9uW8lNzI;AeaAZQ(a0m%Ty}7RWj6e_m)f+2McWoz)5Z9EV2Tz5+;$5UR)MK~( zR#m^i)p|qMt_#bVb3vL^O(WfLwv>fIbnyk1)4t0C&N|RckmgYt1HF8}UTN&OhK8F9 zV8bHiYz&mWr;q$tLag?cG`DCT#!~{Vc^uxYu|ws5Xe!_E$8@#j-|#KP=kww&(m67X zEvs(ZDvw#b_e=O4;v&M{oCd&<$g7KeDK7()u85xqTnf+X%LQ=C&qt1@)P3G&fmwF5 zfzT^_V(Hc2hX{!NWmXqx*2*;8;$Hhpm6I#j%joL%zBYE7XiRCIXkL4U8|%6f*R-{J zDIcq0>5a{xnBebs-%v0%vUa%aO86|{103t;Eje`JsTZkSNo3iPDYAFG=Wg`gpY!_> zum}YoUGBb1h_ZyLRPjSu>0HE<7=Gj0liRE8iT1LM=;y{0N_}QU6C=0& zzU4$lt_@k4O9SjVMj8)`pG9wS{q!ze3&x62XM=XhjyR8NOGOzAOD6Mz@YPa>k+EIX z)7;E%ni>Eh!i?@FVY@c|gyl8ys~TJ$;lIoZ-wVY=V`<+Tx`p171W0vDqL^}YhQB<_ zhwgjH6^e8(f0!d?q1p5Rx=*AvW8?1;U}NtAB&Bg!-IzL@2outLvTD)D%q&N}NrfG` zev?SNNh_d|=5HWs5S^H8?W^wZQ|*wP8ctJL&n(;cDDWlROhkx>br0U;Exhqt3Q- zcMA8dA}^ut&&1G02w}sJnmuCUo#oX68V~&J33v1lZ!hQVj+(s)oK1SV3lWO>&p8Sw z{3#iK?_j$-ITYvRNPqEUJ;ek4DOKGEB*fBj11>CqD(x#lD`SJ`o!@kFWM{IWM_u*T zpVAGmF1`u!e5Q5W?-|R0E~VD8Qqa^CVTId2oj57aZ?WRWO@Az4R84&4Fym+RauN5UpMH1#@y$|_ z4xV$XK!(KF8Nwk;p2XrdK?xYaKx;!a?QeGAi)G_j)h=AJFSv)`Wpi^tIWOb#vPQNu zl9d7s16cW1u?1=0bXEv2PW5)uQnrWF_({r);3J+w$}RkI3W14}`QmskvK>;A?{;ou zLOR=;n+oO8d0U7l9;4vIvfxedH+D}a?6zWN<)a2;fGj&kIX>m& zkzkASz7IDew7wjk9ZdVQ{a(Y9C{3W~u>kxRWI!ULmQO^ z`KI)q2=@*sly0BMsARhLyg$PboD*(jdJK5=MgfvmmtP<%3*U^Sg1TTFmlLDwAimyE zOnZH-nN*iCu@|kevJSY{t&n%No%NKZ3fqec)}< zPIg57?f#=$Xsql5kKS#N7Ioc*?p>brFbA_y1r9ptifpS&yOfPPtq_e3Nt=})PJ!k0 z1};t9c^E}@LH+g@p8Xs@RJ0go?MDcxp3=n}6Sulw_umk>^lo&1Kuc%Uq3DyG-BA)) zmdsB9&vBe@(TM(2j^CStja?n@U%@RnRkk-B4xXLAbBl_>M(9AaI~fg`Z1M~9Y@Ylz ztxEe$CtJuqMEm_ntQ{`!RMJYBY`L3mBvqNo?>F`f3N`*-$7EbK*tj1ZZMqUU3J@0z z4g$I!T(y;!97zD>xm^Vcn%}1l`dSIg;bZDms9Ig>jwn(K&Fla6ibCsyYDZhy{6JvGs$UQrr1O&cCjd{T@-4$(-{>oOFW}5s<%MM5& zDJAyISbMF|DCMtnK70j=Y{qs3xVX-M2$4ypN*tvM|88pdeoMNn&YUS9wSw6hvno8m z8V66p{zaHYLro&w(Hz)r+o1o6C6ZOHRnnrJSHrhvqM7%ZO-!}GH-f+r086W$puYMT zsyp9cDQI@@xE~PlTRUEN<_2whBtzJx=T6qv-O3x4$5}A+IbL*&`?F~$`vfsu8k340 z+kScdhO%rl-G#Z{*cij0kC>LV)B)93!gTCIv(e|U=!p39C&sIlh40Q{cp|buBu+{yIVqT9F zuN*Mbie1yb7|^5ye5~lycCuJu+|_<`zue(*yMBgAU?3*#qVBE2;kLF`+L~Ug@&-n#G*KF^h~*@vTgx!(#GVLS+4TNT4;xc!?R|1#$I@3JZN~|7_?p zvs(t^7qcWh5iz7c-(&KFA&&0Vt+RT{?|~$O;!Kn}@S{1c?Qof(g}wsJExIrR5$Hx9 zVH-axWx07M0n@Fpo%_OHh`#TkdRe@(!Enz9=!)#t>*`^QBwR_V?{_vNP}}1AOTB`Z za^lhs(}tvd`uL%8C^|>MKF0NZLaNpRn;L+UdXXd@07{NItgon!=w-b3Pe=R$U^rzHIxz&yK{*@ zABqSMDPe^T_h~*1&ooLA$ycvwBuS!8eP)IhrJfIL$2-bOQ+we*W@^#MO+Q+@+Tma^ zYV=oHOSRkWeOEFz80Rt=2z)4OlwV4xuG&+FzNB|oUF)|A+n=JlkBck3_M|@)5CKJ~ z={P+xrTTr@&l}Vh_!l2QsfGh4^mFO!I*cUANXlb$w=@nR;ZofF6V_dTjAv8()_o3i z!jXw4{<($z5a)aN2B;C;>#VcK@2hG7q5z%%mvDeweQRMDkg3yOZyVKcA`4oPXRRx4 zblmRVmedx;0SrZ@!lwZn_%vA4BS#@xlzHd6cR5^R2K0^(Tpb<4?rzhXt)Kk1oKBB@j{~iHo20;^j z1E#lc_&%&?rxLl5#zC5v0zh%`M(Z&FB+6!guOprF{C)&|dj%uk$vy}e zXAaHZ8Iz*j0QhZqU`@ua7ssPYSVrA5$TkF@9beo4dq!>(J?z8d z&5^N8e~~=$HNd0t*R5}DBLzx=(qmuIoj<+U)zi`;`MHaLW;i&KjrNdBwxF2iE0fKf zf!tHaysZ<*(-itk{!VJy7^mnX<{me-i2a#LeXQSGS=7yp?=*j284y)nZFuT^*<{{g zqL;qrn__uTyWFIshC#H?4LGc_Q2t*k*{+r!J!a6!D7Q5l^#Lp%gO6nGm{F^8>d4YC zoq(Am(dB%@A?Xy)teCbn#)cvwGmGdI*3^{wMahm5*pm;BO15cShEzS(Sdj=U5z~h!REaAaQDLb;A4ycPE|@FPDSAPRqhL zW+G7M3RimQ+!~WS&+a+Jbsiv2;bn*~*#PVhkUIIjxteC_{M!4*Ws;gt+z5sexZb#n z{70r6ae(Mks7Ae7?*}%c%82)0MLhicVBfY5yO4$F@I@Y5S#s`Vj4ohiv!y9R>7Qx!QhYo zmMW2)4gNAcG)sK*wDbrgKfaN;`K8UeAzUHZ7(O3H#Xg!9oG)!Tb9a0O9!zThwl#lmPa zzbgi~fP8L{#7wboKI(#*f5Jn^a)&4>_Q6Ahb(i@&ljX zS?b&fJ;v;E8A{+kid+b-GF>vsVmsX|jCW8?rPZSu?`e|YFty1cYR_Lh|0J&rwC+x` zD;?FXC1tERDZH@l<8*f>zB38*(jG%$xIsL2wKm~?WI_{c& z8}#yv)J<_!+nJ({4q$Z|1}0q3bZ&H~dEMP(Z87^@M2!gB@(H|;; z3Nyo)JAtg>YMn=6k8%?wKy{md7RoAR!ITwd3v`A9^cqW#<>7v&ya7OR>zyy^(ZoqW zTT;rSXpkzj?zvrsd5?T|Vqs2X36rd0OVEttL(@BEE%H#Fg8unAPq*TrRUFwgvbyLvc6}d5v>z?S0 zZU3UBptDm)5py#Oo!1fGENV{Sc2crkxl=%q4h7V8?VUa;lNm3y&h7`q(^)=XKzfmb zqpF<2OYhODoVpY?j}F#sXz)usF9r}i2hP!A4XXm@0NIRVn(ce2dcR@A0AmBrkJNevmT49&I}fNzY_i%@ITvYAXyQyzAuG zj(I>E5uD?Lisqen2&Z*;<{_w>wXovcV#up66X4!*Adz!;i zY6~=e)+Ec%6m@&3lw3XpwVo2mwKTiSFqc(r5T3C*d#YoCvM*}i59F>?3W^`PI@*l+ z=Fc97|5dXG`7W1DKsf?CA%{_PfQzAe|9MeRQ&&YW>rZmvuh!o=$+}aWv9FWB_>nIvve^u2S9k1|Xu zQMuO%=qw@=rwp447k|{yhk>;&rrN3RE?5B06n9wp%l&b23XRGiaFXQw!?$$_(7MAX zHx6%`ek2R@50#B14y`7T`bz9*K>8}B2Am$vFMbsSn0cx3r@;&U-N^Q&^da@M_d4m! z8zf1=s6v5?Em1zyXViXU$_iUgx?2@wdMJS&p4ItY1@Q2IHqUJ(JngBkhZNgNe>svW zt-%MoX>xra_j)dLzeK%`CV@|@Syj~}tVvJ??sNJ8f+?LIB@BC+O8^d5Y;#%#Qj&ti5J#%K9F_|QY z?S{U2QAciw#cM2&NYk3>(WkA@tvqlKPwoY|&8i@!?P3*_2Lp8Y_9*g8F@C9ME*Smk zT}XX6078gTT6Q>u`qr7ObhQ(>f}LN{@cW{eEZt}E*H-oGy_xk=6m%csXFJZe?2#_K zOLa5h_eni2nQ8B%Afsh%EPc%sZf0z~QGfizAGck^v(BMl0ZG|pB%aBm*6O=^{6ARq zMcZ}(jBZmg;k`nfw8@Sopr&~t{xEO`!V*|Y^&n+6brfpE8htPcgA`mpTjreBL8ey2 zlqzw10#d*mt+(6g78^J!9u_HQN73#1Jo{4A`~yCXb?B5nE2kmukz_`8TrlpiMcotY zx`5ZLC)mye2kdzKc8QmWIE9%+sT(wPrSN8A;*dE{RRE0tAO#Rt>z!=M%b!= z?#(G*@}*LmooKO7NYO*kNum?cr~HL{CcLkzEOt6_ydP!KiA01ZC)l>&Cy z8Uz$2Vo%}qg*!y7fJ*H6mi&Es zaM`1KYhAVfR447Pmp{{?JhV?xV;nax*u@XM7&eNlbu-vfL>R!J2qj0Sp@Jv*CsJ{2 zy0@~x0)q3xV@OpFlSFzGD;0j<_rW7+7r{ibP0!-R@G}6%oQr1lWA)&`1 zsV+TI7DjW}3?=jm9dyX-v^~7PRTjpt0G0nHQFbRfYTCx#-X}fkFO~9pFVz;@V=&|< zY)QX%q##lAt_q9uGBS%tX-ZhHn3c|g9!s`Fb7})o;3D{Yl&S&(fMb3M%Q6(N3H9M? z#&ijP7Cx~b@(g5?Gx)u`E=(A#`9}>PZzPf&ed)hhD;lQ2-O|ysv1rTn|}t1h-w5jVfH&*IDD?Y>}N3-u9yM#a}_@f;nqmGX-DD3 zNrIQWB?W~zwjFtbbcak>STbCCPR{b1%NNKA6*E#IyT}Teeu5BNx#vYBF}(>-=Hq9n z03v6{CSE1)8DUi&8U3{Z%91 c%o6^pCEM{ew(MzrKFcvadI~E>_nB3)SPjHdHMqEsRZ>OT7Im>;kF-K z`%J*+#h4W~&ZP+mUM0R|eQWSh(KMw-;-AXZu_QnXeaGjSc=Q8$2lO`3z?xjCM@j+m zR+yLi*Ko|k_;*gh<#e*1+B(fK%EQ@z0xz|*p_IC(9^TjOU+&GUU49Vh{s1@%FKP6o zZ-aMNff6tgj(CqSAtO{5Tcn37r%;X2#gTLo`LSQa%zt2JF^{P*Kt7nBCIpmJSaVM0H|-jH_mYIT7c)2-#x*UOyxC)PSQ=}OU8KmC31xP zE8Dya?F>*gdzaj=o(OTpz`8rLL50mHn0!T%n41Lm3L>u={Z21?T6wU_XG|Wl&_U&X z`EnowwGNn>1d52U8O+LL_5(VM0ossM({_6H482kos+BAfHkh*8gjKvq4j%u?+ik{g-4JJ?fqL}$HsXWDQtnu2mufZT=!7q>Z0 z!O1;*b8+1PxU4}Uy278IuoWewq;7PRN_55W@Tp$Jrh4EN(=p06iXd4}T+ABm;H$xA z|M>+7z9&`}UM9Am{gNBM_2z%ddBu$J!s84db%T0-2g4R9} zJD$Ijh+B#)g;YO)DuR|{&phjePj7F~VY7T1_}QC>)%eUJ3DYe;=37MtqH zOdV39EoXgD!SP({j6av_>c=e=E$CgfoSZS@o0Il{yT~jOV-(2e0bPn^bs1DJ z_+<0@@{t_P*XCr{@VO?;eA#Spt5AK4gSYCxavbPg*q-BAB6mF1`!a07G|O~_lMUftNpk3U3pJ%b!d!!QWo_amP4*D4f0gK~_b-vi}b6u^?2K-52`N@jt2QfMrvdL)&I zcAAfYM(wxTP*9=un%-3&K5mA-jZ~)8vO}5``FEBQV9a-6yJHYeBfcd!S#vqP$&_v< z6>SrJdN5CablB&&QhF#_hQ+}Ib*lMblD4Z9_zQipOBb+nyvu8EmOKc515)g^Nh5~7+vUv-SI%;IOlRD305#@Z&QW5l{TASdq_WOxPIv>F|^CP6md5 zHw@%^4~!S*f6U2Wqc8T@3JeR2+ z`4^(PZPP3rI1)WnUq3`+|CG6VTsn?FEEB1S(M2p2E^Y}#NfYnzLf26#P-(GC=mp0o z;8T|o+a(3h0e-txsr3Fl`(Kg=xUJ!DH+HKbK)j=dI!C2`i|lv*%uXn0qh^HHsiS3H z@z{ytP>e?jBm`AH>}Bf`FN~;`WlhZuD4Hm?^H>hGwv`B+-HmVc>DMvE%-wynrRz~@ z|3itFD3BI4erUeJbl|7cliw0}HlRL*b*9>1ivde$J9~ni))$fEt#y`D|2xfNe=a6{H-gsUi zrad+sv;U#y@XT0v*o0k22|>1YJMWudPW%44O^+mGHJ@5!!uczR!=%R|Xx zMewM3mQB89%3PhALxckqYlurbC?7DuO+gyACqZvwP90sJ=m;lJ7q;xpq}4|-rN0sx zoEEwGj;IV{qbr7oHN^*^rmv=UJ#V}P+EkxKv6KLR@!vY%`4@!re%2l~mqnwIVM%9R zNy_<*M}KP-t?Drrokf5fR;yY}dZk)MPl9=`>h!(5F!oz;IIvWWQfGA1P{1pH3ZsL1 zS2OaoBFN7$1w21H{<77tX2_U5$FlY3q1hq;T2uh@9tSoVjq9%MXHBB}Z<8=rPPz3k_dy!zYy`$i#Zw4T8UT zT$gZuI`5^iZxLYzT`CX5l4z)qfW|!a^`T-`EFX#BsM8OvKk4z)zvW_znj4rA2y>y@ zB>eurwF|yc9UJdea9!%j85&v5>NUEkEgBvkJ56vPnRg@)XDMrz8k`Ecr5v@(t>N`} z51XC2VQtod97lHfV@7Hc-kl*u=ac)b{#Gsc7Y6~I@3;hLkj8R~6h$H^Ab+F^l z5!_W;JwmbVn|AKfw1pJ4f!yCfq4YY~)Y#E?=9jnlmoUr8q!`yFkW~+ZT%YN^w`Tp7 zX_vn>hxd*y3!tze@!O~EZKNe2Q}Hg3X8QfA&Sk}VfH!*B zD~#8rJV&KWL@4gp_I<$(oq%foM+$-_5#WuU;`HB}nXHRgX{iiPEJk(PN?(^`kforl zbpXmm+Of?T{M(0w!>DhK`?ml84>VaL@PWYrO(iQN)AX455%a1Um_79pZ2My*d5n;*)Nh z@)*5I)pa-9aPizJ(?Tf;kUOsFzycjyWWl>&2yex8Gp4k=kbp0~+dXlZ;NbI}HL$bU zjkbO=vB)4y<-)WpS}jp@iCIbVq86pWvuKCed~cj%Tjk8S{^_Z|(+C=n3;gejMiwR+ z*N1=G!(&#Jl@PNn*-px#^s+v-EL~?S8K?Js@ffH=#CVb>epkQ>BYY^pAzZ9{zaX8^ zQ@m7M3KYwE{_Md0`dMC|X0`G?3O|eJf(Am)0EP5g|@^{3J4mA(kG`=Mo&+1e`1ZDVjGb;!9Ed>i$T~BE`SXvfBw-#kT!4gHBk&otogibR0Q4>qm?Bbea~dYSlAoTxCoZ zVC?;O49C2VH4548@iY_hp=I?W91?H9cN0kIQUD!%`??c~bN)gL>0_I~T5>mbOYcq; zdG?ehr~ZZf0Xj(xXhH9t?_mH?6#3=`g>l8yu?Eq{1418EKb&&5>11lmLVmq5%|CZ0 z2~Ili#;19C=IWx}f-_b-kQ8rqVzT{R3g8@Knxv_@ZC0okitWH;s+qi3M7CFn%oSyi}K8422)fVJS4YlsN-brH!$7E^oW}(VI&dahrjZ z`@e;PO1MIVoU@p=IkQLiI_o8iw zF+aX^L>ER>({TN>%&12d@Z#VWr%UCKi~zihJ?z>|EnobBEk(BY`PX`vPrv={f zvq!pM+i+|M5Q$0!P5xc4EK~26Fx)oG5fc4{!$ycVmO6M z9HkV5y38g+n~)4P zgLw-2^uO#G1hR|&7G76qm7_Aq6%#Mb- zl>E%F+I_{Z*Aczm7qj3ua6J6fPD&#oSUf^G?alu@897VA{>);4FHF*rZSq-}H*;U> zIKfMpVSrz03-vK_7(#`vTH){*&ZipL*CsjfQd&Kd#D$*I*ZWvQoaNu27%>JU?9EKn z+?|1Zi2x6IZtqY&6?oUIf)&Tiw(2*L?w~(@2H0FMx;lTV(SRLKRxF(yH)L-+znXIR z=HcqD_ANZj?sa2coQm!Yy?giXji1J<-`-Hrz1HmM$QQ?x$|UC)~^ zMZmdlkXatN2uTx$}!N!YeA9se2?GmwBt^>nop<{6n8z`iE-~?Zmh49fVkr z>MZ!Z1@u5n?9DK4>&k~)i6-W4&Xo_kr!8kOD9va886M;-HL+v)2K5hz?mZ>DKwR;v zXS-r4pzm*`QqjcYYN^&N$|+hJ==qd$?a?C>-071y3V+r;94l;T1rOljE?P=ciKRAV zI4lGzIS@c!F7U*#dMXfGPvDGI9G_0ppkK?Qh{iY@`eus0&%&nqtM-uV{Z#Z*<6!x(a;U*p(P)pz4lPdc2j+K<9bc z#zshLn&EQuzvUk?nSu!~t^4>QG|q4Awr_?%TB>PVcEx~Yy0*QIvxbo&7Uf(Nm9vl& zxAb&sZ+Y4Yi=^`zAkYx%&EZ;;wiDqwJEW_WxL6|oN-rCHt>okk$^>fr??M}RYQ$q# z(?jTG8+!%OA~b^9eg}3?CFQky|5PhaiEZ^3dZ_POY;5}=+R!(d0CYu`DHohf^=G;x zM~kA`Bvk{%x6)|Q3-6k-H@^GJ^sWs|O?{ukx-5WAyvz9N?c)o-``;b}y5a|n>$Om+ zHO(0ZH1j!V6fL{XOodT~?~Fqznl6M)McGTSSeiWhVAR3OzvOSG(3Tn}E~Wz`TFZg+ zxQQ6sk3Ft;QeUL4?s`%5S@U8l71)d6`bZG~zOR5Id5-nFYAe!WAqI#E6TaoQoF|sh zeq)ryUbvLHXcX-IG>OdaviI=!4qGVj^Ci3T-bbt(3kzd`N$%63Mes%YPvVc@N9BEs z3jNU&wP0Wiis7wAX2589l>bF}uHWe#>zS4rv&}gzwA!zB&GU~q1G+rNFN@lnSsdT~ zc;|zp#2&6E@O3X_pUt~Py=-@EtH6#$wSVGI@C}_&@)(R=`+XtjUNeQSWar7(3Llz- zI78jpE5+&oOSQWLa73Pe59lZ7B3>CoqFP5U`B_@yuR>X~zdfE91?>SNw5B&pH0byV zm+EELY!>x_fpz9jj6%g!Y(pnts%dSUR}w*~*1z6BIQ2MSO`DP5z18c@{6}H&2h^P> z2R@f+_hU>kil_hTr6AD9Al6&PD#Wl?o3QVpLfY*-1HXxBbqATfA&~JN{_S-0!i54a z!2`D9a~DJVO`YZab^YMv!7$!J6YSsAEtiQZ)bqNV87C+Bd^}x**U}ey*8L&P#&)?w z4uH{oH-RUYLf}rvL6S@Va8?<+LYHFVVK=wh>>K0DXjSsunnN!>++IDeook8fvyN}B zX+WJv&oHz!zcr=tws2TK9m`;CEBHSC1&?D_gK^rEJ2Xau}oJMb+vvFb!2F zQT*rO|HZH%n!!9_Rolc!2huTVQ_4=2YtxgYI7yGuUF_wc!ttO*#o~6(92`0MJi#q# z{|JAbC$qD>(}~Zqa2nE}n>*JyW7`i&FWJS;Sb4e)eMW9>C|hr`yN!vkuUy0`mY`P_ z>TX0Gr&2Q6k8s>!1^o>jUS9l46O zvu_}-FkL>*7BjPK9iwx+3k7=wkv>q^l!;07vPw*=6Me#x{T?xlQ$HmemMwoJ_+j)z z&~Cg`$+jGf@c%py6o#6??O7GLEmq!~az-J#waojhWk=ttY1Wgn03TW*|4450D9IL= zGe~v2?N>asMab1=e3M6UbmGVWpjz8^=%1W*X_F9_jZ-9pa;~%Na%A#KZ-G3+&c@TD zp6_BkYSqgPSx_a70;GWk0Can|U9t%FXUDla2~;>^-O$>&w*(w3ACe)Ng*;xQ&yyuS zkc)yweK>t!QhEsHzMyWZ{qAZ-5^j?>%%!ZMD~`DMNNbG_)834Jw=NPn(nUf}cuPn! zq8n~YN_KHZ*?9$Cd5Zl%aF`80qV4RnpdSc*;AC~C-{w4+I}5$7GAuqbjTXGqo0IoR zp0i;p`<*cYD>Z}D_x34_*DaXQD_rHn*msMvlu%$wjKAOC`x+*ngL2o?ad6OH3~>&#RXaBG!)$G8gmZQi5XubzXtX( z$|_eJHl6IcUNK|X{7W!9!V;Ckl_uS9^HE5czg1LkQ>8tsmISSf_uuH8kmQCYtXQ zeh?F1=DA++K`-s%vQqsyMceSK^0i{TB)<2t~A2ygCl02$(+oQAYz8n5x?-AT=O3NW>e9&EYq~7vwOd zFtilA4+byG%yD!Omla1cfWSgxT5ziFbU zejdu@OZF7_f9$=5U)0a@IDUwLph$xtNJxluiF61eEz;5@4N3|}2`Jst-2wvAT}pS? z(OpM#H2j`N=Ct`h*~+ZeF}1Ap+}O#EgXxK?6w32PSN;%wDiiyBA7UE8 zS8-02uIsF&vt{dzPpi1n27+|9l+dx5B^Amd^{WlghE5j_`jl9SA?H1Uc@FFoBhN(i z`LMHGs3$}MyK&k+D-38vD=uHZEejaIhL!qr|FA{MMXBY;wr0GMU;Ee{W~>Q~R7XrD zVCo(#&~VHvaOEnqStVsjfyFw>H7%W$=e4Hh^n0pC;3ZvwJVini$#9y zxy)ui*37fMy8VV&JXjWhM=%w?JtS971Y5ses z8pqbI^mWJ?K>pu=V^FT*R8VXsE1_n?r~W3bY?+y<=4d9ih)2NlNCGKQdV1p@I(Jqr zbb$Bo@M8Zs(`+t&8AC&VS#KSqv61CNQe@!hdVekSNMXb%dcRYKA#8Lx{sG?xmc7P1 z$f1H|-_%s!saqxn?QHfTB8VDrad!F`RmbTm1lQ^fNXR!xT8k|3*%lsiu`f{Su2bbn z#xGKvPhz|?e(;F*-CV?^`r7L}y}?}igZ}Jp^~yH3&Yptv$K0Bk!D|{;d;QOOi8^du z-M?*>$N+DWUQB;h5jIdL48cC1fs&dGh* zc-H=FT0!7CohPuoXq{=NE4b}{xPpkKPlC}!GIlv%T%I()yAiA{guZ4E+ z-QHrN*6!p^B_-k8nobMW3$v(rN9tpyoKo4T4cbT}&6T}Zc%(@Sryx&Sr`6s!N zU9dGSHNJ;lJSH3_n-Ss%12eDPT})D0bgcuL#0?BT9k;B?{qvE?vWGv+F^_7*9(uZE z#OL_q-l0OBsLbM%)5sOc$ctmy%lf0)zF~IQ1*5vrOb~@>3mL-V3Z6N+& zq$)m6DUInM>N?7G@=` z_7Q5B&sL6QlX#lwkN2xupJjAjeB+(7_x!0?<1%!DNOv;n!Yju8n4qfs$q&2FhdH0ZsqC> zjs+ZRhMzO&^X#riJrPs1pU$o0tz}${U9J*?!Y4`7ze1tF5l&UKlY?`&CV;nCtMNtnv(TuTDbHYGqBdI=XX%N?0< zdMGr5JmAf0{UZe$w)1aF3ZKb#d>oL*DpyjOsn(nKL+pGU1YNqwJ311VqFTLC{uGt) zQkxpCeKjIk#`QYMQZzIVLAOO8scM1|<*@wjQAH1Xl%ptX+SrDs{Gi7rdrmQzoRDAs z9Jf50czoJDd8k?3q=BF+&mzxQF8lf}Eqp?v30t|J4`Q6rxgrYozyqkXe!olLG>@~6C=fdkHs<@6L5H%K3`WaiqW?jrcUw5&83VdSe;vMWl?QdTO@;mUBl zKP2l0*-0Qu;WN^>P)!-(8)2HPGE}gZPiEYDFCyu^{%7MX4XfcURlxJ2w3wEL?keY} z*IRn$sZE?&?&`MKYOGmEF)2^qBx_a`O-=b0U7^sWhlN61F4t0~NOoDqG-m~em*+5X zULA(ae*L!~b`&IOg&Jqh@5V$eRZG8M=%Pwke8gJ(%RgFxJH2o!1WM9iI@Ctpi2xtS zP!%@2LU@v4T0#@HM)E1knJj1xmly6W{KN@x3*`JS9oT+x`TMoM^Up|ao9L3)av_4@ z75v%qAW-afn(2skcR-ikG;Lh@QoVq#E#FT$(pNbLLqyxw@u!tE0Vf5c2;x05aqJJ% zcrmyT1ugujm|IC>w-)#FvD#)f|w*0nHiDdtd zH(<z7GPn!BTTLuBNfxv{EK)I1JCB_>V==8*TOLHX` zT-MFocd88}I*+Cy>?j#1OD1|cOc1LnG#%#!E`KJ8CgC`y5<#@qk_tv_y0`!z4<8Jm zYL!*It~u$@Y8kZ992;vzx{oY6<lGm#)0;U+_-?vWrxq+8c ziO!+&fjWwgIaAf(lTTX@1Lfp!3~Tl(Rxf6mN_(`9-X45A;6AS1G=J9s9y*ZWR6N`I zbVVLOXau7pH;E;-tnD}df;-27^0RvoTYRGQQT7$EP#K;iUbWNUGVch5VBiIjq5}@U zBs>__U<$~z@{F8~>hbi#0aKD*XoO7L`#p6al(x+4H>E6Vn|4Srs!&HL5m@`I7O~`; zdfuRIRN$r`%_)JzHL(dbjsU&dQ zh{^0)(rN4#Dv{>(!#4Q1qks7Oa{aOz(&;f->DwdFIE5y2YdM^p;~VzPE#1*_Y6Kq& zZEVPXCNe*d6F<-lIM(SPhYAHv#j>VRZ~3qDpNAQ$>_!LvTqqQ%6HPB~_x9=_o}&nd0R zc9bWsK2bEYes7DNkYm?YqtC0`dIB2fS zUqH!M^vOb#E{#_~Hig8B2kLY^N{Y6%yObouRNeVrt~{HN?h9VFpQmeNJ-@~$6)cC6 z+$uyJd?f=1vyXs;s}d>b9%UbM*EzcE${Nc37U()WKcPQJe37diWas1m6U+8vSGGrj z;^wWnOE6l(Ye4B;Jn)WM!LU|n;tD-6Nh8mIK>PVIp;(#20q_R9z&j}v;$GPtgZ{>z z{%qi8MbpFct*RF4hqAtL zk4+c${Zz*B0Q&@{gxax#WUVi|-KHkNUk<0-)p*g>RUQ~-XrO$AS$bErhiT)Jcp13b zyD%=dwsKkbk7UVn1Y5rZfE$$u+d;YJJ?%y34u<8U1}EcrMr>l%=G1dyYihw-dk17z zeX?E^5#oGZ1+uy@7HCDYIV7S^*)*UOP>uX~ephUWace#kOq{sCRy#xNSiB{Mw?5pJ zVtR54hHZ=ou2@YO+&>kzgOv6CcmQh(vUx%H`ku3j(?zQyI+bGTbW@|*JrDN{Wy0EE$>OKbGo#&M88Z|r9Vsl zYRNH**5her)m%And7f9@%YyAHNAW$oSjTZTAlU;ViT$G^`*-oVQkppGQwAURifkAN za1Loi%-17J8MHJ)dp2;hIZf27FkYfOS&z+V^Q2?^Q0mWN=Z2tYv-lyP@77By1br`m1q-hN|ckH;5hMFT&JFA*{fMDQUs5hO0h=gF>L|Z z1#5^4_%4iB?_Ka-zm&ZNJSgVJdv63?jH$5I~|X z|A&0!;|QK>$lmg4c&;Ly7O^6+GUv~+BX4lXML1wJ@t>s`whr`HDfC>-R(+uy=r&UK z#CCOIszl620bwc1uZ~9F>4~`Xqn}i)4%dsIvztMS_)Aqbp=K_Jytu{r=5t-^3&S_YO@1s2&1UJ1| zVT#tdg8{E4>XjF>WXr9FIZ7;-)ksBYvhj>A6p1s2v$CXK0_7h!&yG9Bo9HWATAi@5 zU39ZwcKnixr+KCdWFnl)|52+v{WK+rG_fH{x!uN?jq)B$W`m@2G&L%dDN&5S%3&GC zu)lMpc1T)oT6AP`5|?whrYN$%IGme^vd|vRWAB?Z?|u5dBf6nj z_9jD%RkpKK*~BMJPOQt_#E*z^qh=NdfEOPoUfKp8F8r#a(o9g9Mik7H>6scDW7zDD z;qWi0e_%Y2;Y%POBq%I^e|)w$u+k!DZ#i8FRz7gK#jhFk*XwE9Dt0MdaZ?7Gd3mo# zF)xN1U8b3W-wFpW*T7Iadv+5k>#Fzu(4(e{t4^D<=0b6oB- zidry;1@5nYW0Z1elq^FN7Uq`1f|(G{~mzt%AMfC310G4A9_A6fbYHG<#|0F+s1KZN_dm36(W$W{6P1vbTD|RG40^!_v-n2)Gx_ z5J{~7SirA~o1uzJVjv__2V1f?Do~b%#r~vWggTNyPI5thXPIstB3|{FeX%UkP?_LU z#X!~m%pRl)xubm`caZjV%Trf{c=E2yjbMQ-hSPH2^>Lm=Ug&Ex*Yc(LvwaaAk(RXL zYzJKC5Y*Cf^tf!bx-z;pAN=^-@yl7+Em4m z0~9%o*#XFHs|{~@!DXKolg8-5rX8^!Aq$ruU56E-Wj3voOi#2Rs+wYbPt zn~vgJmzB3}%-5`Qk!W+M#LB-QN<@=A{tY|4q&Dt#D|k%9q*ZCPesO+^{^7qe0=SaqYU^*_W-t@MSd`Q z(dC2$aQ*7_EW?ncT7ir^6$haD=;2O`d`!GeSyy5(OP4B~+8HRexT*tI3XG(Nn z->F00aicB0$j6HkpG;XBp5=wc_f8xLg`LR)>W8KBvhiyeE1xl^*%=KkmSP7wA}+D? zRvHkfo-5K5Xt(VJ!@^`48Py7&w)c8C`zilWVfjMk5F_V)Ru=I|=1Fp1Gv|}(_4u;! z5z}Us@yl@{KK+Xmtu)|OihMIHgfsry4mX`mpa<>1Tw#XhRSMeN< zklH6T2y2Gh1r~ILhsC-?F;{6q|uvc3oTVvH=XBx@Y}EC zJ7bQ1iC<+CBgb8z3wy8KwfQxp+8MrH)N8I*7B^^LLM=XPg(s={ULttW1LJq8<(Qqq zG+y+KumN2JmWBl0mM1}QwIpI8xs|hd)S7=Z&{36ruc9%?R~z_+cU{@#L7HQ zY`D)=egublR0|WaYwMt3JmLN9lgi!3^XiNHS2P2;5SnuI6lPklH6SX@3<+@JeYZ^f zLau9gw$O)R_3r#*xhTK}4+2IyR8HT9y}s+534rKHe=@x+AyZ(jMdkZskQhgHP{_BG zpfIbObdE;jo%lhmh(u-WvP}h@f@YM+0X3hrmu_xgbmHw*3y@%@K8GnQ>}+GKDAGcs zim*jhzE(VpS~`}?I-+y+{QD9ikdQ?$#IPr!#%6Ck7i`($97-)6!wq~J&2~c9g)<@a zU`NN?Zm10bG>Qf&(`5Ne(~G$Lt4W!u`e`QvUb~4wuC~$xGV8?}w8$UU9_Q&!);ZK@ zr4I0aU9U>koaFFg-;3i8X?#p%hQ({}ZOB1!OX8=SvB6ZN%9E9Y<3s-JvK5D2;zuu~ z#B*=22Y>|Kg}(xi#fyIX%7+GS1orHuU_@^Z9py`hUuzSZc)0s))XIQF-%xe(Rwz zuxY5XWt=!E_O-nX0gwFJqEMusv3T!_oxzcoxkk+J{i9+Fk}wT@#mj&-KGcy^6~Ft1 zOERoA32RUX%1crrJN_*0+oKC;+X#VHK3nFCpQ|q}VC=9j4e`cP0^;!8a#if2@XC2E zyIUf~vw+unJg88SdZG*yOMtaD7~iqJ;}@y#&!V)lZ77k0;atb71Zh7Ag@I)k?b7cL z@@6tvat(34r@g5DqIoBCy`<}WE%XtcRe5GB%_^R4P%@)<2)37(??uU*ojexVgTUL+ zF<|nBVe7%lE`Qg}TS`DPK2&XdQq2b%aZcjIIT?JoM>`VrZ0( z(4D2HQ=U!vEk zFFx8f-0o|k%+t!^u0KEol|Rc8&&*q{B5QWu$f%v5Xf78keEV635Y%d!GJq7%&k0HBda6b{#klsW2#vZxpcaY zfjeH=D&hI}T{xO2C#IMZ7X=(piF&GwGQbZFP9L6Z|Ms6_rIr~zI^@}lEkDPyxZGWr z5ZwcRKy|r*4oH=3wbhvzza9by=eOr6rh7_#ci#0GK7uq*KhNhMr>*sLs6oTvbzUiw z$}YPNZ3BW})J!d_0-Ko9xOqSza04nyl2+kFg%#fOC;G>g9N9gWOL0CehNtDJ3~S2O z9g&7XhZj37q!>RnM(UIp@K0Jus}2Pe3(f0b&>*R(^EWGT6>EceGx_?QYt>2a38TzD zz+3a&FA|wIA{tN(FY*GszK;!N6@eT3jl#mdU;g^y#jEi!#C46Si28!ord)ai2yPJVotUtzjHhIN>x}bD%s)3D0fh^H50SKRJJ5)VnPYzB1F(HLX1kXbu8a+KJh&?Sdt4kOtrEUbqlobXv&1D z$m{Yn4g+Ej)eq-cZPva=-%}P}W~E#_DyU1BQ2fHuoFcsC^=-^qBDqb;6 z`D9-axIwrJXjxUsvZ)Ebw(r5BR#HRXO^ldVX@cCH0eE38^KEslb7_D^_SQ0u%fKeyf_~Vqiggu>`-$OY`b68%i0Q~_&fVT4 z4mHjP!Eu^$DVZ^m9377$dJgIw?x1$mWT+JAfC+N>jjiyfQw-?7D=Imd3HL88Ei*Tr zJiN-KcZG$d@xeC~KnNYc0+N~AYW6p>xDk&fz8^Vs@0vSSZsHpC{(9yt4i4@oInIzs z*PnD_mw31?KA5L5NNW0m)X8{bwwB8`f-X``+vkp6UCw7B|Cl#Od^5|5bBbC0e+=$( zZVyu*D;SMES5ac5UCwcNp}w21T|9GjLzy}k%;_?aPt0P?QRPj8I}+MriO@Xb*StI$cO=Pd8QF@) zc-k+|c{Xsf6a!TM0XVD%;*S0zuX5a;X+TV7^g3E<)gp71 zqvHGG_R8HCkFd&qzcu>)a(;`6zjQcU_lPd~@HV~(UCM{t{mB&bswKH}Y~f=t1}V2w zM-%9h_p7f``}&UU3ql_I4;U~~-cL)N@*^H+g-hLv#V=iUi7A!y7&n@HQd@eoUgi&} zFuO!_sSW59w$~LwS?NRtct+2@I_Z-bCjp=Zwxa;;&U+S+Y=H}n?MQ(TLM!d%U7k`phTgazH>;2Gul@n5Px_?rC+)MXLM9+mILlY= zbw_Y>$mCm9f3C33k!heE)}V6F#R2Z3Xkz0%Pvb^1d=n{Si%jOBJYEcU&fJ!dvWKoo zDI6Z~;9_mgsjD>2GGRZ+WUT%P3J@q5I{)_hxH=rKr2t-mq;KU#q4)6VGr0L~JA(hV zFVo@1lO9yD1uQ2w^`c;*_h52=FOa}%xmDd?CzAZCM)fwH4CDp{$Qx8os7r&>;F$}b z%)c_Tq&u$lbUt2z<{n5}0FauXkKfFfy|rUS{#}%T*Zycdolp4(Ng_uE6IAa4kS1v6 zf!+^o*?)JY;kC*uDyI8(FcjgPy}Ihm6C&xOy+iSTI+z1RlBYxCt1o z9?MM;MwG8lxSh7QzpC)YJ^*Em2+FKAl`a&DDC9y?*96~)~c&=cJ{17Xh`&Qm>Q+Bmb$pNN7x2IRkFe1g}9EQr5 zVkt9>$S#OhLM-Z)E5%A z+5hPh^a59QZ6mtYbUoM63j}%yoE(72748Yg^GhvWu*2o1W{3%_AT;4b13W zN=#A%^EImuD}u+Io|hPfzd48imJCSE224KeT@PT=8IVi5q${@dZg0p_u_r`er{s2ycBCIuNFX=stIhEV zIb7j7vHVRVH~G)Y9V1@~=)`2=_^dbiFaJ0d;yu&MR&g2{Lj=8i4Cm!>8FMY!Y(N8) z_5^@>xJSmvZY3y!@P|DdPps8k$!h5hyB#& zYQt2}+S0jNU1eyQN&cO(Eg zty)yx{!U5?PNS7idm9g^)bKk`Ah#k)^^o^)!ueOamtv^{)^O{OpLk_=*AqU;l9?er z>_ZOdux{A9LV=u<3vj#xsP{ib1$cd_*RXKyF7NlUwYxx`3lzYMdj%xC(zYvXle^b9 z#d+pv0=!ynW1o5N$D7O)cW?I;vgdXqJ>4UlG76YYAR!UC%Brd=HEzrEi(lSVMMYI? zhTRE!=Vv>$R)(XFUV}#wt(-y zFb)O-)sy8;PCt~wad%tXQbZs)Akee5a<}ULFbzQ?c=g%0D|^Xb&2F+TSNxw z1ozHEDN2`bdjWpCp-@sI2<~_EL;JY@_X`^M7sYg+&pj6Zx2vExQg_^bM9deiGqrsH z-}+18eSUteiwzRVrC%;Jo}`R~s{R`XQ}~|T&parhr`paN3>B6jD3zC*COQkerPA8EL+VG1)zuCD~48=04bh88`bt zMech-$ba>dXA~^|WilW)yH6V5|Es@%+z5fG{Tm1b>J0>t|KBnm0-*6fMUV#@*bo0H zMqKxO4^$cO31)1Qxf60VK;epUFwx4i{l!EnP<-mj25#MO|{;R!Uk{oirjPZ zr=PDf=LtT5uv%^GqX*`OGa7+Ei9_UX8JGz9O=sOoPMrE#rkRz>n#xTuk=w!gzFjjv zH;+Hl`_Vb02WPS1g+e}!n=u3x$gh_sIE!J+wPO0!p>Wxh)&%VPZF@PmLDmIM&0W=C?&Yz{f!|{A@(HFT=XIdKP!AATFt>PJ{~N0PtpXD z5KwTDyY5hMne{YN-XP@iz1nhA#7l>Wh>{vWfrl5ehiQz_MJ7YOU1GB5s(GwK*^1^W zJbus$avZT`MwJSaAy`=E1-)w%KnX8?nt@F|zy&@~jz&aNIgl#%?IDsk3!|&vUK}F7 z^u*SrOR;XODWGUP;i=3gqlq8JlJDZ*-;bXzbk=~#4+dSYUcJCK&18nbA9ke#H>hv? zHD7nhe3GP=SxsQOjyZ7Z`L%WG3u0zQx$X0@Wbl9pgl)+0w()zZe*En7kC2;0f*{@D zvmg|bx9icD*;VV11crVfY~wcv-71qoUR_Z!bahSST7J%0?r|g}zfpPr2WADI27vIW z?=1Tovi6T&xc-uNhjO))=sEMNEGC18bDmfjf!j|SRS>Q`9B!@xrvBk9jWCnjhU_J( zz_X@3G`9T9G?1`By;Xss$`(n@&^O0B)pmYnJ?|giAl~(HCfleABq?!V^bo`B z^*0H&GVP=nNSx00Y+S`6j`vw1VI%H0=+PQh>?g7SfBM&~Ba!dhsld_P7TQ>X>x8Of zdZzS*OxX5zPQk}5n$?f+;oRyr`X5_lLJ!~{fKp%}_Xp%4uB-p&YbgPyrHjde0F$_W z^^ipn6v;^N2AxbXoD2fm;2Q&(pj7mjm2=WOXK|bk7|gDun9J!{6I~9b>Cy`mo@*-H6k4Z3 zC2x$2HP3(g?6&{DSn=;vLH}kx??d(eH$Au$Xd&`mmXB6jz{wCyg+O&T|M8Ws?2Yaa zX!Jnoa~X8;8Y~ct9_*{J;~gp)3o|gor`bs_cBJRk)xV%6cZHj-xK;ghafFmE4d-=z z!B{Z+B9+fRiWw6X=zm*RF!C^!9iKJwq@Y&CtG2KvM)0;fX;VhILg>&9tOaumTSOk`pE_Yy zy3;?qfd86-IlkQPYc;DuZub2-LkARRu=ygHY+E6SN$A);`r@3M2Haf}PWYXChV{-7RGp}LGOtk!K(mI_ocZF z8?^zQo}!&)al}9u?+RT}I_AK;z#LfTXpzCl7eq19*TdBgk`WBAZ57EqF|(9jcfEBP zwvm*Q7{I5CEis@}AtJcxPSo;)#E(7o-(LVYt`Ubh*P5-ke%VDa#(?juz8t4E2us6s zK&?1{GUk^lv0S&q>+cz&mrB*N`0a9qCmVG-y(gGqSAvVoM&_bGuwa?=ID0&S zoWoPW!i7zb4|U*z(G|wW-YVZ#J4+c?i?$^yS3ykjzkOKgy)qFs$?G zdZQeK?WN+oTJMLMz!D_e2#XlHFf*k5x!Dw0io$xj@5+J27c$ii9oELWKEh#gR-T{Q zS}$0i4q@<&xjG_2Rjx{q~U?9>n2Tu+^C*t(m zc0(M2yf^vQtWxxoPe<8wROZVS$06(1=iN_O)}x*t?tv9!k&jzc|2+v8&@7hchFGuo z8<^u|g*@5zEJFdgBc6Lh^??AurZ7e#7uo}htQ{*@{MIQhxBt>tZ~xf&2;M+L6CnQNa< zJmF!iX|aOHi-{O@(ENq1*9+JosXId55nV9dJJ-slH;rZO>|rZn{6#UJgUFrRqqHC{ z1q-b{JAW&=Ywb<9t-UShq*W&|3XlP@yWayU1#i$Ml1FKtjBP!pDaG4ce*V7P-s%SI zr;^|dl$Va3uS%DL?mf%Mdj2s%A3}FSBf4*dEzFax!f3G(6adLy2Uh_FCq}1dwUg!r zHq60D%uEH}6JFxp@;;mX$aw5s-pF7wmQ~Vgy8Sdii;jRe!8QfM*4B*vfp){Y1@9$W z3*-j_J60qjZd~~5*)19g*t}2zg8OX)prZ9Jr3ppMb-ve8pg>Ja+1qyw{xRD0oLL``a_gykmwon1nXIS_NQPe;Ll& zTmdzKgaNa7TULLpC+!QZXo`6_M8T~-j8#ctTTPRKqqV0Y;$>|YTiZ3H(5aqI*H3al z!M*b-?4VhX4lZBG_&dkbs5-YZ&6)0g`wt_SlY4}UO;s$4c8mkJ8v(N;co;N*yK-Pu zQHAu)sQp=g@l#^p&+tO-+09Gf972}N5dTbkn$bn+T0Ay>{Y1l#)Lw3o0WGP2#z!cM znr@zdgK=-#llCRtqMGkVNl;X}P<=3M!%ZWP`1{3Qxm^~OAUR*ek#<+S-@Pn^l-x8c z$ouS`_eMd=_ntY1b?aZUxj)~3&@?`LTn=5Vr(^(E7>{G#9AN6TtZ@5re+XItjy;TV z-*&HaeYz`x6(k<5cxPBVW)IQCkm}#%Q11D5rPu+}xk#oHpxSU?)JcYZdU$#}eUyw9 z^pRzG$bEOAzf_PCoM&w@q40>X0?h;s7Z#R#D?LAG3|-PddWwPZe?DX=t%VwR7VajkN1C)UQmZS;3D*5e*?;=T6HprJ2FgMPiM z;Rd}DQ_SY+K1qo#24GcYk(QA~%F+{H6$Q;+!cv7ZjXTU`flbqhq=705AdoyJ;TQIp z853m^eJKsl=gc4ePt4GdzSiJ^{*c&?VUj>;@dFA@biw8~x}oKn-N&T_$WN{C#vi|Y zEnaI1sQY9u9!%x;=S-WHE(2rF3ALrMlK_F!W14TOd%q*#pNO!^;3I@23D=Z5!Y%UI8Ma1i4$RKsShl}PK>M!&ndQj$KY@2j0LrjF*CGLVsjNP1uycw9EW zMJECPV-YrwEX~)NGXbK?n3*Jf7`T7q-UlNj^a4DF$w>h~Z}La0@y@S)N*T!hg@*A^ zTac333%tYj9aZyubn5TXq`aQcEA{QYSya*>;JbcUY6zT%=Y$9ue8d4v(5CNyFGoAS zraEtz^=5xU+j)jN6MbTora&)Q{uj)&)VDESbNc2SQa=4X>^kf?HIta)n_cig^znKrRS; zgwNxu{2nDRlV7RCWWMOGjtNj&vc|wX^$Mq^c61bC9!h*Vx!U&!L>$(Tge-@aestvN z(eofm$bC$XTq!uZ?$FD_PopVqTqe95bftbCjUX+G)KIL|*U_Ni2`)@XrIyz&C1@`;SBF zj5{Pv#uBQyj6eLTn@aM7;t3ad7788qrD?;Nu&(=wjD@h%p^^+_0Dzh$-zadt!9)MP zGeW|4Zzv-E1)4G?byGy7OWz}Ua@B=Say0KaBwt**cWG~QAbyCT#&C_Y3llKfy~OX) z^UYl^XV-fX>n<qd=hr)k;+f~e@z$FZlsR>Sw(z0g zDBO!Xyt8ujRdumhvN#uT-TsHfWUaF=CWYj&qcr2s#37g&uzco@Ej6W?Zg07Gcgv;^ zSMC+B7xiRM_Orp-N2!fzJ=vs5lJK`%!y1}GbWgTbz-6~Q;z4D zA*P;6*W$->Wxb?sOrsc3j#{lzNl0jx|0Ie7qWX-R<*YQcYiddxOayWpElQL01@;H! zaGg^A(%v5HK1%naq5V0+QsvC><1L0&z7dEfr48D97TPZi^Z@=bU3gx9=G8u@gaFP# z5Q}U}g(h|wg|`$d`5P%=vQ_zu{CB{s^uPhisHEl(0zkpfHdZH#`*H3Ed?mHj5kuz@ z5DTzsYxWu)SuBSt3a6g6H3TvNz9YEJ&#nF>-I4FNsSg$KA%C=;L7$yh$6*hmDWXkD zO&+zMRi^ye<;pXq+v*ee*jyHY{Nr|qQj}O?YAMv=XSgKIBU_QdQ;A&%Bb;o zZmk53ZY~KyN5*wfE?_NH#1ImK`?j@P1SwPj)lBdRdNRGv$=~KTLReb8GGQleYCYe5 z*;xTi;D$ZH0KGkIREMw$4t7LM81{zT^S3?=M@TFys8P`%lHxIT@@FENHUdZYX8x|$ z_JSn9?`2|+4lX8OaKQ$0OAP^DqN{%4gyQk7HOvf*wFB5&0Zh5$w+O6*I|iD}dnhV5 zpwJ1W4sG3j$F_13fFWQa&rcWeA&OMxp4V!UWEBjTt{+%vLhcVgwcKM_LaA7vur|xb z8Nb^}f31ekE*ol<)?V$#KkfABMC8c3>cS#_Qb`a+bw}IL-^U%5ubI-A$=(5BBFan{ z+gUSuPPR2fhJ&B$Isi$poNPCxAg04U`Jc%Eg*#4M*A6G(M4AKDLRU=sW_g|BT?-oJ&++jSq)B1tu5s<_w0RB zlOG#xqz(1~f#Tg09qxaYrKp}o#i67YN-ZHc7&inz1Rg==Im&<%f(#`bHe#NZE+>h8 z$-^3LIxZ_SW5TIaK(qU70NH~pEbhBSVX>I!@637t6JTTci~}PeK;?LKguU;n#|uuh zuJFLBGD>L>K=(>8VA(Kwh2oDeUe$QW`nV>VZmTSv%Y98^PBeuTmYJv>p@izB3aG7c z5Sprox@?_ydC|WuXTy0;D_Abw+<#<2K3T2`GWkvj|Qht#DK(oN+AWe>a#g8D~I`f0l8ihb1JpMsDOK%}Lp7>v|!>&yAZok&)j7{yksX~W= zn@51&uB+b58$Lr7IU_pbE(VZ&^yr{j2;3k4J1eocWVpZOS;SqijNM~XFxq=cmy?9m z!hAwb^Irh0*KPrCL)VMv#v8O2!NrX6=3u}$LRN~@CGYc=;%{Q3_Fdu-KTl);RA5m66p)WxdRnX1 z(lr{0Qns}FG5`yC_w|*Y49xwhUCE>oeD0V;PE!3U7Dk28WAZ7IN*fQL!#>;3Xb)pS^5!bVbR{8dMQDQXoqTiL=?#^ zG$Y=O3HyryZCUeSLAbQ#Be-iNio^9wT0tge%Cc8C6y+OW83y8V$RYp)Wf_4HcBoen zWpuG;wA+UMWHlp!wyB-t(h5e9N;ADaO8k6R;&i;b*g?R1-m=Q`f+3dEK4c_Tg<$`L z{6#;*bD1iOs6GT%$1WyQaLB!%5^jx@5bLXb8iFVFd_?MA->+`nw!SMy<^jww+707# zvQsHR5`vF7v)_?zf( zNtNZ|Ax23n-FkR>0~=eJ>ueU$$kT6Sf__n+%XK}*Hg2l25KW3Z_k*KEt}NG{kYK*h z=1pN>P)e@DH(Q2aV1>yd7N23QY|mAgF_BHdYo;CTx>`D}##^Zn^IR+^@PX}f)rvmU zEjRRAz9+uV(F6j8Je8E{S4z)d2Gg{BVI|NQEKM?5PAQux{AGXXkv$ot!AYZphG3gB zY+TfKWXZ9r5B9nDOmOV!m9+rVqA-4fNEru+>L~1b*0v*SE&CEUtz`Zl78HXdxJ=N7 zaZt6+vh2WFJdNso?>mOAqFdVF@fy*>5TM=Se4t`q z>#xmd(d#}wN-vudNEvn5dCVe@x-vni-1*`W|NQ?)(pASb^|f&mR8&+zrBzB=xnZkIbLPMQ z|0e#UZ-buqzAmzzL?TnQ7>$UobgBmKL+8(aoe&1b#d_v|K5ei@e23+-6}LU%jdtTH ziCAxsMKi+3y$BY~yM|XU{jnO5MME`jLTw{me_;EY?J50+Ko8`pef{Q$W#RE=X4a6D zndEHO*uDco6@}-c8#~;26Z;7gpy}LyFv~r~1z|Ll!GJ_$&PlSq@5KM_^0n_XxC9c= z5BPpFVbXj5L7`h}3%KpvJpQ*AIeorQ=5R5WFFmb&H#*skTfIk?l51AG5si_h4ByQVW@A&W@3>!w z&5W51n;h7YK-pPb)O9ivicMTDE<`TZGo#cV z8$I2v6FZ*3Kbz8(txb!xGGfza%vVa84zK>(mh7IOA}cq#NEfzsYO{~~%{ zqqB3<-(7pgb6V6OlOkEg@E%eIwASy|XQ_YOy=!4MO2c9xtNX;4;px_(L*=OR$P*L@ zh@Q?)T@TscrUj{*xb^x3-KPOg&P(@fBFRB?Ew)6w9F_m;v!VFxb>OEr*j?gVn!c>U zWQZqJ&mZxKKIjAXYv!&qqKR(N0t(7;3lL*fA~b3aODSxqgB*zQUmgfw=N88BrGTq# z{+cythAZO)9|bILL(?Lk1fU=NpX>O5>-eC$a$ItbkFDh|Fh`jI1#Z-bS5=umlZ;pO zdg&Gy|NeI{$mKkO>28R)WbOhZF8@69O7k#gJAM%*WIaE3piLWlSQ~I2CSM)ijxvMk zPq+DteW_VQYQW&q*WS$8BFwd&0t|pRe%YG1`$vC!R_EevTXZ2>j1xKq+*J#Mc&y9p zEhaz1{_Eo6qPYNRx2Q9cAVcjR=m5#Q^zrB4l)YK~e&F#dDhp~@|1_Iv*@lUcFQIg< zHmM_5rWU1}lm4^oVfzG6=kaH$&Z*Hvmx zt4(3IGpv9|ui9xrdVSu$_daUu+NH2gZ`G`t?3-am#Jp5|f3e&S1+p1W3-87)i#Q6A z0(A1H7AzocH-4ebz-_RP|F+ZbzYG%RT9TUcaL95G)#ct>|CZFXf1F7Czpf(yBwKb3uNw{*$D;5%(;k?Q;t82jp!td}wMX2h0&)4j zy`BETJ$m+5dcKx04<(7&=C(?xrEoISrzs@I#Lr215ot+#r=cDT^ z{}f7om+AGRO>&HlYCnhj8m~#CUBVxw+th4#-{TRyEtCx6u8Z$8d;jK18CwJ;2)Qi% z3I9UF_h4OaEj_8mavN$&!0$_WniMkkrkJv>f%xK0epqEJj~t^4H~yXtLGXKX5X{SF z@pz8Xm-!EhK&hNejvOB=B${o}domDQwm8q-qGAR_mJ%x~dMK&nO~Ny_&*6BNvy+G+ z2o8Ad^7~BjbZ(IQ@5CZd^4JM?QjIgQ8xFxSNk6^2+Rv3(N5f^(_^zoIz^sh=mQ1Da zJM(TYh#$rMpAlc?R>-q*M75q`*9P*cUw(QZ;jG24d`*?F%nE`zeEy3{pHp=H3(zZG zGHjExg@e)rI22A#sV?1fs~wW-Ana1x==$ep^~EhqL<)PhRC{d~rb3yo?SjiEydVe9 zGsNAGD;NNPD(}B~E9^~w;&p6V^+Ix@s!q*kk+P}QLEJSNl(-KfM1)?bDeg(W{G8FF z`rZeR@VBL2X9)t8N4dMQf z&pHt847C(4y)x|%oYFq;7lTTpI{)$&xKMNvw|<#!sk?KP^j|Nl-=ir5`e3({K(*&) zl}532#|k>v0!ioBDfFw6J5FyVNA(=^T}*m#*A#YEBfPdJD~(}$@s@F6fX7C+%&@#{ zcZx~tE?;`P>%`gM{N>u@GVKE80*|ZRa)KTgA>rk5wh!CYizM&R>Bi28t(tP{R~j{0 zUdN){9-Jh&ULU*=-(>ed7U4Rd^J;7s8FgduaLAIEwb z03J<7yGz-#%T9z~bh0{cw*Z@J^KCnO!iVANzHGj+*lT9zoh{HQvb_JwZu#}$)tgk0 z#0{>@HF-4mdjG+(%1pnoISMn?jHTV4BtA=|tKS6W3-czJ=R;)o4cF)i;$Cxw=q_o`$9nW+VTIT^J9ryli3krbB!a?V&USBIYx2NJB$g~~bqa>Yq{QeV8ky_N~HSibeTz2o7>Z^dUMt-K%b5Jj%O#q0GH%cng4@>Fv1M2{fEU~vG?02@X2%oCDWxhPeJOp zCWwMBcuo@t9`wwGV^qDLde3@5sN{peMNf1D{o3OSK6{J-;N?$? zmBl>U;$~d`n<#4D)C+Of6vvW!!#Xo=hz9KJa?gyE@87=#RqzXj7f(Q0+f{<3oWbIY zT1RCW+KZLwD`M}%mUs84(Q`;^3U>>e9f)tyM|J#d9o)4;c{`Fcs}vD5s9%90pByO zw8z|mFxlOj=m>vZ<_(6Qp_6R46jDlq;$jj2I5ny0+@U?PyLS@u58Xi%cGG;)Z6Fbs zKDx%w)%T-m&dVofqOu9MvzXb|EY3F1PQKd^m z;)^dCOh2@-7)niRh#5xA4g?bejWXj_M%NL6TDmSl_EKBUirt^`B4cFt4%6YGWOE~p z*omT{AqO-Z;XGHB%+UA~xmc;jl8w8lU8F&ObxEaY%l-`(8#vayEBiX{{#T9gD+^y> z_Wd!N6w)O>&aLrra-Yv~sw-#%q6Nua+`ui%l6{{B+UN>Xo!7+f`1|Dn;j@c77t3EP zre@zNkXBZv^OxGs-F}gl><3ZC`OD@TTF&_leB@ z`tu)bxZ15QUAk_DbaYN^P>&VF;G&f!smhx`0a+Xt(9y|jqTt)K@< z-Dum)^Ky64LWbs|>kqR(&c> z{9CRWhy2S~fJy@%ZTM~LZW1@h2nen60(AdruIAM7Jkq?Li$P!coEog41_`r6DE z>EvPu$Ng_D1s|C5xc}l07x0pl`n-yW{BA2>pbG^&v>{ zp2nO8n89Bj!@XjXwtBLNH`$)Lz+sIA@W zg40TkFvb-qf&aTMuN-+-uYomC;rgor1_BXLi-yBG7Ny;QNnn)(LUnDn==s(tQgKAcb7R6?j1$e4b20h$ zN3KVYz;D}B!M@7Kh*!8FA22o}f;;SW-l+vPBuDmcW*R{Id|~35n7}jX*)Rl_$WyMh zvYHz=-I0OKz24tnp|z|oBNlWGk>TN{yQAh_Ie)dxPxJ>Y=7MKkTqHgy07%G5&>u|7 zPZ=*6;KsZ>^>6fi=kRaIzj<9Fb9qr$BG+~E1q=0*P{4D+WhSZ*c_t5}$#@R*XaV~H z(Di*h5iGo*@sROEMqOxO%3CH$6H`1>=03l##6>a$H7{?I6Jt{5t7o=l@te`$o}gr5 zQA9<&^8LPu0E=@nV~Xh$yUlG8(+RCSZ=XKyb*%KG+jsjSwn=JSe`)hB_Bfk!# z{tYRRn7?-|)F&eOl?Iaey}-iyZIy+JgP&=glKUW$C;sJwd+uv^oe5Bq8; zAz`-d$c430=3`&6vhU%E)t!Yi|G~`5eXZ*Td1&{2&3l9z%Pc2f} z)zh~hMYra^x*U%44q$+4>Wn6L#(=cezuU_f@ut`lFS$+|!c4+?ZY?Dr&dT0tg(Lm_CV?Ns{MS?}T@|TizNKH<46%Ny zXddr2^d)$zCG%LOJgAuXFjc`k2W9a_T_0P!(aBA-Fq{$)KUsYSpLY*A%5r2BMvr2fv)syij=QQITu#ZzF6Zxqa6U|h`M zg2DA`!ImuDrty`yR^81&{^{XdhKu#@9?x2HT`^hJe>B0~)Q4{0^=<$nx`S%&)ggK( zB;bSm)soA%Thl6H2sfP9QfTt`NZhslP02hF7ocYdP)rAwb~&>1Sk~{h=IQDT?WEB= zmlb#%gx^$JZk6A$xz4cNDKphMW5!M24Wg4`vprjJnzOphp%`!n1umER+gt6|{p0S0 z?8qbVe&|HINYYE;Qpc{T*lS-6Ivixy9D7vAIpoT4;X{v>sp7WZc6Ab4@dC)5*~m z3Xd(2iBh%|ywTm{7)Wz%4pf4sWz}Cxy2)Yo<1D<%|COWJI1T4H$WTCg(bz)JlN zJbc$}U9TJ8a7M@YYp9kY5C1j$d#dom_TKy@>FJ5@d6bHt*H@5!eAIds zHo16LE9S>1#|pdVcNB9b4(>2dzmhy^8lDQYv2FEu{rMK-+vmQlBAWTg)RfEQ309&L z&o|kI%e8nY#A&XR`+NQU5Jb%(m%9)DlX{??d)V86-{2DW!bF$fRaq9eFRxySH>3{E z{mc=BHTjWl6^$g9HNK9bngU3$YpFc#IM?&^-G8&0e9_u1{yH(iq&AzcIF}zpYFP41 z;rxHHqA2}P`bwP7`*HAE>R||UJG$M>zjy7GZ(BiCNU^aIpWx{a#lI(a61%r+#T$CP zugKvnuc6yX-J-9sG|!ed;IV*8^(s(vtvAcXUX#6e=Rpr~&Tied2`*Yj_@W!1#Cc48 zn}|vNDkdIP5~7-bAv96(#AcuMHe4jiq#)_4z=c>-i{9{Nifrq)W&>kID~87MrMh*Q zXw}q{iU3`OfK-$u*Jx}6idxmNT`x1VLpDH$nfyDOjLK?7{5_)yOz-Q zY}|LzSNBQ`hlgkHD35JX#+~@%V8n5Bg6+Arwe#Mr$a}~!$P zmz11Y#R}GUzl%R()_bkUcg zr=fm?+&}`Jgtrz}ad%%DW$RC^G?U2MJuQ`j+7Qo<=>gcI1)nD~>ygT1*zCDkn^GQO zM^m%E~O78%-!+yM5jdo!!|M+n;Ok*_Si7#3XZ?H9M8o zPH?eazZLNL=nl7-6ROo2f1x8};LgGEh)1W^GlNU74i$8Jv1gBl9tuXadXO%Nq!b?Y z*L-h&`j#eIm+SM}LHzR*i#C}@aT)->JN)xX$GorFzF&llSj_5G!@sLls|^oc-H{~# zs~ao0M;a#8KsoZ7s0>>Ja8wLu!T3D(t7sC;!IZp$TdjaMwhPYvCZsBztEE#ek}C=C9E?eCla z_|rg_J@vD8HzPus#m{0CjKT`>E!9v|&E<|58c zeH0Z#H9qgCLQWa-`gQQRM#t6G#`CP~-yP3U!{As_Q|_TlUyvqQDn$p+1a zonjuaaXduc5$(>8w(Q~c;tx%P+6-08C%a4(YgD9#M_-R*kIia)-UVOCjiw5JK3V3K z^?5JwX<2U;zEtUELuy_1B*cM`AUfexeUoY8bb9+T)b=)jcboeonXfP~rqCp5ZXiGp zmZw_$ZRdYhhLaqzclFI>o?*gy)Z=%XQ`aO_S5kZ!-N8E~2UeyW)u|15WoNRVfiply z|B&z|zF)DtJtHXW4pRh!n?^{#ZQDG?d0TsG_S0WRtA3UsvkYZrFVb=aI~FjoEq6od zX{Renb1L;u<=$;}bhl7uov6F-l-*}{WZ$({G1JyP^y$l@Sew+vr=(L0X#s8X4Mfq4 zqKryq1C2ac)1}(8jLB-!t7I^$CXg@3L!uVDlh-#2##K>WWV_M$1+(i3c&puASn`;y zu)ZQKZYv=G?u{B^Ix9iuk-Wb`bNKlyJRX!7?w?Qd#~nf5Zk_yA@aDXIV16E3Yd$@C ze+Eb%c0x!Ld`}#Xu0%M8V^!~(h`nFD((qKjDxkz}DvK`N=+);{pVs%aJG})RO;#^TV)e@e&=he=}2##@A5hWQGPl!IYei%!<0@v;`YKKW(3jlY$>! zO1754S86(npyPQCZ~s&tb&?1#ZCeXuN|YSUo->S#1pUL`RcL+4`#_)jI}69bGuXti zlkZE;8AM+n<6S^I5(DWa&HKN#igrTgezEd#UfX)sXFqeQ!h!W5ErY|eQojGvlF`_^ zLl%42OqA_P!JwTW)G6#?J>fgxg|dZvutJ$O{)!E6pQffb5W8iW-p8LN3K>;~4$l9a z-c_cFS#%|!$a_KBT*#AdOBE0IfFs*h~NWu4w>6X>OErbOe$#yu}YXW{MG503u9m5q_eVCGl*%v_te zO-7qZpW+_b1Yy}@Z7cStFm+7LX(%MeNINn}aDJev%al17h-;-E8n2sSRkiUo#6(J= zvCM00xfg3Kd*^!>MD(e+)6$oSX(C|#E{1YhHdFFG>CV8ll0 z`}8|@k=I|{HE7g6EX@bRZgYwkO)Sd_($3U{40L)21Ry*O6PGN6M5Ao!f=pbCPw{D6(!(ldiTC6SiSrHP9rRAs zi{`ZL(DJilfI8%4epOVeVyls?4f-o zEWHovYGuuX`PkfUFFR5QYL}>h6ghlx(L9lU+`U66d^==7%zbA_a0>qt>8AXKUBYn2 z2@IRraPQ)&jAlpj)WM(l>Wr)ywuclsA%T9QvzgzV!aIOkU;S)BO!*Jfelw{ekFmw` zQ-;WF^KbRp*J=r~-=8P0^(hSvfapjs0?#btJu3AqQ$8Eh^NwS2d-5**-O>~1S5`Rcy*<(jEXPs=a%+nL!p^Ql$PFnxn z(al%x3oT~1HZL`I4E@bAM^i@TW z53^RLP3HXhFq{v1sO(fx=^W}*Q@pjg^!uwEcTttQ1RC)Q=dPpaaO*|y%|5=skybzf zCLhx%qs;=BeE#>a$}rs$lBqs!GBY-qg{gL-%N7n$J@B2^1PY3r7hs0_EM>M>w|KNa z?k!;Cx`x(%rJ!S>-Ty;MO(YPsy5VDwutkz-gCup;W|yJCixt*rqXuktE|Uyw;?o1Fz#RD%X0; z*Y{o`F0lfIEvM7b6`s<_*78Q+=A)Bk;uNMwrZ=NOS?)C0`}0{NujjN zGiH>n_8XN1KPVaynp@05%R?SwW1BzoQnl`G?VHK84usDYo6>AZW=Yr5-7z^@lUn zTOfOE6|ov%L4W+h`-mtmxN?4|{_7HWf2X`TQ>OalOF}k!S0Fx&0dl@t(W#jWIx+oNP$TE|1PSOqyq_o%e;o`9v$TN*PV zG7}@?%J>(5EG-gy_JGrEzRe=XX=eo`&cOhFw@s*zJmYiqz;O^56%)sjksEMjKQ-!JjzlVVTdL*N`!)N$ zlR2{5vCNXNnm&mOV5r(R!$H2D{q|Xu?A@mFiRVe#99p>n1WHEPS{EW_qRL)_9||re zxiw+6T!N-$7PG7B zr~sU|Ys7R0j zEZN7B07p(9?uvjD!j18#Df6w9+%YaUdzeX24rse*oc#mRom_4b_V)MvZZc7xtmPk{ ztwVrmKW42mxfp@(Vqzrd_1QhFKj-Feqe{_V-NR^yBj_iWbREgYr6}nJYoXKfo=MojUceQDqw{_XpJ91`H_n(fE5m;@J z+5Q>ZI-pug+;HR*;Dnbmm|52? z8ZK(7l^zwb{lBdao8P@gaA^#n+{erL9u~XG6OQ`aK3nF!dqv!-L)j}!w3!RUM+I3e zg}65ZEuj81Ar*Iv2yu5;WQHNLZFR9%2zH_W-9ohLmRI~JySLzr*B(@lZY1^_RGZaU zjVyN|Wrv_Hgl@KhR6cy-BR@=LS05R>A7C9AAB}i`MfYaNaVjv#`09U;Juea_&ZP7w zsfxn_$LQ7&zEoh z%C!%UT0ERxWJx(5kNf7+>m9J~EGw`XwR8LBC~tSql*_BQBFR5TdBd>EO179rr6&3P zVCfu)q1VD|{<%4#A3lv)X&FH+K6C7uCk($|k`s(C|3npSnQ-p*wH!bJH(-=ZhuK-% z@BfteOq<=6{*i!>kDL!5K;`lSIFda!*Jt}J+^kEDhCB6QpALVx>!{D4({RvES@%|7 zpcEOG*ggA5)X{Bz+Q3~5m@j5jQ@GiK*FDF#QYMgqfrSWL` zVo6`fe3YoS|<%Z3|Rra=aLjgvqwl`X{9FhX0ju zIC;KiN*x4wwxRE+&5v;3jE8?X2L26wX}0L)#qNpnM~HKNm!lnn-w#A`v_Nr9LumCe z_8)l06)}O$_|>Ihc#?4q1)|!lQq8*ucjdZ+*)zrN#KRR1&a~xecdg)|I%yONtkh8} z`oplsqD!rW)t70e-v9WIAqoDxZ$aFgF<(51fsx-iZ(3=RN3YzBbMiLHxdQ7IatGhb zr+n(RLmEG$abBn>MS=CYK8sMv7xLx-GLvU@SuG5_Sqe z$fLhv*B>vOTYaqf>qe+8j-1*bBNv%CpLHKms5bOdkv?3s4MIfui?b8qC2^&Aec|@$ z!0N|R1!Q8hd9tPLV864--~gq|zw7!){>waR+)Eb`Q{YMJ?L*K2%Ixkq+ho>GzL?ZM z;d|0oe0)xZYQ;jm;aDA5Zt!isywuaLNIJQoesdotMFWe`G6F*u#%Fh)6?;3;T?SID zwIlYfsI#+=g9Hj_9&3_Sn8eNT4+U@+Nk1~@nG71!VtdQB^0v!gf5d*~ma660=c*nK zpG2!0jE`qKhU?8w-@si)5IM$8W;6Ye-`8Q$u~Z!D!;m`Hee^it;m&xI>0Ov+6P;+Q zs#Der`w;)>`#&;@GIf*wRvB=hW0IcDwUoqd3F#hsp3!@$6QgfDwP^!n4`UUoSS;c! ze88aO>pcs6=goqPe&N2=oPq`qi_sI$JeqIoet+jd@WxSEcD1q&dv*1GBOpajd5=E_ z0AAjdAObhBWVhc)Zy(LA8Ej|S6hD+>aU7Z`w6CK;^wT1Y%Tw=J?5`eLrrvyN0_Mp* zYMoImn?)&jKdr#P@!&0N=}HhAvE`(yETzduPnIHi$K6_IZSG;B!&IAU_PZA!j>cEY zA{Tl51|UHld}&UQ(ZfNNrn1LnuGaOk&z8elXI*~+a-93Upa&K{237Rl)&R&7L7$JR^G|No(we+NkK(8sZL3-HlW9{;cFNR7X^zHoU(LksOQ-n$Eu5BL~=u6#)~ zWTaGgItF58^hE7xPh9L{WWS2A(*?8=ryMboJwJ}xy{_uv;?t%3Pp;a;SG-T$D808x zwlH$_F{a)DS*Y3Wbh=~FWxO|Vyi*6>bljRsHPvWTX|P@Hk^^s#jfn7X^0QSFoVvDr zjBWL{@30YCO4)8$wfk*GmDhnI%l7zsEf~L)k$~ zpFL0QCPFyWKC9QMvr0%qSj9L%eyXBIRc+-Zm?vEhgc!eKjL${0%Ov?!=^7C35%${Y zWIaL^Rz7#tcOgh)%roAt1gjKTh+EiWICd&GxjPhIuV2 zT&t(?kNpAdy}T=?v+x$Qq-3=P+u%eVKDOI-R)TQd=o` zO^)pB(>lJ)OE_yHdFH)U#CEZR?F}5Bxg^2_xRll}&kUaq$yDvG3nuk+lQZ}WGs&X) zU@l_OrfC6&e*z_t%|6jaDr9PO9^QIU!ae&+;tje)JCw`ZY>*Ga&$=V-kyWbovw^k);~~53Gz1x$eG!WYt8o@A zwUSg=fR|i}9+E|!v_HGW=p$P&%=xiRC&!4ZwZ+;uPMR-r>TF@=_fTQ9Djuwtu2kAa z(OhQo2kAFeX26IciON(TyPaB98^=LCx_yp))?c8NT=?GM$x4#X56v_=B5oaoy*04~ zj2~f(tHu(MRweywkJ3wbsHT)B=)ruxTU0sfwujkZP0RK^$CAKnLoBF-iv!AtM^AbC zJnP!BzCE*40S#UM1B0H+`~f{4^^Qcc&>$sqTJdxq!5pP=K7uKJH*6u*jr%{EHgu38 zDM!@$DtJ&9MY&Qm+fBUIM6&zE&nnZUdzb&23O?GoRd;x8w`x@d8}B{Y`A=q!=&Ev*iF!>eE0crBd%{do4eIEFzAiH8m?rjflks4FFHdq2AIezSDM@7uvX|q{y=S`>`#JmQm8x<>}#I?^0WkdRZG`mf939- zl(UL}m-b)M3%NOB#iyE1ZNmp%M&o%}-X32G0!EBTw7zPuu6tm(rNYNp_LX7oC1+wN zCT`G-U=$cD^p)N%2mL_VE$5$R_lne0((QYIu*|J+paoiT&r+MYy>kcgu3cn~`uCc; zU0u(9eo0CE?9*)rUw&8tku6qLEQ`^kC3ff$Ii-6ui$VH=#=fq(&oP`T$H-!|>LGaH zVaRFa5@zw$VqdaHun1i+QVEb*TX?!nOTc4xPp4hyon(%W@6KC8*xndScR<70)Mj#d z|EaJCE_#o8B=TksYW*d~%H)*C$WJMSKoOkB+xOPCDUZ?fo0DuS8bI@9{uNOnK(f_I z)+P(P_q}%*X~I3->b(5+^X*MD$0_dc_`Nk;L$tQ3SoPb@6wjXKM@huHZx3<}LCkv1 z5BLv%T}d&!DWl(Bsm;Tta|+IFJ)5q*43uS}=Xvra4EuuziPCSp1`W6fO@UxL{@(cv z4o3Y8u)WVQ!IPgPn8d7B>&u>ZBr>&`+pm18u1?1xQNtiCP&&!I%`vyPL@m$mJ_p+p zouZhskGr1zL$`fUh;!iB)Gf(hKQq|OCkhf-K&I%YQCUwh z+Ju`vgDuYw9@8*qwVW`e=)TY9ssfzUy&h)oerrQZDkuSz+6n53TvA+U8c9gK7*=os z6^^ul%*0G-AtTp4SfJSp{1O|4zhlgiGefMV=uFd*k5?1B2WD^Os$^&k82}$z@wgN< zPIYoU)XW|rAkMap=ItWXV3#IEaJuG?KLyUucqU{diOKXqmN-*YjqAFH4X#k$x-(Xn zgZh~dHMnAZlSxw|&jnKZ&(vZalmpxRlNMrnt${O%KJ@|EaArgyEIY4tNuR@Jk^O1s zx_aFmNnZFIC?x|G+2s5l8;MxHeZN6jKdmKfrfX6%@d~X)!6ygpJZ|U9uD^G*LMI57 zr)S;O+t+Wt*q}%;^I{LC-!b+sB2_XDKYw#AD#nlea_^IhDpNeBbMu;g_SYOLM7il>1>}0aP9}wtzZJ|Ma3hiD z9XhhX6Na3AGua=ZV(wPX?R|-%9_;r$8H(avDks0vy8MGdvaMz`_2AP^d*^F5cPqZ* zHYx4FILwx5ah+O+Vq2u`=Fi=arO{QpvwKn&z`|Mo01@^6m&JcSl@Jtw&Vfu|x?-}k6ZrO3WujPSuvOFZ6_3U9RZ* zVKnw~L}ln|ye88z&?$=347==(rXh0?mN*rAX2qruGxq+rwo~jPzi6<%c*n8cimHY} zX_@eaC2Y_{Pw1@KyU8U4pViB)1@GTc_z61OiVs$N0uaMy)9zKQp5)pr(6r!Y7y{oblIAk2ON#Z;+K@s!)l}$JRn2o!3=dT$_Z@ zneKxNp2WEyZ=vwt3CB{NrS0_cvodG;VW|gWyRXb#sJ{|dMv3>|b@ye-e*N_vP#L>BC-NABA#afA!B!+{})W7SlRq#FSZhkN-2RXNHtBB z@G-Wj(pZw`5mzi$z&Pp2>nx^x>%l9KDgTzyLNT*r-5B@Eiq@TYVkSDlT=pfYd8D2KV*hl=c^oYED+|YWw88_ zsOdS8*#|MEZOmw^^}$yG~q(%f7MwVRgb z=b;79ghzd3t`fbw6Js_lrQ_OUgPaF9$uUf2_-W5a#!5c-oSaOVzNH3E)<4^>y1$`&p@_wNy;a0TlU z?NUfMQqN<{p1#^4uW0J5Df_5FKB8L*8{Pmuu{xbmG8^>e*F#3;K#X?T0P(o2R7ffg}VgSH68le*t=k{|f_hnDsDTjO3 zPWaTK8Caz~N!aEvC@xz=iU-Y?06CLwhbbo+aeAqTZbV8;+vFUK$jX9B7 zqLgb90AdzB(5hLHDm&gvITs9E_Ji(~?%8*1IV>h0RC=^^c(K3==lKa0&MQA~$Xu}> z{=beH-u>Cm+qlrFI^VrAbbqCz1AN{0fvmsy%M( z{op3D+?hU({Iyk#2N>IsWQ>irtba6cA25pgsqxwqRFsv66x-ZPMU)Be%R!NG`v=U@ zOEL?p8dVQL-~}FHZH53b=uNcT9XK4tF%FYi@?=Ph_ch^;kfAGIq(%b0x@|wyQ9jTd$FB`u5tuBzRktH8{#|xv+ zA1rhccygK>bSwE+p$3hGEcoYXx#tK4~2?#=l_Vc^uQ$$O$kNa9KZY-pD zCbq>FYcXOxMCP0Kt_(vtFq_QB13U*6&uX??+6CTb0PPSkFF0qJFVJbv9*irFpa)hDa_8!JHIvyOyu3n zi0(#QO@3@9KPmk}9-Zud+qqC+CI|*6-)jL#i{^SrRUjXnm7zm$OJ2F$H&-mqwT%RSqVuk=68 z6e&yVB~BrboRL1&hER)5cgh7_sCRDs*v11{5~tlYKZnV)fz~4?WPF9Z4cv}QM8gRs49&2%hW_`0KwMbQ9+nYV;Lm;P7Z1`fIn<*=flcr zB)16|GV*qD@tVCyK_ha%eXDivGG1ry@Vw>sl_%QCNFfX`pzhK$bS~N%`LZseolKl| z1RHtZtl5B$W>GZMgUL^6^1QCifi;0egI0T?Pa}$6Hbod0JY=g{p`Pu@>y>T&Qg~J{ z`{EmFH~c2trA9{ee3uq>*P!*DYnaL-ywB$0r0J*qPl^3F>~+bG2Di2%zdp_5tQo5h*>Z+7yH&rQ2IipkjQ=O`IW;nSQCfBy;_6opV6c@& zdOeiyOC8hrvc&AG{eSsswc7`b);M`mQW~^j#egwouZjkZL^X0HtxGK;#+JbygQg6! z!#W=xo^tE+{cQS@=j)x-7S`pY_DjxfXr*}Gpa*Zs`&sPtWpA`}Q5z?Lx30Q2eR zThHnRHAl?{6w>zJ=Be+c?q=ypZPN&Q&BZJgOqh#nd1n~DZ4zpgaxaYxoK18PwHrRj z9@MmD&XMrjI#O_WJ6e_1Z#HHT)q3k!+%9RouOSK#`f-ov-TWv}w!GZ~+2PnS8 z@$R;S*Xn8~-;)roD)ULOH2TNF!3~T2u|rN#&zq>vU&c6B&@10*!;eZ814xOEf>yMu zz;RgkzVVgs{SVWOg`|UV7*+^TIhOA^dXy8?;9&6isB5JsR-*VZF6S=O{xMkKY$vZW zX(z@DPb2#%pj$M5$|jLbLP`72mQo%Yhs<1M!w=ABhbc)$NpXX$=O}o~Uy%a>t(vj- zo!}+EV33Y0QrQnuWHaPoAh~UYh%OSc)i5LA&s=qZUY(s=6ds3nSaMhH|&C zsl99OpbM z+UXY~oRwMI_N~Fxb_+G|l^p9PqlO3emTjc9Z)$}srZyZXvqrClzN`*i2ShRt64n^x z7=OtgrbVe^aPY?p$@Db7FoGk)kj~g*frfoRVCufo z!Fz`n!!JB;OSojU_VmPM41V=1E}!=m`LgfoM8AEyoUVg-WBhbx&`Z1%kP~hxqDAGT znrOY(h7wVcw$+t|Onudn;BmSt*m=Lmo(Q@fOGxrR?}OEBt@%vuu6KjD?5ZQ`JmjpOP{on!fw)Q@eCp;|riMPEPg}|<=1-V2ITNNr=H68Om9!M>p0O#*$t{D7~WDHDQ7($@K~qi6cz=_pF_-pvJX2_ zel07EAJKA?s=3+bCsi#r?T2-vjA1?^!Y~?QRvlYxSC#z~E4DRJS|jsDO~8@X*l4)4 zz@}2emmc~07W{+hl8=QH{O1dWal!iK5w%DEW9cj0qI{pPEl@;4r4FAFLmAh~o4EFdkpG$P%yG)s3a&C>9D{Jt-L0N3^0d*3s2&di+C)mD@uGo)jK zs~F{wyB~4pe2_iT1bDCm)Ns?1q?;6_T^y||MuiA_;Oa7kD zLFxEc)1q>bl+_2O*bHFy^sdetH3V`7I7=hUCUn=r?sCH zNx{FRV#7|I)X6i;*vC$rY;F0!SBNPSn*;v?Y39g+&K}BL!9HtgjdlB9-13vSo4O50 zd9@Pc@2Q8vx% zipEN@3Pw<*Hb{7Q+T(hxpTsRHq-AHGxfaHBC++n-D<_y(n&h@73+cDVCk|ui840E6 z)KvT*b*p%R2**&`d1@?H^3;g^#Fmf>lQQf}RO%uzKXQi4E5(c1$bG|gzElu#eN*$4oV@?EW6DLN`ti*oh8~e-wpO3&abgwU;zF-s zR|6UC#0?1q`c}|Q7=swfZK(-Eke36QqfwkC=?3DUpstwP> z2%3x8PN2|WX=bZs=LA@#n|SqBcVb_8gUG(gP5o8v85GKjxmcf8R(n;y2D9h~hbC&$Pe$j6wnK=ss8nZfumy4_(Bn_M&mG=*q zZgU9<80Y6kTAQyXS5U*wn|dP`dyNuv3GkJ)Aqu}TlskJs%_eVNR5Xio+~e|m2?VP6 zu&&cWiAhAqiPL_D9J4Qc@8yyTNhN4FX~75=B1@X0t3(1>xb=a?A(o2 z6>(`WoTjE)K=tI>dRLXJ{tfj>E8Td2?eR}^-?`-btI~c+$grD;J$)`4&57>0TZa2+ zAM$&>mzZ2FI`Pb1;^Dg^zL)rhTc2w97qoWFSc}N$mrw=^)<-L1jNe}KYB(I@8?2Pl z`Lds{>gP-DRSdM-=P*Icv=zaA;HVVR>s!ZlN$!jJna3nT4#N|W3rJKXvM8RD{d^p8 zoM3AVnfd{LI;Um~Rmmn7M^Ec4$yXS*s+{Vxw$4wL<2Rm)%#Z3X{rY%r+LBg0+vGJy@}zEW`~;r)?CinTyO(}3x$wy!cC)>zPY#<9;JT#> zG2>#Pc@!RM{qdOkR6n5Ia90tdO}0u?W4FlY#aIi7qxJR25gVmg(KS#-+VL$`zC0o{ z@Yp9d*(1SmDXuO* z^XT^@Jg@SAUWsN*>s|_MWs9zny5~1Qepn~uRLvm*K3MX?l-y2kC))YwWhV*>>X;b{ z=B@IbKds{oLYgYE{%0?Y@A@X@3)jAxkr1}pfwq^ZK3M@e5z122l!s($`~ZiR<33rd^jP&W)?Z_Th{7B(aEU(Es|xpP%^9 zO=F+&7vBU>eYL`rjg?OAh}!t&mbey0J*VG%Wgsnod_uEo2ha1qJBEVu@{ z8K7!Wn)hFethEgd$ZNQEHqGTOEQnP0L9+G_aPSnMhrZtGuFUekH<5@Swiww163oT} zx^!heAC7*0IX6{qrI&F-aU{n=>B;e@oP+nTl$0e%V5aB~`#a_SYfb$MIU!>XkH}hm zxaiiF@cN${)d&0&eGw}2=v98<6`cGov9)0c*xYqUu8u~OL zW3Eug)4S|*R7F{QM%NRd8y~_?ms_ymjcT67eLc=&odh?xp8v}edf`KMJ%xRAm}QR6 z8#FMR5T5v6zlt&Y8GN|?eE&?DJ;v&I*I<(st`)9vTmo>vE$z44{d4*-F@{r4NC-@83g*d5;`KV+l4&2^dU(c!Y|B>s0*viTLS zZ_!^{CAZu*f6+O_K2Y-eFBX*`BIMOWb(*9Cmv1t;`V>3v>~?wsHEtw%eH$9x+K%ob^}@tWu(t@^@>;|?QWyD|5geN+9ZZDftx~Jag0JrX zVm|fpf!5d7+EQ2_1@QG~Z8c~iGWFkJyt6*dFYr^pe7ec|1?AC zRC9Bc3(3I@%TJ`Ew>hE$S#l*%p$Z)7*jb>9w$yx{^#zAO=D3l-+k*LkjL&_j*%k9lC^BLKIf0)s8b~-S zAo6L+R^ajLdYK8sBeh5wiNa5W-LE#nK|T_)UwA|u*u6?iH^_V*xt00;k$H%Q{ByH8 zKQh6XnOvPr)a?8sW;8{kjBa#vq}t5PAQyAdiC0R}Rs-LhC2n0TtnZdyn$ax6kFI`K zJSpKl`{8x!moHXOfjGQs?{gjFNMW)sK^cmuX*cW&nISJ3VF#f`N$o@mHaLt-5{Mn> zLI(hfNz(of>1}pt%?UXe9+nMt<4A|bl_hLC3=z4hU3{(Q%5v;}R((UPKk5Zk5#(9f z!|vm#em@!!?=P5o8L0`TJy@#3jy)g^Mr=9LJqvy?yond*9V=a+Ab{C-t3ZHPp0B+d z`H&jp8hrLTOV(au`hAi4HQ-pQB&xY}z((Kcs21v{Hf(^G){~)T9t1*~m-Z(spZE zpn}{tYB!sG>Kl(8w;71co0M7%Aiph9V8g!o9FJcL9(qHN`EUHj^*t5J5>PqxILo8# zTR>VbNI2JBP_i$)814SaUfi z$jii%lG1)=hQY8EI&%%L-C&AKy)$~oqO%v!+s`r#(asEDv$GV;<2JaSapi7V?xG*l z3+FVVd1~-aU=u*mKVLTMQ2Y5x>%9qn(R;QdI%rr`jd0B?BbEE}VOn4u z?%xN|Nq~(Eor@ksJnmO6Jv$26Rw$1J0&NC&wS-i%&>$}0!X*7-#k+k1= z8l6&D!OC?bbE$U69xN$tunzClv2rV33^W#%HQaD$MKfOi*j8ns7VnX)?5{OTl`s>D z3jcD&5Sj7aj+*_CVIAgx`LqZPd!iLWWhPZX=WEIl{E7RJUbYYmhdEGaRHW{|}B%*%YmMOoB=XsPVlYuRp9MzZWAl~Hx|3ZW)m z`<~763J!OW0|EdAQBWXnq5B|@w$@X#l>(0f#=C+}y-LZAv6j9sZ-VO7O_TV2 ztW>FUtM3$NuBW+j9ZPtncl3Utt;$<{m6<@f!M>y4WeRp@(6s2)QkU)l+xe3F3YYT^}_n^7U z!O)NqwjJfs8*#w^jv5J9mQQmOtD0y&pg1_pp7H>S10ye(Ev~V0axFV$Y{j4WN62tJqO4{K)O_>wkMT=N1mOUio@P4|M1igJsh!U|JrKv$_aM-;w}ws z6A_G5q}9Vz($oS%vlprCo=(p#0mBF#xzo4x+b>^{0dmHJEwS7lZ2t3i>px8p!>HCU z3|{f(ZAr;#@o%s4jyTCx+REc=*Ro7k=eYGkTG-?&m2#A}s)(-E7CmU?>|4T0oe{4p zO20I3LPt(_i0*!?rVXvJ^t}0DxsBf6|Lmd`rEXmpRg(zu%y8$TYIOsU(FE-(WPc-t zSh>Vj<}N}qUBmm4g0RUC7rQ?vz2boz8UR!RokMA7sb`v=l=2I|v%_}e!Mm%#PC5ND zlNS0=A0l%=eD_IJCH$|xd4nQrvrx^K)-=th?(sEPJmHmW`^pK#V-ImQ(Fk#R@Il@v7EQ?^vC8}-6R zHDg$DXU=jeFN2p;D+=cxtep9za*w;(sg z&78830Jp)f8@^UHz1&`&O*ZsPz2n(6c-LuDMv*d9dnVoEXRSp0Lag<1s5&;y$g(At zlwYAq3*~vB5cv>B=h!4La4}*wK}40k`X*^-gZq`qht4Hu($FUFJM|>O=*O+a)ho)* z5}7)94;iz{;euvYv1P6Emp4|ip8ob%UqYKAiR#?zwqK*QB5Vw3(^h;1Ryl5v=uE-c z8jopH5d)YQ@X$ZsYnaLW>`Wj)X5}HK4xa@r=vPMH6vyZ4C$Y`B4D1hip&tD*!#++s z`p@3cc8>WS!C+PJ*?#0ZW>{UdK|mV=GTDgSj;0LWW+n`hSMOt3V^I^4xyyT-P#*6S z4cnFrWC#Q4^s^|0HGS22oko^IRh5jjx@T{F?U1_j3Xe{de4I+HGNp&*l;xe`sTa!x zfX9>%@%qap1*W(nje6c}!^GxgHe?DdvV>j7hJ`OeYO9;I3?;3gsJi~Gpe-4w9Q8seLLFJ!dzjEb#*IwmdTMnAG^8k8i6c5BawY_vtX(sq>%r` zbNj2^5zGMR8+5ej_b0ShJ$W+FNd!GkG&cpy{yQ7fMR%U-wMBf?dV|@vGS|M_9TYy{ zwI7A#$DWuzUZbvT`a#CxJe~rS^i#35}=hg zr&P&@Tymy5`8yA(y4g-rN>2GKUmeW-qM$|ups;_>YZ;vJJ=~ENlr?f4=vIiUdEiD0TDg>r zU+D-X>aKUMYYxG%$~Tq_4;^1#V&%dyp!T_hFR1_&IC$h_~P!epfdfrb* z1C?*=y&$@!=A3lioXw%^wP4wh`lgux;WVZ#om_7=k=mMTK_S~AYwuW4f*Ya|vtgz7 zS3JGf5IW6phK$xBsPvLrmsEE;T?i0cBV;A2v?zuc@$auP$uf2)dgQAy+utRKyi=a= zt#_axD*H>N3WvsH>%UC5S3RncULWki4|^dn9-b;UxFKqCjuYf;vTi?QBeZ>q9RiDu z|w({nGlTNhqqyBBCoXj=e$5>z4+o0 z`j$@jF|-quoO2km&@*KR%7R5(E^1uovHB8W&s7NnN9hH&aM$?NZT71V=V6#``ainj zODMVvAGFr9FNUM@$BAM{2%=!`SB@p2fum_4BQ9`qw~!hP-lnec1|dP%THYX@p=4!m z?K6B;3)K9Ab*cZqtz0I9mE8|eqR7Nr&*;=02}?w&34|p?O17swFu5Ktud3Q3b>2Ph zsk|cw?_>5fGFYP%el>%%`Z@* zVjt)K6~bib0!kv4yZlt(MnQq76`&Bqk;Cs);ROVt3&pdpNm7-X0a0pGc)VgnBh_>N zyk;iHLD4tm^Gowdq)t5UH{$(7^#rnFEzSZkPbGMp~en|34LKbuxk$q>)QU)e~rVRw5Qkl+_sT8O#!)fz0T|S9r z9Xo|856Y<}UXd3%gKv}k0Z{-iAH-yZ=qGF7++?MvlhM5x`cme{Y)VFs^`uf0g1UAu z;#x%L>^Y{|yk=)MdJJ0$d98i^s1tRvtoOeBnPZy?EDo#3)~vhaQFX^%u349U+i;{V zsk((#s?km3a9TE5JS#}g){4t~IzHGme7JT0@$&-a4{~(9SA!0xET-;bEl?D{L2lSr z5IxA}trY1RLxAkJOd*~C@4UpeWsD!^Gfm$=M;)_5w186n_&ECma4cBrA;>wfa9NDU z_Ai^kPTR=Vqq-g4YI0I#9_PzS|PaHS3FDJ8vmdRPXT`#}xYx zhv{+uOmNUX4Q{HBX$dddCr?5Kz%)4t5o$_j9qboHdxx1x=>dv&6WHA68vpixK5oze z*DXxRasjK!zonN4`)jTzWUwMoqya?2uc7tmkkh@gb$BuYGFe9fQi1Okd8&Gjzq4(W znm9N4Z1FA)A(SuhPQ#-;DG;?kv1YN)Ei#t48&_kRswxmAbOhZyakeqXDqYv(WT3T? z29WJZ>{!5~*?vy&SBTN88sb_8F(EK7aKX$dr{`Aw46G*_j%K*^7M%s$HoCn|*5WqE z*2?s)EeH!>X&&GgtVk)+`RCuzko!2kQsVJ&CPZyO-(gcmb>QN|g#N7oW@S!)u%7eu z@k@4&^QN$$($zod?8mB;&^!k6QiOMmg{4qgBSUpvpYZN4bT(ukH*`yvYKh{Il6uCR zQD3E9deB}3;|-PG0(NO7r*nP{-TlnymXd%F%(u5+<(pPfbca>RSEBzZp=6XL(jSQQ zDl0s3Pb87&^ex0p1K8%A7`pY$S5Mn;W=3{LzY=Wnr?R+zx3hBMO~GJUKfV2|fQrbF z0h6*(ZUJ$u`y~B{L=#e}3o(t-9h7S%T^Z7i$YIa`x4&LkVid?DfrJQ(jNSBl&I~+c zVj4_h_)(*aZ~om%==-3J{MfDiTaSE1#pe_-C)b4G^raujsEZ(kO|R`cqU&i!s*T2G zQ0Pyi57}CwXHBkvD{OWB0TKrss1R0n372#n_rnScsT&3#$=pDHSjQ%)Y`a*54U_Ud z*9m=O(2Fp@uZ}p3+l@*p!%0|?P0OKDPIRyPIOAjo&GtH-2)r@$uQCZn3q*}KM>Uyf zX_};8DNcCzj$b}*Dvp4lQ&YBG|2WH>xhK&G75jC!oAnXh)O>Z@80nKRS5*V)AZQSP z8^Pz$(E8D1oPOMB*QXbh9L+j|)|SC}7Vzr-G{@!d(~~>yLyhYxQM!COLKZ&2OAM{A z>_T9R%*7ozV9lw;RPu71?Hj)t4J2Mou*p$u9311TH`byCvc1RCZGrm%`BWoQ=YnYYVZ4)EoRCYA=`<=%CH?$U$ zfE=x<}N|w>jEwj{tq}IHsZ! z02#J}=iZMCKUJ}v>rp!{n!DN?+d1j+d95jfV#1}8eKMkWH@Id9DtkmB0&#icW7$%| zqexYvvic&fBR?OXfb+q&Hd|JW=4Rj%4R2nzto?arD?oW0H%#^Y0$|RBt~x0G4v~;) z7NhJgxVTfFy)reYg+9Cm2a#ra$sj?Lc7?jkU zyfsRVO^?_(2{CFio-sZX?G$zp?fc$ZKs44^S9elaQUSGoDT9r7I@$)Er+$$%I&aR9VK5zF8or+GfU@Rz#;z-QhidHz5V8Z)jGCBXP+#lFP6_eQH9rp z9+7HAKFGs%pEsS2DdSKGQ*9ZBdc({xiI?LCRBF@k0hKTBZ(4crts)IyhN^Uya&wE< z78b@ft1QX|=9HN{&9sHW&!eTK{!A2kU57jdX4i^3A|-dz-HiOvqX*m`{_d(0Xc$ALgHvIg{hH9P7vtrGW$-KgR2QSLzWD znsYAZZgqUBqRi%my>^*FmZ&)St^v;~2>McP+f^Dr;Ud2~i){c&NncVf-I7 z|Kq1Dt@ektwg47emVJnR`B!a!&*3N>lp6QLO_9wh{jXR&D~fvDFdm;otXrT`cL7?@ zsS;aLt3zNp>tJ7>wwb~V^raK{GsNUV&KMw#t>qGns5tl>>} zBTDGwRgE+53d=;u4`V69ithAmz92Zi7t*^$y4yf(n^orh&oBE0DGVQzFg7f__65N) zpk+w`HehZW7?L=BD@1*N)d}^(KX8+kcxRGv$l!66*mS1x6Gg8W->!k=Y2W7cDM3rG z=YzR(mcZ^C@hNxAtmIgu-r{+;mAd-S&cDbtE3_RsxoT{{GoE6k#IB%u`eWT2*au5Z za-bZ{7fkL1OjwFxSxe^UVd zO!me+bGCHfJ1e__HVb_#WoM|C8J<9JU(J{?r$LiQQM!;Y5J6SHDQhBow`)TCd03y| zklbIuL8wk*oV8+eVA+CvRV3ZMbq%d_Nh|v#cH==iQB2iaW*uLQm-8jx;D;Q!oLiV> zlG4ofI;!;%u(uLiT!Ny&gu9rCUTa{m1>uy2Pvea*GmMCWsU$+vze{@T0J4vtiY#~f zGeW=cTEHtKjulnhYD{Z&^mn@YT$}1K1l>jiDEXbaYNb^{L%mHkz*%D;_=`*0tCIr6 z;r4;E;uvSv`e$UngP!%XdcCs;MW$rpU4@Cgt(LQS&0{wvs18JgnLD#-C-wAM(<45d zxF8m<-gn)#&()1!;`CPP;x3!CT!ZNaW(4h8^FV+#Wl^g zkS+_&w)>e9jc2b#lN0?vqzhAtTU}-~xM-0}$B+Bp?*AqPx1G~dy`pXIM(Eh4e@r$O+8o=*CMQQ7)Suv6wmQ@S_^qI;XhubvUbH(sGS>Op`#=$ zI9MftBtEADJQR`&HP{uM=_m_mz!A(8Dou5b%9_SCSfu#F}Sh;T?#Ra_iEJ zW3~`i2F`l^-y5gi_J5-5zoUIO3O&5&9xp zN;+v=W`<=CsXDAr@h-^3dke^-bn9{}%o$@nn3+=M_Bl2p;a&StKSNx9spt+DIg@0R z9{kM2mUs9x_8T%gUclYMOP*#eO8`{T>0guoltP`5ifPQ$sP`6rluYQ;ZKkz%rY5U? zj^I8kB3Eg)m33BU6RIw`B^E7F&fA_fn%Z=SFaPOfck^CtX?3fN>yh^ZWAr>LCB)L5^GZgnG^0-@ z8k-wyB42)aVFDk>?A_^&)^`m%myY&0StD21{{! zTJ@D)*VFzx!T@U>0**G>)hlgLYe1K1?52uWyFpqKDe;*L3DD$BNF!Z4j`x5Ds8k?^ z7FlxLWeQ~J@-oZ*iHEftWT%3|3H+u7zrNL|!-3W4oth}^{MZV)Cv-t|CT`Jxzudnc z2p}!Wxtt-6hgwOA(W37`$9ARoIMJ>}54G|JnUs>|xaOW>S1BIKbiFj_vTga%xtg&S z_8(^h%ZcQqY8?dj5<)IT&$ct?m4_&QF7UOWP4XqiRAjS79eTaMdFC^~K%j3b(tl>5q z(YdnlWReh=G2u0bBc^Prp%)m73ERcRp~IvmNx>I3vSno{iYll(_9_FE zP1%2N#Uc{%E>=;2!@oWolX~R#x3g2Z>$=}mdbnpO>XvA~kR*~#MhyOQ9JS+bS{lz* zSYnA5 z&H)yPOCHlm9cXrnc6exUvYsXLWZ$;+>O;o7<=yc5iq@Bn~omY?~z@?op zm=9dfh2`Sy{2AmjEX-rFp^Vl7&g$?j_C4Qrsr8$n7?RtlRekfndJ|K>@*cm!A$SXLbHOb|d1kz4O2V1{y5%)H0W48K(ZT;r= z$SkW~x9^CGfS8CQ>q_?oU-D$rWD$A5`Kq_Y1+g>NRRlXAE)d~2n=ou2$WT2}m!pi+ zS$XraQmk->QUb>8V?A#4oonXWXWA6W6^vVmm|l& zPDi^i012Snf}4lc_E9$~GnvF$InNAos?DA#KfT&=ike2SGSpP77=Hf+>~uV-(3!CF zT%ZL88_7&^SHE}Qmogxkt>OI@+dvy#qtI_1c2*Czq4#NHEkK4&_wG|=+}R^4;X%Y@ zNGjhXZDH>SKES`LXxpr?+y8F#IQAenYL~NC7rZ7M8dF@^ zN9E!2=QSw+&`j;K#;Gizg!5~zPSd+|O2%+l;E+pY**BJ5z#-6)@9nRR+3O!StO|?Yk;R%jburv+uj2zop0Qf zrZPW!#;T}*OYrC;9*sqGvBv|4;ctxy#01 z$^zkO%kq;4$b2|@dKONcp;Ta-x;r+LeJq?L#Sr%wAj4$$l_YGopKbPi=tShqaHrG8 z%=w#Y-aU=z^hZxVt{6*kac9v!+CD2lP#Ck_y5$ZFPHCKIf>u;(ZEYWgf&PNg33^~6 z8pg`>{o@I}cl`3b?+%`*IZ&jlV*jN6S50DqFxAghovCp?E5kb+V63&J zG_Wb6~T0OZTp>a1Dy##i%{l@q(PeAz7p*(5;{r&20PZi zebx-7+>X@Cxrk7HowxK`&qQJ02+<7vUd|Cs= zMnBOV4OgBNGfNzNvF!M@Vn==>zo^2eHXV3{XU8IzUmu6DY;+*N&d}qoddtce+2kqI zV!V^X{n}4x+Q+HkwUpoezELx^&8T z#zt$R`m&Bk2?$;hS&2QK;DH8wf^7^3^8k})u4wKu7?=M9mcvp#^VPTA6zuXTCmSit z=*iuB6dM@&{s7U3xR0sCi^ag(R^A?h0L`vN+6o{<_hQC>Cc76c;GP2O@iWaz4H_B$W#tlE%yi15>VoJGYA8m>MPW#O5B%6oZRJRUGy-+4px9Y7o za8bLi?0pp}O`Tp<l27dbUfRnB*eaR`NZny_F>6pMH000|tk-sF%%}GD9x2+r_1xc35PR`HBJPpbqPFvZXTeqb%NU4b#S)OpO$h=YrY3?G2f>nJ&{-{u&m{6xv*)+Pm(UVoYDF$Qk zV1&8Q$)H8)!M)EvVrD%K6hN218c1e&d}nXb|3wZI;?+?gkwnr7m*Uo#c4TXzW+iOC2_&)V!$ ze%WckgQ4*8y{nthw!H4res&Rl?M*wVL(hPO8s1Yqg^_O2j5-baOzq;G)6kQL%TtFB z#R#FaJCp0V7M4gmHYQN-w(r=#2n4LJqHtlk6hmc~=ty-jTUu(0MZQ=O8+;}cJC0A1 zpp~yfm$;}KqZ$>%oFQWixcCvTz*M*2vd6tuK_^Y8xiNiLtepXSg+ zAa~vS7xgxbruAIFKn`*p3}j{~g)N*??ENU=F>@Y&*Ok}L#mvyrr4vX&uj<8@maMHZ z_SS78Ffa39mP^qbzHKt;`5xZ$S$&9D&lGa3d5SwWt{k6+vJ ztU$L~(1B%3?h%jmyN+a@GeL}-bp%;RMc(8cZ>gdFucXNjp%Dta>M9Ok-<@YhK)Ct( z+PV*baZ>`Yqw0EQQX<1qC-+lDwWGyU0Y}08nJTa0`LV^e+uS>_SmNtglLEopB7>p& zfn8jaFihPHb)*l0Fy>*83w93Qfk?AP*FkM_SI=l=yNCS zE!~dFdb&k+Ff3S!)sOSTuw_k<(U2ZVlIQO#({{dvAZQKIfJr0pNB8ft*)*J#1h;$z zNuR`Lh)qlED!Ggx!l*{H-m&r@2ND0-8%+R6`Bh8WXcaj&9uP`U7oNNt&o?%)v~e+% zmAExL%H(Y3|0NX(9&EwPIspDeG{Sc}%55)p|gx2^f-q zpBpAU7f{7fgG_!X``duM%2<-&vkp>ruV8B8}Tt zyq)S+jC!?k0O^)xF1XrY2t=rOI*r`-?8P z*PzhlyN;x9d{7>?qk!519OiOsU4c>$D0-9^pv1i6kKx?N=&ihy8}muVMwQ|9scNtC zQvH$@z6BLNfic%nyApKI_$<1;3`DfQ}#1Nb^%#SSjZk~9!bw9*3jD0B9&qU z9Kstziu$GyVRt~2uSSP5QpP&Lw3)hM&WL}Dvsxp*?*CPUylOp$1d=AGewBu@0ol#c zx7i60wD*RQ>7>)Z^+s=$5U*H*CR|%Cl@WCGG&9+Kvr_7dr7SrBVk^nzssgNRa%}I) zkn=}kkKdOr9K70tOfcLjr(7SbS)oV2#vPYSUfF{7XEGCbfPwZ#4sgrNNlst>xT6>i zk4SW9xxnDUYBufU<7fs~dhbvQCiEv3W!BMLh2_ioUPRQWJNx2nZNLxT^Z*!LqcYtX zPFztkKBuzEi%U~`cR(du5t6TROW3cM!=1oBcy-rI}4t3M3zu>70Rn=N&UT z(42jACC|;$9h)}n@3!r_115p4>{>kY8mp0DwFH6)w_N7@x&8Aq=c=}sHT?LB9l0um#r_shjid0bcZx@q?fFb-vS>#xy%1WR6 z^P1T&31$fJz3S6@`llasCr#Tk`FK1pH+S%nciu9x6M#BvL`g`*VgE+u&c=)Yd$IIB{>l`Wa!5!3zf@KO)c9YgEJ-96RXe|YARmffp~nLXEg9z6 zFA`gyztg#3a0)orC|v5cyY+F|3}o=sKC>2J0^lRai*0tsNNtrPP=n**Hby%AzK5jm+(Dy`W;TscaPm+*V*@OD3HFXmD zv=iO!x7@ht`QXYwR&=Gw3_&bnpJv}4^LNj}&Jzp zpy1}%82yqr6p-uw2)Vp5t8)jn`upRRS`NXWF&8&zHCK9gVDMm8WkdK%7i;&(eoWbi z=S|N73Rds$+%LGB#67MHQjRR7 zF4FiUYHy)wo5nYa?V}>~tTox6DVY0khKl)j9-lvfc99Qb>$C;V;O;cYTjI*bpo}dM^;yVGK>y}RRUV9t!oB|Vs=*(Tcv&p zoI$&f>3RX@Sr!e1>s8%{Fa1HqcRGBRa|E5fLPHEy-iE^eo5C*mu8& zHOs@-|39ecr`Q`LVb$G@!t#~SOlC9)Fp~;RZ#J4;*3`7KJ>#J&|Dz7`@eWE->|_Yr zM3=Z@Mt74~8sw1vnXyOY-?g>s(FHC;ci4L?>{)*nJhL2^adYf zzY*)S!U!TR zhPN4w&WzN^hPo)kZ<#j5^}pv?fi7e_{<4m~el8vg*k-{)=fAQvaAlE4F23@dFf#q* ze7!8MUJ=#5cdbNtR?rai2RD#Bw%T4<1(nIhkde|W&Xu$|LsQ{hHHv-ox>FMffwjse zSLs3nmZhTqKK{d#lZ4v6h=a+a_ogr65Z18VP5#=G94(T;m(u$FwHE9=h2Eu%QDDov zq^)RmQ4I9WoOx-aj0GyWk@x0s9tZyMi>}{w>f0g{N2H@>tMrdHY1PDJcTJIS+I2Hm zbd3>q8hKR{GKUK;%WGMEa_SfM;x06)?(v$NG$L<>=)B%w4BLg*e$-QW0f^2V2bP+d{5&JO`x2=u z_un#4*)Dq;VVQW{md+7edb#QSm1n7F!{RN)urgrb{Y8LgsdBWpMWH5Qw6$xauy!(h zRBnImm_*f;zTvz279l_aWlDpf3uL`=TY3!MPXgMaHFs90m$0me+5QAO zN!$oC8c9n=0B_f7;n7}vHEf5G-KLWPP$Uw4ZW8Y)52Q68!7F}(9Emy1k9|fQCUvOj zPYRrZuz7M_Fl*KXwUcCbjd~}K&7JqZ&${R72Zlbd9qN`@|5p9XmtW8CA#B>J zG~~DkvDEGbs|{vIa!|>a^yq8;G;KauC~_>-1$uy^#8{8MF*e^*5K^t@RF45RrlqYO zMg5nu8~%A(l6O>R_*Q5AmbKUnT*RI6X@L<&FW_AS@eGSbLF%vE5xMoQ#P#%}7K4lJ09b zs6}=k-*JF}iMqu-#4!tHsl+P#5ANLy8eI0Nwfz(_XgPMJ#7--#!I<+uK9>$*@HRvp z7gSsyRE|=(#T^2t*gU3AN$}Y~kR5$VSK_l4?Xl_2)aSzc=q9P^x)Xa-J6`T6(oS}n zL;y9amvcKFP>NQczuN&@3&<(gccQuI?@0q2Cw2#(4}GpqKFgi)n$~fID=T(XY?gj| zF%%BMLn>2A_&pUnj6_uY9)E5U=Pxg$2gi+`>0sFE7;u(PU~JtFYXgyNKstMLofSk? zJTO{LD&j6sz}WHLJ)T`<^h@FI-*SjAtRgk41)AJ56~M!UwlV8>6t^`%iSeks>ZL23 zdWy`}GuRO>Ba()Tv$`ToDw+y6APe7JPPaN1(JNGMIJK+VK7Mf@S6Ggr$}ysc)t=8t zj_VJR$zD{Ji}6gOEhBXW@7^U>W!&R`La9=L99ebO^vx73*RjQ!_^`sRDU#;NVUL?X zvUR4rs&IJbXd=ru$|ePrH%x6!c%*j|LQg|j8&PFsQ*ou2F|pH@ZXoLH;i3c zT>2(r=)mYHJKht#q6s`#h5AW6pGE#n0&f9>?@o5Je6PILDgZJ8JMOe8s;sfaXcPjJ zp_~z&63yQqu}9H#hJhm(_#GnEuaX}>5H1sR>1X>bu>V;tubt73lMB0Wx9;NuL%1OV z3^fZlE11@{59Qb&Uf{oIs_(cCLwZ(Jar@lr1qz$&`VP|^8-zF64ZN8aUM}{JFQ-Ov zm|VP^L-NYow+4dZVU{oCtt8#SGt;F>c~%W*`eCR-qHpt?v?O}={%%71wr=0vLUpDJ z%C#A$vwcDv#V3D-_#|a8`{X`Pp*7-X-flg`QD!IIU*!H$8)eSN1=d+-rPJn;Asra+ zZeoX~WrM<7Le9fOy7Sg%)4J|X57?}#SU9Z}yWrdvQ$5LpT+p}rS{_yYv>xVe60ymo zZM8e~f`nZXITR5zh~jVs1Ky(iTfyV<{^BCPYn`^KmxDdY#b|(X;ds-C&84r(!=s?G zQ}k|q;?tzo?mV?wS+^I!76r>c5Yf0Ot+a=!q zc|bFq4DvDsbMU*3j{HD3`c=#aB!l`AY&B%KL^ViuOwVhB7JN9<(~QnBSXP&o*~eTecPVB~;L}~X_0Z$VbFZrntP1j-)mOT2 zJyUTv9YN|yH>A@$e8tkUNDaY7x}?e6qJ?m!PYRAfMq(xfnsOJ43z3VqLcHgKmsD4v zp3^(;ltOtRxBPov9We>JRupZjqdXR<84&9~<3VPTC(jHKrZS0q>5pSJ*H-p*)>6Ys zt*?%VbAKe9c2t7!@O+A64WsGFQBx;((~Wxabisa)=Jk(~dg-x%DDs942JC%-H*@38 z$$v$;)xb7w0{18FQD`!7$g5pKS8aOS)lYxinPakCR9cwe%XxP-3`|VO^vky zjOSV?^2W(z`w6dy*jnYHtC)>^8hvO$@--uYs9RLPPiBX+%Q3vSQU=G=B74iB^FM8L z6TJ4ZfBJtua~ho%G~W-wk)I-b_lgpl1&;5$%sa$i;9(@Bv9|L*c`g}F&aT2^_kH;I z!0Gq%nMWtvoECDF=kF=E?+TO4_+w;KGBTYie5b%r=_1oZuFb&^+nZ<^&9lQP)^#)> zoU97xc3WN*Ej*dyUyS%oi2)(Kt%@v-ROqzrOE)e4N+$lT1@>D(Q?c~}`A@UoIs#Mf zIekhy!7}`Q9mo&ogk+*><YbH9QF80&HREuI7?27>xGuw^r zXvh4PhxKu@?OaQ%C*;OyPJ&AJr_V2@%8O68t|QCmvSg_|+!H96`NfJw`5^O5!8R?8 z9tg82K2F;PPJI0%TR+kMINRTXuC8U`{_kP!@h`OAfc2a*I)_%TXMVgcADSF8iC;9R zOv(hJ2g86*h;AhQB|K{L?LX(MXv#X8PQkBHOT=M*NnraHMA#$LK%dM(#LxVifTpn| zrI%{fq~i`FN3ao0@|*20amxN@J=LJ&yo!|rdhu^t{$eHy#@K;+}oVgaR@1E+(QO^>2U4~O>6Bl{;7I7-Vj6r@v}}l z2^rbOis8?gcdOPd#@NA?9GJA6>Hv?Cgzge&*JuHgj`^h3o_$RpDt&1^01WS{IVCXJq^2t|(D$V$rqCm|?9p%n5<6CE=kTEG3-X(%PA>@Xb z72h?A4pGhDD&-q0YLH^4y@?tYi9rK_mVOdXQubjnqa4&j{9TIZ(|AL9@pH}&8hE#NS+?z|q} z^*Sjxv)37&S(b}5&!>7jVxji_muQZUld>eWz66ZAYRqg;fnsC>QfdaXS{dQK1oP{M zLiFE);VCuk`dngtCQdyy2D(umm$*pvf6CCSHA)7Qkyx*0qjxa}E4tyi3Y;f?>H-wT zCFr!rhI{FOw^B#2t3=~xIkJB9Cz+AtawO_+^RF;n{5KK9$7ysn^802@n>lE$^~eP@ z=2Ky*@PmuM6W;MwEb7XEso{q85Zj??MB3|P2Uq&14I9h;F4moOuLbz+Y*bo&l<~Nd zXO8X^eZRxa9H9?=sb55+p~JxlZtSP7;EZR`Lalr%V;r65W;!=(H$0qa@Eq3GTAJyS*tzFY zuzfd+@T@&c-o?Y+PmfV|b6viUQu#VyJw>Kr>-62Au^pF{?lqRq1Xow?@TstHMd{V= z_b?)@i{y+H@`{QidijizlL-)*(?eWR&#A$Blgx-qxbmZ)n}N=tvBlR}%hN4sl##wS z(mDQLVCHA|&I9?{y>CzgBG%NXXYG(d)-+}-Xpcp00SQZ79Ij@wyWwW;j+7XVQ`S4K zQ3&I)?bQME=g)%yo%B{5^F;&QaqXgKF;v$pbCjd_q@&Q6(?kwdcpji%MPm7t;Mp6L zo6~mfw*2U<${sD;dC`p5+?xUL&#|ChdUI8E8U_8uF%7sT+cNQJd$Nq?CJ&0}DpT?M4E{j?1DbepT z4+nec$A38)AqENfz4hR|UFeehqoVXaBtnjW#O_!0=glX0vx zGlZTz8~7khH4XW-oB_p=6AwkyK>CLL00PeLa_ju$>gZ+A>xitd#EMhM8GX92c` zv^Y|Fjo7(lbop#DiCA+P_9-BF|0!xi^&O4A9cywA0(UK85~U@`%IG2OdUG{rf}F%H zJ7|mjt%&$wGF~NGz*Nu&Ml*{*T|p*l!^>8PUV2TcCbnxnEv^Ap9>&en>d6P+#lQI) z1pWWzS)!^culb_Ry#Z0>hPb(e zN|{gsW80D@6yr7N5QEAmhEV0RFokot?6x3&evVg1{z!Am8f(#ulr`5<@qwG zH*ZCEm$t&NonAwSHxw=iXhUC8d#v1LU`}^muCj_Y6}L~~mR8tbu=Y*T2=Q6C$u~}l z^=G8=&s_TC^0^i$gj{4qe`#TG!8fk&SF!^HL@S_mD%)!Pyx^Uq&_GYHj`ox)ACmj* z<3+&6)&td}ooNfqLD*H$q_fLc^tM@9pNK$`sLx+X?z~mR489L(eZRaK8_!!9s0W7f3qrJ~nd*1D570QmW zS1c(xD#2z5g(v9CWA|y%OtWHoJ#^r*q<|KhpQud4S)MQ&i^&sag4lYZN?wK}hR63< z$ldY3_g6=T#JNU%7x)zs(ULXS*>#-Y?t8ud!Pn9k{3BSWeazWh620%yToS36Tr9Vl z6|x3Fzw|x)xj0OeiW0hGI$Du}%RlfeW<#)_pcJwQvcQtA<8*Dv{=J31d}{E7vQb{A za0+>v5+&Rv8g7+k2yte3$<^9GRFK`Bqd*D0k|EPRK*R>`rMV2<)~+q7E?v@sDuRMz z(QX%KQOBU?<=z?I46b>9Fswt@+cjxS!ZRJD3|5aN$X%oPO~Agj1^W}XTlhLTb(gb}>^Khi*VpfL z$!~o`c|n#vu#;lO+gK4&6Hg6zV^d-(TfG|WC@s1OT3uEU!6i6kNSMr~L6e6&QBSJytr{UCH zi`tZItL*on0pPuv${*x#N=atFCnrBxIx1IknLZPr;^P{DfmwM4)EQhXvB!6(!@rk)!)QFo*o?Db(YWJUK_giXKLV^DTai?&&P!lBWk5o; z%5?-?Ejkb_K<5p=KT|OfW5K@|R{7O1Ku56Wgqc9_C8w2W+jCE|ZePn5loGH7(AEP2 z@up0E_=`keY(So~6S`^0t;hv71Wis%C9Q6CgVeL+N!*^(#|R)fFK;g zSPPv?i^m8*8|!2gdiMM&zkR-a#}f!}QF!U@E-L?q1zSqW^pAdnYcZvxQ2 z?kigP?p>(HR$CAwoe-vpUd3mS#JdDZ8I5l7yUv&i037?@tB_QR#{6JF9$EB_`J#Nl z!+ujYFDU+M>Bpj+0Bd-G?Kbpfr|@9Tl&`wXONb%^m_3BEf6C{X30!3EwcgCzYQI)i zruag6O-Zf@vDlNVog25MMBGqjq9TfN-wY`l)GY(-{!qF#0gp5*BN+Y~DL9Y{TTClF zz;iKvuSp4wWlGJcdCs1n-i)V)ymjEj!}y-Ilnh$&+DymwJ&Ct)_+F8z-urqEDgOA=$ZA`(4o#!$QnCi<2yeUx^7)>|fr`vR;r>q^_ zOHU(*D9Hs~xU*;`eT0+084TfxFP&yI1qab!F+%;NVGOun*P z0_6OI=UJ9UoF$DIz3zAO1@;?1R$;7oGHbyVrdyI608DYwu3xoc=Gwv?V)-Sv`OOtA zBy6VV{}9^pER@w$heUWRA>s+nQaOmeF#Z!s5^sVEY8=kJzE|FAPYG=yRn{VD`S_#; z2i7_#vh#~vOwLhm&r5#vBQ1rd+=H>+yg9^_K7S%G!grg_q=(*ao{j)Uo(?zg)H!3| zO^ciPFLOP6p2SJ$rYyIj)`Ng;=;Y7tV-Q0Ch`caoNnq*M2qf=YPpKf{w|o(yV851T zls_I^z!CI_mws6A#ux4735L~mr4)ADq|t9GUWSx}o>3zflX&F3q_|;f36k?#Z<(Wk z1+?NkiMTi=eGk6e1?&!8B6$UKWSmY=YsK&nH8)Qwzgf9%(j5e&Mjdz??cDO}PDF#8CcHvz-2;LY2v5 z>dWK(shnII(d8kXfss%V7Yb~R3ZhpFkf&)+Fb|t>>~b@mg~&FAWf9EkGUEP9Nai(( ziqhwSJijGxF6S?*5g|Ru%GgtROdY;c+Pb&;LYn|_%fbjD1;nn}5QgeZYj2F*(#6y> zZuAe{DU~75jF;gog@=L`7PbHsatfi)kPk=&8)%)M$xQyL0Gx=ou&HVv^w-pW?9&rL zgJ;jJ6ZaK9!!|e%Sp@eIrKB@d29^kpgqZfZAhfoRIqcjnJAzbwnIhIJ%947;z;Iu~ zn``S)q(3;qdcL}Rdnw;)R+%mkX#G0~j%0joA*W)H{%+j4-9z3p#<8dF!dT5y?rlr3g$%c~gvv{?)#7?YT|ZX{OV5*j>=(R#&)M%?sQ!^Z_+h z41%biV_L|_jqELmHiE>hIYFoXmJ(fQD+?hDGXcD*bA(a5>V@pMd$Bzw_~1YkxrX}< zA40;`rJ>f7-b1(^!*HkzmIL^ zzmjTZ6y2{WEE+wM3~6rYbtBCe2yd+R`)BjZ*Cqj)As!}>l4a}`EE`Eu_?vYeKcbjn zKIE8bl4tP5%sF|-0zwJ>^6C9w*)AI1pEt|bleuzF(r;;f>9is<>BvX91uZE%D~?uk zuc-W4{%s8A!)||1UhQ4(0J6A8G>La*0kr{ZPyHB53##ps*|Y|K_T0ZiY+^DVR4_#F z5GthKK&|SaA@yH=?k(OXtp>3Y`KwgKm9K|;(p71!y z%7;kbPU55VKf6cHe3&4jDK@da`v51v?*c`V*>#nA$UNZg76C zzU7Qzg4xiS1DFE$uT%L;>Une!Pd}iQ$4to^#ZC=Mee|b5v7kG4FJ$!7@#e4d|9p8^I14Nj>h%0N)jP$t*=1c!fllONz>pwc8bl0gV; z69QTf!<<&~mm)<0=ATZ6Jl#c&LE6pYH zZxms)kDAx8v%@W(Y%cr@>iTce%qGOZM{_18|D-~YCQ54m>I&_QHE1WdY2KB6qA25t zi4#2{vH!`#7_T{O_@xEcyx0njWd)P7m#5roD0x9})LHV$^U{5YD}UXT`#hESr3SYJoBdw^%Xus!&~0|%x?P^ud>$aIw>Sk@0U zW7{%i{eTvWSuqaD$+vkx_AdO_uQuQ#>rCgDg4u3MnUmbL1>B`U&a@+ynED$Cw&TRv zMwTg*xzh9Yk5PaJ@_D4wjVxk}Wjj#*aI@D54o^ql*N!)Nzn3X|R7LN484HFz4|wI7 znh~zATSjhnoKU+`3_yL^)e(kp4pn)h)Rwh@On}pZwpHzkeS(YJ@NfHWhnRq6)(;TE_=^OG7^@UMdYLybLVbtU8u;bUzX`E4Cw+BVY`5M)Xc#p44XSg#4Ig zS4B0D*}w&Er2xE;PZ_`rFt39})&)(S*k#GK4Iyxv>~}Ld?MWE2baVYNC+qG>-L@*- z`l+LNT)9!n%5L?&)mFFyiQMiK6;wS2ciu`a)>Hw48Uq|kJj5?J`0+Goa(zzCbq2Jai}b5Bgyy}xf~{FowS0&#m5EA^SDMn zkz(xSg=b`Xn+s;{J*=-7AS}Xchtdl_4p2_7E3RF63X1?Y!lMTAgEkh3VM)u;dU~UJ z$rfxw3%PdQe14{V#z2;qIQst)F@`gV6g5!T(_Nbo98$dcdR~oEVasE_Q1$4wqOeCx z(Q#TYV#zF*6chA;2Z7O+Io z7fe8kUtcS?&ZZ{2+VN>S*NiCov#T^R`!mcd+6b2 z)UVmGve;o~kFVv4tNc~EuD0Q{j04d2pv~kBK4f|=(xhXnMEg4sNEj4dHp`syGilV7 z;Cd53q$MB3E@iV8-Sit$uw}(E?Y-G8lICm6*aGp zh)M%BnGuF(b_}|xo}lC4sTfHn-9?&UGr?KUNcII^q@O}uc_>o$bogm>LNhXn4)U}< z(vtj@rHtl5#s)(BCR)ns8Jzrmb_Sa}WZ!qC!_;ADD8cCHC#xYG80!fnVxw|UPU>+0 z({ji=_2*FZ6|b6qK0Mg_F)W%9hsSHxzmmzx1);lsG6|va!xq)6?pABPDb~?)+%~Yo{7Od@)v)dDX2AW=l7GUu-}D`&C}GjZ;WZqt{@&sH_trV2f0t%T zk(;m!h32!Dwa+_^IDI~p{3maF?EWhGkCiicKzI~)M4d{}F0l44jv}+rbIT-!qPgSx{on(z zA$Udr+j=B8?7w6`A|{prXUD3I-L537&uV~RpK=j>Aqu6PI~w~-2c^z`FXJQ_<@ z2eq~xv!&Bbi+-rjfX0fznw8*f%H6`pY3Kv~C~z*CcHAjpyA@;e04*Hy2<$H@uZj2W z3BXzptzpP<9+VgZ8<_@ho-bLbL5qZTWx@km-fzH#3wazDa(Yb0i<#7pUoc=nAqtC) zsmM>$l?OiZqn)@l^IB-RnWTxalQ{N|0OLrnIl{a+P~K)po>$bwmL#CYE8nj@ebus- z#OCDx31t6Ip|F@EGhSiVg7L!OlY3S$gdMh6ANKU%cuF)=Q>IhD=II-YtWA=`Of=iF zV%mgbiVvsGLwAvQ6&f+7O)S{A>%))KpzjYBVveRNTlUYBcGl8IIP^|g>Ma8tX^I8y zwgy%-XV&6^nW82g6VCXPGYa{Q&)#(Y5uvzG4tQ*$w#GI~f{M(mz;9>NGP&@rSlIaC zh*MtogodrCSmnv}`Q*M{n&tfs7Hztn;MTe25U?X@G^Zt5635TU%;P*~)l1WYLhJ09 zlY9pl)sS1?4F{pHKCwV80JD4eIk3%S2O5hmBaU(f(`2OoD+l=pw~RB*`-pPBmRlg; z6}QL_2S)4P_U#Q)9BmovEx}pdU5r2afw$G~mP}IZ1DzlNL%hZe>$Xp@lO*R&!NeIx zvm)N}rK74Kmv=T$>g6lO)Dy2YpGh{Akmij)zQ_FIM-0&JC)Ji7d3^0=o+ZeCWE3HEfB-(Veb ztUs5C#x8!nGxZqD95P6G)|mpp_n^6W{&LCq#ag?l( zyJEeeN*WbYS-Jr^hs3OTx&aIbzTAeiBF)5=u-Yai> zA0m(|Vm6r;W)TgGL~NK93?0jEr>50YLv1|?{~w4C8k+Ge{v9qCT7ozjl>rNBWBt9d zdo=PTIIK{ehCk|1ta4M|{Ax=~xqi1AP-m{FmbO0NZuxZa*4(iDvM@u_>lbgmUsOZ& z?kn3@00TX7;Ffgo!x0U>QZA5QJrv7y^$ZS-Y@UC8)n+lUrx)YrLqD`QHt&RU@Eq{n zft?z1oR=)jYsBJt3Ej?|KaR6?r(VSyr&IC+DLuu03l-BtJ5EABn(qX*7YdRCx>rj# zd~N$NAkB%lQJaE|FW>LJqNG~ijgc%D73WgaU$VrG_S?kS`cT}`{5k3p%~9OaA(mit z#!0m=VkF48J0Vms^e-L$GqJXqx0EJDK9Jz{LB8I1PwGDLY4W74Ty+FrQqo+xXk_hE z`|4?udE=*YD0Yu_Uq1q-ZIkGpDlVBmT2bpfpBefj zeO+-&bigC#dUNxs$5m>_BgKOjM2S~@xw*DWPHH(gRca_FLQjPIR%Q;MZ*LRcENh`j zHJD#=`M&TBY?~h~DAKVEmwGw<5bj7 zFKygq6=Kl&-hc6ZGdxRn-n?1by{Ri@w~Gg$(K_>G8AF+t)AAL4wRTP3JYI7jH2jep zPQ6BZ6r>wpX`|{;W;OJf{xsGmK~>2^mk;M^@MdXzdG>ffycqSHvE;&!!Qf+-qQlq<%qQ6*kK33-}wC^T8j;C zGd;HwHh0uRTXqV+=rfxxlS;EG!^VuSD5^Dh_0Qs#OX*o|I)_HjrukMk?#0n9ahF~O z^-)ILpdO{ju6bxxl*SrCU$1F3 ziI=_~wiC0u+e3UdV!7PnlQ)jdgbU7QCBj3{zdCJzl$$Xks2(3A%WryqHE=DdXmOwKKSSs{<%kR3ubMZ> z4QZjZocGM9pBAg8cFgaZ)tPGe=99fKHMK(%x2HQqH+3nJnpHD$j1%td4mRtIR<3KF z{PrY5qnKW1yk(uDEI4kzGWPYGU%NLJt7~}Y7}aSi+Jbzp;t1z?el83R!Tbb znq`HR9EXGF2D!Z&;013W4R|bWy{ohFoIfEq^&pss`hJ7its?xHRMbIvx>1=_V5waU z>+GOS0}8en=C&KwuOTOtjiF%29Mia>zY`V21dG|%5wUJy5?ekJ0e3&wM@Q$04+Yz9 z!-yuKn&%02E~j5Mr&)@inv~ZX`%yRV!_(*PECKxj&PN(G0hy^BW0gBr-V=^;6L!{b z?*BCmIsWd?Pbf>~N&-Z4>l#6#Kf)gs+x8sOP z>|3N0X9D&;S%Y7;A1d#s&hFtKJ~!apj>$K?Kz2V&vqk-^_J)d zBa&M8IapU=*xC&2W`I7ld`uf-5Z1oxA&GbqXYPYH8GlUUf`))i&#}j{oN$5J-YnqH7eXZiuZoJ~oD7CW!&88v<7+DhE`Uv`e>47!Z zdN2I`wDJLHMUtxH`p-_LVuOcP(g`Qyv-5eb!e>e(K7XjuAxhEyT#}LE2GaR$Gla2K zIkoZK=8|QNM5&@X&`0ggQi>%?aY)bji{s&z84u3QT@6h(JeTsyXl5m~8tWr?@-F*y zi-^*YKRCha7yTJln|;&!ID=BaVr_B(Nt zLxKMfXh)D#`2Bq@ty9R{lrx4yNA!b1h0hU_0Nd1?Q-antv5*fg9Q+N#%SNrDmKHBm z<*&g%d#>C5fVkgKTfi0_<+=|Zp+f)K$gTIL6<6;QN;I}L8l@J9T|8kr2`vGn_nx;l zTr#6^IW1I=gex23M@3YYI3_knY22i3x+Ii zO68AfrhlLgIwe~`F+d|kB~_L!icf|{aqBn;*kIVM&H5*^x22|a@>^*uKu;geZ%Nd+ z`CvQ_j}$yICmO5~QRQouuen-%c-U`=zB3}>5jgvfc}mrA_gI#Erv)ZuFl}IKzaM)) zMwMjNdZR^mPSB*OIe%%DrcW=;Zp@0=BX5I=u3{(w%d)(Cr|R~Si%&!lPX6=j7>Jyr zIylr5aeztW$=DV=$HV6;$l!m-!P(!X+Wr=j)h@8m4d3SQw*PeX^dApa3)6D$oWpy{ z{#LfDWaz3v*^|#&;;@p0THVX{BgXSdy7%L$PhSR$#AMps)J@W)HKllqgl4AIh(!hJ zFj*b(nlp0EjW7&!SKK?X=j5ag*1!{Uh85>UOh2=!F&NC%Bhq^K(Gwnyy;n~-iDwB3 z>r?be7k%*9DFU3w%K#7UGyo#fi7Yl> zIftsjb_*FTSue-lO;vn*EIvmU+BEUv?{4QJ`gM&DaXr{$)$}sjkS|Qcu|!YFt)Dzm z{1~}QHBos`>W7H8So&zuD6h~X609vE_{P@1o|~{i3%49P926FlLvFHmczat;bAwi4 zzNyPm?iW8uF7Y4hbkNET&0G2w*~=o!uz1g+ek+#FKttmh*_m;1jJ}^pYD<<^#zHCe z$XU4*OD;#N%9ZqfDoMiG(7a1bmk^x<{`T-(;4kINP$xd%@$RBhe!x-(s(`67u~p;M ze&(AxcS!4roH-nt{Lv{)Y;)sk!9K8w=94PvMshiibrI}YQm zvM&RpT?}pBI_o!3LMc%ReH6Z{%Ygysgpy4ZOHkmo$17 zody+~3d{s9CNNQy4!bA!_wintb&UIVO zuAHQa-3d)D2sid+yQ|Fw;Mn$18Ae?V!%%7ugD+(#E9Fj6TLaumZETjfx}#}N<7SpU zwN9TDZ`qA6P2|OH$`aEH#Y6ktP7WvQmweeOk~<5^GA%sI{{^JGIZ08YC z!)RXnw@a1~&W*SKaN?uYk=MEKu6D#ZvrM)-#kZKax92BxV^q4krl60JnO^3!L8>qX z-lxitHTf0FB;%cnfVrN}#wup0fS-aGTQ`fXOiQPVydUi=8kcenT(Ym&=2u0^FDLeh zsajjN{4p87T?oQ$ceHo8LcWNfAJCYzY1LrRJ}T4MJHly!}NH;A09I#j*~f6m;v%_^*}UlV6D|P9qnAyZ(w@50*H)Mz)vE zZ=f?;ot~nR)Fj{4yn47@KJC=+6`L<=DBSORagkgxX9Mls>WB3ju1zq>DXLC)S*#r{ zao47qP8f&Z9!+k0-0^bGa&u=~Z|m5tvYO^(N%g-3AgSuTuPnd3Za`g-TWqi!GiTiR zAFIijLNRttV4X@y?%DT^_~t#P<~sStLHkKzWpsPF#%Xy(i3id3h5gs9eVcI&roetK z7IBNY>plVz8w^F=+Vq{MUDZKG(F#M)<(cWt+l~lMHPPmaUp#e_eL9V$@XoB2QF4!| zivqPHf10LDp(U<4IMgKg9n{S{X|M{co}vJ*dg^4MmER0nu)Cr!C1R|>1k7lsw1XDc zXFORmS+9OL203IJpLUSm`tvXXY;P`pY4sp?XMU!Vfk0uVBzFe~;$nl3jGZkIp1q^9({magkgUnHr`E%b zYJ)CqJ{_Ad^=poNkt)>S7Sw-Kln0XYnPOkr{MZNR>HA-U<@cv7L=8Vb!34tBQhYUr zUIuR5gk6BA+SE!`b5|5}zQY@jhE6^9Hm++X1-xebN<>|UsK~-jp8HG~PQ=$Ox-u(O z4G~d_(ss+Ic$Wzr{G=co1c^-{BSY~C3`(?4Ymi}0o}#v%GZ*J2T+BavZN3N<1810i zYL!1b#ALw!%TO-O_y;DxlEQ-LDhGZ0{GLVWv|p{Kip^Y$25v_Bz6VZ1_!BR*NB^ZIx@NE@t^DmTcCRZ=@ZAsQp&EqE;`hfJ z3(E82Rl(QiGM;Env`MC&SMU5bFpZ5aG{S4X=UC>n?ipGmN^)(lYZXUHLCl0=cGZV@ePMY}j^mS8n&nxxO{I?)k7o6b!O9{n#oh^6pDzuzK z=es-TPy3x0zhw$qaT2!5&Vo0n0kz*@O)M<)4H zr4d+`bjyMUBBBO|h3CR;PjE{$*z_9h_ht>J6sV`0T#ivVd)CiyCbCDZzc28cNB8U2 z8OFQ}I$AgdBQZ}x&a4;UCYjqrG$Cb${DkVy;U33K7E}}L+FOxDRP8B^ezWytKs&X7 z$^5>&;tXz3`0M?^r|OFXp($4dB5LT|pOaoiE=r6eNyN(75g{_i1sb7tlO=x!a@Jjm z$ojhHvRQxZo0jWY`b00;AkgORxW-+Mo}OL55xti-cLyu#IiQUARw!?Vm*EM_>IG`= zM@y-DY-g$*b{W?+_u0A{r*7S)poISJJ{N6gjqsY*pP7g^zF~~ooE@{6Pt;}E9o~{t z2U{aA!uHZNkKEqALY4D7&?d9Hgz}i7s<#4=z|%htjeCP`Bb=^bECp?-6fIM_abY@=O>?3bJ3s9zpS_332K{0DkkLU*b#NIo$6`S=O+@Te!;jFWn{0yfYa5%!%Z%k0A>uZFE$ zN%mZ5(z3@yh>&*jCf~l|H&yE7M(?J_O)RUUsr+tRwc|@*vr0WtH_NGtd6sQhtGcGy zuk0R&w-qy={vae!DC1gA;<^L$v`=_A zq6gB2W#vke)HZWolJvxvYK~+GI$iv3!_goDEwWkLi)I2*y%a!OIDRhbv!?Kv`3B)S z;|TBomR~}+^iqe4%C4+cLzQi*0Oq1p0`lL-Ub0=wG~m`n&;)d z?*=A3swkxEs;e8Ee_!Oc)Id@giE5u7i0dF#Ygh8=$U)Ys`d9ta&uHrPve#{B497OG z_~fOR49>HcDMOmxU9*1l=WA{4hi9We$p4A=U&w!IIF5@Pv415|n3&HW@26q#O3+d+ z1guYL?=s7`I3nP!l#^bUe(hp|R#-&g)8#Pn>)7poyDRM{-(-e<12WO%QNC7dFU~zC zWv?}GFfL#bLYw(0ZZP&mc{#;i-rHcCj#^DtTO3*0z;AY)_R03EjjtYn%$K4S<_T=R z15rl!>PY{|ovvz{y2*>!PO<7#orUGruJt=|4Kf=7v#q5^euCj({{SMm>jDeR#$OCJ z6>Z(sm9TF?G?ltHlNa>(FhJ(y!AKiD-G!Hvk^xfvvUg~UV6xzoq-MDK2Le$`PyhN= z-%iW!zI}m#%&W#Vp%IL3QrrFa46`8`uVNQBD(YPt5>a)lJy$-({Kd(dgyI)(I$R#ZuQYh z;3JB+Dxxj#15x;*Ti3FRYX<(OjIQyY_Y}$(&;@22TE}kknz!CHWckR4%yM`u88$Av zB8fEWQ(Ls}S^RO5F27GPE9blqoBLSrJYJ^>5w>yW1s?=j@mstK)~zsd$&UBhmPp6u zxi9)unDCd&xLo$dnVZ8c7eDSSf8uUf8y?a9?#@)F^0NKV(YBPhvUS7fG|x9dtdsbC zV`7eS>mH2yEiBoJwVY|xR@)?Jx&5RqVN838F5B0j`pdsYtUzb*02@$}x&@YauU0}F zim<=-EFg$;lVZ>nrFIQaTMj&Iq2>M-)8=`fWO7E9>ZIS)>_@yGL_jULa>tABMwWuK z&-DD4>xKC_Wxzly%FEzl$y0T{nS;NWogk8WbH*dztG~6mzZ{w1fpq-1yiz_teaBn& z=4zDI-pcU$M>qrYB5)AWq=(ILR(a!2K#Uo}TOAz_rKM zZk!T3HF*^bx(N1aLSl&zE?*^NWQ;iD->T)lzNWgpf%sM5BPv`da`lAs`nI*1^7|V3 z1@iWSUeAV#p>oQPxmYu}%fbchlXys-ZTeZ04$6ozUbQjNT6MX*V9mE>6;*cip^wcq z>f4?z+%yxsg$;1S<1n|KggiTy|AD2Nt}9rJw)50GX2Ik?LhZ(BFTVA;?XS?rS>8u& zH9cF>H_|q*i1u=B-kkP|o4C~6eoyr1Q6ufAzn1@nLzb;xeA^KIE=Ijg1~#eT%ujH0 z)cV6+03AX55|EzvoIK%hz{3%1;ng1T1CV}VV#&jig=09bId1P6>O#q_mnuI~d3^X} zozQ!x{AY2mCKpJsaBz6k5`OpAg~RAQzMe?i#M~}gKAK;Rr6Ck%O|or?sREP6HEwG+ zbH9spHP`ui^6l_A7cV7ah0!)?U~-W1;<%JM32{4%^Jtpo;#w`LhQ_@?E7ju~UJ$}( z;rR=+d~ID|b()?Ra%q5BuIg}u)KVf;v!_Q!0|{kJ1WhFZUg;Yz=z95MvN+Fe-Z$Gq z$nFs`iz#k{Dr|`2b{@Lc zO?>7}e&ImTx`)`Xl^71Wb6k$@TK{g9_BlAYr!b1SA!?=z@(QW{xWXqg6Mzw~@jbz$;~ zIkgYhZ`0G3ZrfAsMDl7jI_iW+9B{Z;S9hhKldD`bU)OCk&s>v?01^10^l~ma!f(^; ztgk3@Gt6hJ5AL-~0ZjEU3MmUEM{U*O;eMDkeK!8Q=2viZRj5>Qr*kmSEo@F z9;?moG>A^g3u<+0$Xr)Jmyr)d>F%?%1l9%qQe}$T`BiO{NO5@+NOW9Lj!C8? z=a(F<^EJtuPmTPLd0KT#!qN_rifH(w?Bq+B7$$<%LrJogu zQE^txTUG8fSgI2D??JtgY#;JVe6(#0e@7=V!-pVpsKg!xwtAaroIbPjRA70)>9uTz ziLl=HEjm;2G1f4TSrQPWW?afnq>)N{efrDPJ-F+!8z^Top!L2X8#VoAn+p3!> zR&88iu&0va=&^;1%qBM5CVxl^Bg&?qwpZb0nK0JkIGz5C-Ssy(MTplbe4Y11EaKoa z_!&!Aq}b`SDui252wD6LX?lJr`r!g(UCC8!_i2Y^KSG0-%gLyCf4i5?AFs zQ(In8So$fnGbxwoqA2NtKwkgB-vfL%$aea^RCmnzE0A+YUOR6prAB~X9yexY)YnaY zrQ`aLf*~j-a>dd7#mXz3>CEXfW9OBWkv*HzlKZx#c;z^+vQ6&u#B8E8F3%D0o_?V+mwUi~_vp`6T)O`0X+Ik1ObXOe z-z`q$E?w6>ys%cx{wX%Mk2s-qpLgu;Qz|zq z(}TlHqw@)V@3jT20{IfHt)j7f_Iq)%QbQ+R|2-kWGhSs2IY*-oV6sxlA*Xi<$l_R8 zd#)IDQ>#6uux1+s+gaI4&4~Rl863|CxpS)lxViZ!sg^Ntc1&qyEj9FDKrsqb4x2_` zlEviCsIejqy2tyN`c4>|c$&eVeSd<@)pBql8K;@wb}v0$;J0*cbf%a|G)KCMdHK?2v1;a&|;#4TSl$?(Tbc<3H=pCU{#TwNqDlL(o#^MDS2V>(CZ!d_{X zd)6D3N+tM}Hwd+P4a1T$w$9uvZgC;ywWWY~vu_oBWhQiUT|K+f3axkiUHF zDrPi|4{}#+Rr}3GvaBurqwVA52E{4d=#7~NmoMg&`_DsDTFT${=W7T1sce1Dr}{kD zsqe0M%<<~F>|%zaCf)2@vk82=Z9;A9cBQ#a$L%k)53(uT{^;j3*Y8JOFG{lnjI?VO z_2n3czo*I=n36#xPLwoTQM`zn&rjmWh*yzUtw|X^&PdEajSRwZ3r*B$nwNrLLA2== zZ3-rHKl%55>TOmVh*xuhzlplee7sDlK*={PoRJD*q`ro*ox0CpWwJ9YefSg?%sg`z zs8sZ9=IYy;F4^O-h@`637?D=8%hWP0{~gwS^3Wp?Lc(cVde*zsaH+tca$51(f}0Tm5~)IrvQfpWq_qg<48lNEhk|O| z*si$lUc^qgT3D4WiSQzIqVVljXL!7Z$1bv*D>i8ZC(5_2kp{^6;E#PKw-*xCtmfZc z#C~}}u2Q*oP>tZ8^is2(%F0Dl$#zkZdf6uQttTM;M6?T*(XfbU0<9f^y?%mV-&U2` z(>^lw0+trM>(T4|y#c+}8%3+-wXVqFo4x7+4{m-xt36yNZf-U^R!p_Y7H~T1*c7ja z5E>0mzeRks>LW%r?_!n1v&iD~yo->6!p(OD1IeV)8JESM>-ofXWVu|eH*f^Ed}s@k zm<^qQM%YKD%0|21_Vyk#uYw*d-t7H^l6RpZe9L{NlO9Ax&RBW+{tacfHh7TBO}!%p z1Xt1+L&U-6zydwHh>fZC6icKzNJ_J0uALorX5ZyZZUQ%**9HJ!xjd;>OfmLg~T`q9%U0 zVs^$imJZ;|wEJJ^tk>>Msimy#V7K~I$r97&kN=OoFaL-7`yQWmr6NMv$x_*}XBmW& zy~Pq{NJ#cDjGan^kbNg%B>TSa$!=sU*>_{?*~adBNA-I3`uqvs$NT>9>SdnK=e_5i zd+xbsyXW9i)6CQ|9wa{5p{aIqJzRo|gluODirqyHvo?HrTr zu%vdsQzUlai@LOI*v&{utExT6JlTWd^r5$&id3rfVr~<&Y1ht7yl?*&D4tOOjUZ)i zqEaGbUcj!Vip!CZP+wM0*KY1g;Tv6PNFOY=8eUKJFRacx3~yN%h`auCzS8H50a`Wo z`f4br))(2t_q@E)MAjP<+x3KZ-8xNq%VJzEn^tr0Jc({b9vIDg?C-J@1!X@0V60(V z>B;x4>R;@ocoL@uCfv4PZECLfesb+sG;1s;y{xj; zH*?N2S*i#u7cik`9Y2esi!+BgyH$H&K)g5`kS{>1-IRG;&*kS>s64S?)%j$W`h3+? zWc(=)$t2#hmT7`q`S~Zeb=|Za7kb_jza{0}wtXI;zz~I4>Iz%4KGS`0)xFRE?ft{$ zxU`N@We27O=!UC%ftgTZ+|H)?VM&$sq`P~^<#=9|*vWwH%;?LbX}9^5H8F){oP8gA zyS6s&`gxLy*fu7&e&F5PYw)9bM#52y+vDoll18!Pl-9Bta{2dWzi+!AGTFAJ_~}{@ z9nA8hQfU{u+DnY17T;VvJbc_FkY+%Z1uxtmI8Pv1sWG28=D^~gF^jY1O*A1hv>jOW zfp>0DFSn0X?d6|*UCT^#eXnJ-o~W)WmO;j)IBm2fiy1eyu1`O<3dq|&mM+&m`o+{q zqKf?c3Q0N>MFFQ_a;M#tsX;K&ysL47NCzg_akJsWkI7{r-UP|@rbos%Y+Tnr#)y?% zc3A&z%g^2}IyrE*OMLZ{pP$pQ6%qlqTGmBxv4c~~QMvOAbT3VI?aQ$aD$72&CiKTo$=^N`+Z0ou`syr`1nU_wTSx)%MSj$WuKN+P7K#qX`-JR zZpGLSdD*Z51r7N(j#?Mup)WQb>_^QRmp#I}&MvLd@oWe{?_hO*PLtikUz~3D+`p}nek#$F6ta?3LGyBpZuX_(EQ>hxmq)8<2`FYg_n&Lyf2&nl8h%Zlfis~2}W z*`!oi?R~eJRkTrT9^ch%nYbl~$Zp5Tr1QuN6w!WHYjv!n(f0p5en6L0u6d~4T{~{V zFwDz`*bVk1ny*+CTh?eMXWlR#*>u7+gz~K87b7 z_c~u)nVvL`4XEYr({g|n3`Q_dJ}A~n5La3xzm~c$*F#}GnW-0kru$nM66q{mO}g!T zi7FrI+_%1m*!qf$lgICM%=uN3LhU_pWJmK{aZeX+nIw^o%z987KCBqal8xUD%Kjq4 z&5ImO%QaZCUdvDTQXjbgr0=KkY`?S8JK$Ig^Rr_{JA2CsTEA4xorsV-9U%lgtH%-6 z_e|=ha-4Sfg@~%zrt`}M7M{hz?7o%7hcv>HYa}Nhk}O|+SnD@wQ&E65v(kyK_^>pR zT|`HNS5t={a$k0|oUgEt-g$9sOT?0`?o?0X<=&9b``1QGwTwqZM24!bDC@e6?uR6Q zTu!LIDzZH4%WWn+I);1GU0)ySwIK*k