From e07ec313ef0b352024f54e768d6a20ff07192bd1 Mon Sep 17 00:00:00 2001 From: "Limor \"Ladyada\" Fried" Date: Sun, 2 Feb 2020 13:26:56 -0500 Subject: [PATCH] full refactor (#7) * moved files and added NXP fusion * rename and make unique names * renamed files and made a multi-filter tester * USB and Mahony examples are now superceded by one calibrated_orientation example * add lsm9ds0 fusion demo to calibrated_orientation and removed standalone version also moving really old 10dof/9dof demos * make one unified calibrator * add CI * add some deps * add more deps * more deps * update naming * more deps * skip and dep * manually add conversion const * more fixfix * change default to mahony * fix skips * clangclang * moreclang --- .github/workflows/githubci.yml | 37 + Adafruit_Simple_AHRS.cpp | 72 - Adafruit_Simple_AHRS.h | 21 - Madgwick.cpp | 250 --- Madgwick.h | 79 - Mahony.cpp | 274 --- Mahony.h | 72 - .../ahrs_calibration/ahrs_calibration.ino | 86 - .../ahrs_calibration_ble_nrf51/.uno.test.only | 0 .../ahrs_calibration_ble_nrf51/ArdPrintf.h | 62 +- .../BluefruitConfig.h | 35 +- .../ahrs_calibration_usb.ino | 140 -- examples/ahrs_fusion_ble_nrf51/.uno.test.only | 0 .../ahrs_fusion_ble_nrf51/BluefruitConfig.h | 35 +- .../ahrs_fusion_ble_nrf51.ino | 13 +- examples/ahrs_fusion_usb/ahrs_fusion_usb.ino | 167 -- .../ahrs_fusion_usb/sample_config_data.png | Bin 219474 -> 0 bytes examples/ahrs_lsm9ds0/ahrs_lsm9ds0.ino | 72 - examples/ahrs_mahony/ahrs_mahony.ino | 120 -- examples/ahrs_mahony/sample_config_data.png | Bin 219474 -> 0 bytes .../calibrated_orientation/LSM6DS_LIS3MDL.h | 31 + examples/calibrated_orientation/LSM9DS.h | 30 + examples/calibrated_orientation/LSM9DS1.h | 20 + .../calibrated_orientation/NXP_FXOS_FXAS.h | 18 + .../calibrated_orientation.ino | 111 ++ examples/calibration/LSM6DS_LIS3MDL.h | 31 + examples/calibration/LSM9DS.h | 30 + examples/calibration/NXP_FXOS_FXAS.h | 18 + examples/calibration/calibration.ino | 221 +++ .../ahrs_10dof/ahrs_10dof.ino | 0 .../{ => deprecated}/ahrs_9dof/ahrs_9dof.ino | 0 library.properties | 7 +- src/Adafruit_AHRS.h | 3 + src/Adafruit_AHRS_Madgwick.cpp | 289 ++++ src/Adafruit_AHRS_Madgwick.h | 87 + src/Adafruit_AHRS_Mahony.cpp | 272 +++ src/Adafruit_AHRS_Mahony.h | 81 + src/Adafruit_AHRS_NXPFusion.cpp | 1487 +++++++++++++++++ src/Adafruit_AHRS_NXPFusion.h | 114 ++ src/Adafruit_AHRS_NXPmatrix.c | 467 ++++++ .../Adafruit_Sensor_Set.h | 5 +- src/Adafruit_Simple_AHRS.cpp | 85 + src/Adafruit_Simple_AHRS.h | 20 + 43 files changed, 3526 insertions(+), 1436 deletions(-) create mode 100644 .github/workflows/githubci.yml delete mode 100644 Adafruit_Simple_AHRS.cpp delete mode 100644 Adafruit_Simple_AHRS.h delete mode 100644 Madgwick.cpp delete mode 100644 Madgwick.h delete mode 100644 Mahony.cpp delete mode 100644 Mahony.h delete mode 100644 examples/ahrs_calibration/ahrs_calibration.ino create mode 100644 examples/ahrs_calibration_ble_nrf51/.uno.test.only delete mode 100644 examples/ahrs_calibration_usb/ahrs_calibration_usb.ino create mode 100644 examples/ahrs_fusion_ble_nrf51/.uno.test.only delete mode 100644 examples/ahrs_fusion_usb/ahrs_fusion_usb.ino delete mode 100644 examples/ahrs_fusion_usb/sample_config_data.png delete mode 100644 examples/ahrs_lsm9ds0/ahrs_lsm9ds0.ino delete mode 100755 examples/ahrs_mahony/ahrs_mahony.ino delete mode 100755 examples/ahrs_mahony/sample_config_data.png create mode 100644 examples/calibrated_orientation/LSM6DS_LIS3MDL.h create mode 100644 examples/calibrated_orientation/LSM9DS.h create mode 100644 examples/calibrated_orientation/LSM9DS1.h create mode 100644 examples/calibrated_orientation/NXP_FXOS_FXAS.h create mode 100644 examples/calibrated_orientation/calibrated_orientation.ino create mode 100644 examples/calibration/LSM6DS_LIS3MDL.h create mode 100644 examples/calibration/LSM9DS.h create mode 100644 examples/calibration/NXP_FXOS_FXAS.h create mode 100644 examples/calibration/calibration.ino rename examples/{ => deprecated}/ahrs_10dof/ahrs_10dof.ino (100%) rename examples/{ => deprecated}/ahrs_9dof/ahrs_9dof.ino (100%) create mode 100644 src/Adafruit_AHRS.h create mode 100644 src/Adafruit_AHRS_Madgwick.cpp create mode 100644 src/Adafruit_AHRS_Madgwick.h create mode 100644 src/Adafruit_AHRS_Mahony.cpp create mode 100644 src/Adafruit_AHRS_Mahony.h create mode 100644 src/Adafruit_AHRS_NXPFusion.cpp create mode 100644 src/Adafruit_AHRS_NXPFusion.h create mode 100644 src/Adafruit_AHRS_NXPmatrix.c rename Adafruit_Sensor_Set.h => src/Adafruit_Sensor_Set.h (72%) create mode 100644 src/Adafruit_Simple_AHRS.cpp create mode 100644 src/Adafruit_Simple_AHRS.h diff --git a/.github/workflows/githubci.yml b/.github/workflows/githubci.yml new file mode 100644 index 0000000..b596305 --- /dev/null +++ b/.github/workflows/githubci.yml @@ -0,0 +1,37 @@ +name: Arduino Library CI + +on: [pull_request, push, repository_dispatch] + +jobs: + build: + runs-on: ubuntu-latest + + steps: + - uses: actions/setup-python@v1 + with: + python-version: '3.x' + - uses: actions/checkout@v2 + - uses: actions/checkout@v2 + with: + repository: adafruit/ci-arduino + path: ci + + - name: pre-install + run: bash ci/actions_install.sh + + # manually install calib + - name: extra libraries + run: | + git clone --quiet https://github.com/adafruit/Adafruit_Sensor_Calibration.git /home/runner/Arduino/libraries/Adafruit_Sensor_Calibration + + - name: test platforms + run: python3 ci/build_platform.py main_platforms + + - name: clang + run: python3 ci/run-clang-format.py -e "ci/*" -e "bin/*" -r . + + - name: doxygen + env: + GH_REPO_TOKEN: ${{ secrets.GH_REPO_TOKEN }} + PRETTYNAME : "Adafruit AHRS Library" + run: bash ci/doxy_gen_and_deploy.sh diff --git a/Adafruit_Simple_AHRS.cpp b/Adafruit_Simple_AHRS.cpp deleted file mode 100644 index a3ce5cd..0000000 --- a/Adafruit_Simple_AHRS.cpp +++ /dev/null @@ -1,72 +0,0 @@ -#include "Adafruit_Simple_AHRS.h" - -// Create a simple AHRS from an explicit accelerometer and magnetometer sensor. -Adafruit_Simple_AHRS::Adafruit_Simple_AHRS(Adafruit_Sensor* accelerometer, Adafruit_Sensor* magnetometer): - _accel(accelerometer), - _mag(magnetometer) -{} - -// Create a simple AHRS from a device with multiple sensors. -Adafruit_Simple_AHRS::Adafruit_Simple_AHRS(Adafruit_Sensor_Set& sensors): - _accel(sensors.getSensor(SENSOR_TYPE_ACCELEROMETER)), - _mag(sensors.getSensor(SENSOR_TYPE_MAGNETIC_FIELD)) -{} - -// Compute orientation based on accelerometer and magnetometer data. -bool Adafruit_Simple_AHRS::getOrientation(sensors_vec_t* orientation) { - // Validate input and available sensors. - if (orientation == NULL || _accel == NULL || _mag == NULL) return false; - - // Grab an acceleromter and magnetometer reading. - sensors_event_t accel_event; - _accel->getEvent(&accel_event); - sensors_event_t mag_event; - _mag->getEvent(&mag_event); - - float const PI_F = 3.14159265F; - - // roll: Rotation around the X-axis. -180 <= roll <= 180 - // a positive roll angle is defined to be a clockwise rotation about the positive X-axis - // - // y - // roll = atan2(---) - // z - // - // where: y, z are returned value from accelerometer sensor - orientation->roll = (float)atan2(accel_event.acceleration.y, accel_event.acceleration.z); - - // pitch: Rotation around the Y-axis. -180 <= roll <= 180 - // a positive pitch angle is defined to be a clockwise rotation about the positive Y-axis - // - // -x - // pitch = atan(-------------------------------) - // y * sin(roll) + z * cos(roll) - // - // where: x, y, z are returned value from accelerometer sensor - if (accel_event.acceleration.y * sin(orientation->roll) + accel_event.acceleration.z * cos(orientation->roll) == 0) - orientation->pitch = accel_event.acceleration.x > 0 ? (PI_F / 2) : (-PI_F / 2); - else - orientation->pitch = (float)atan(-accel_event.acceleration.x / (accel_event.acceleration.y * sin(orientation->roll) + \ - accel_event.acceleration.z * cos(orientation->roll))); - - // heading: Rotation around the Z-axis. -180 <= roll <= 180 - // a positive heading angle is defined to be a clockwise rotation about the positive Z-axis - // - // z * sin(roll) - y * cos(roll) - // heading = atan2(--------------------------------------------------------------------------) - // x * cos(pitch) + y * sin(pitch) * sin(roll) + z * sin(pitch) * cos(roll)) - // - // where: x, y, z are returned value from magnetometer sensor - orientation->heading = (float)atan2(mag_event.magnetic.z * sin(orientation->roll) - mag_event.magnetic.y * cos(orientation->roll), \ - mag_event.magnetic.x * cos(orientation->pitch) + \ - mag_event.magnetic.y * sin(orientation->pitch) * sin(orientation->roll) + \ - mag_event.magnetic.z * sin(orientation->pitch) * cos(orientation->roll)); - - - // Convert angular data to degree - orientation->roll = orientation->roll * 180 / PI_F; - orientation->pitch = orientation->pitch * 180 / PI_F; - orientation->heading = orientation->heading * 180 / PI_F; - - return true; -} \ No newline at end of file diff --git a/Adafruit_Simple_AHRS.h b/Adafruit_Simple_AHRS.h deleted file mode 100644 index 3c5d38f..0000000 --- a/Adafruit_Simple_AHRS.h +++ /dev/null @@ -1,21 +0,0 @@ -#ifndef __ADAFRUIT_SIMPLE_AHRS_H__ -#define __ADAFRUIT_SIMPLE_AHRS_H__ - -#include -#include "Adafruit_Sensor_Set.h" - -// Simple sensor fusion AHRS using an accelerometer and magnetometer. -class Adafruit_Simple_AHRS -{ -public: - Adafruit_Simple_AHRS(Adafruit_Sensor* accelerometer, Adafruit_Sensor* magnetometer); - Adafruit_Simple_AHRS(Adafruit_Sensor_Set& sensors); - bool getOrientation(sensors_vec_t* orientation); - -private: - Adafruit_Sensor* _accel; - Adafruit_Sensor* _mag; - -}; - -#endif diff --git a/Madgwick.cpp b/Madgwick.cpp deleted file mode 100644 index 87ab8ab..0000000 --- a/Madgwick.cpp +++ /dev/null @@ -1,250 +0,0 @@ -//============================================================================================= -// Madgwick.c -//============================================================================================= -// -// Implementation of Madgwick's IMU and AHRS algorithms. -// See: http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/ -// -// From the x-io website "Open-source resources available on this website are -// provided under the GNU General Public Licence unless an alternative licence -// is provided in source." -// -// Date Author Notes -// 29/09/2011 SOH Madgwick Initial release -// 02/10/2011 SOH Madgwick Optimised for reduced CPU load -// 19/02/2012 SOH Madgwick Magnetometer measurement is normalised -// -//============================================================================================= - -//------------------------------------------------------------------------------------------- -// Header files - -#include "Madgwick.h" -#include - -//------------------------------------------------------------------------------------------- -// Definitions - -#define sampleFreqDef 512.0f // sample frequency in Hz -#define betaDef 0.1f // 2 * proportional gain - - -//============================================================================================ -// Functions - -//------------------------------------------------------------------------------------------- -// AHRS algorithm update - -Madgwick::Madgwick() { - beta = betaDef; - q0 = 1.0f; - q1 = 0.0f; - q2 = 0.0f; - q3 = 0.0f; - invSampleFreq = 1.0f / sampleFreqDef; - anglesComputed = 0; -} - -void Madgwick::update(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz) { - float recipNorm; - float s0, s1, s2, s3; - float qDot1, qDot2, qDot3, qDot4; - float hx, hy; - float _2q0mx, _2q0my, _2q0mz, _2q1mx, _2bx, _2bz, _4bx, _4bz, _2q0, _2q1, _2q2, _2q3, _2q0q2, _2q2q3, q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; - - // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation) - if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { - updateIMU(gx, gy, gz, ax, ay, az); - return; - } - - // Convert gyroscope degrees/sec to radians/sec - gx *= 0.0174533f; - gy *= 0.0174533f; - gz *= 0.0174533f; - - // Rate of change of quaternion from gyroscope - qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); - qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); - qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); - qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx); - - // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) - if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { - - // Normalise accelerometer measurement - recipNorm = invSqrt(ax * ax + ay * ay + az * az); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; - - // Normalise magnetometer measurement - recipNorm = invSqrt(mx * mx + my * my + mz * mz); - mx *= recipNorm; - my *= recipNorm; - mz *= recipNorm; - - // Auxiliary variables to avoid repeated arithmetic - _2q0mx = 2.0f * q0 * mx; - _2q0my = 2.0f * q0 * my; - _2q0mz = 2.0f * q0 * mz; - _2q1mx = 2.0f * q1 * mx; - _2q0 = 2.0f * q0; - _2q1 = 2.0f * q1; - _2q2 = 2.0f * q2; - _2q3 = 2.0f * q3; - _2q0q2 = 2.0f * q0 * q2; - _2q2q3 = 2.0f * q2 * q3; - q0q0 = q0 * q0; - q0q1 = q0 * q1; - q0q2 = q0 * q2; - q0q3 = q0 * q3; - q1q1 = q1 * q1; - q1q2 = q1 * q2; - q1q3 = q1 * q3; - q2q2 = q2 * q2; - q2q3 = q2 * q3; - q3q3 = q3 * q3; - - // Reference direction of Earth's magnetic field - hx = mx * q0q0 - _2q0my * q3 + _2q0mz * q2 + mx * q1q1 + _2q1 * my * q2 + _2q1 * mz * q3 - mx * q2q2 - mx * q3q3; - hy = _2q0mx * q3 + my * q0q0 - _2q0mz * q1 + _2q1mx * q2 - my * q1q1 + my * q2q2 + _2q2 * mz * q3 - my * q3q3; - _2bx = sqrtf(hx * hx + hy * hy); - _2bz = -_2q0mx * q2 + _2q0my * q1 + mz * q0q0 + _2q1mx * q3 - mz * q1q1 + _2q2 * my * q3 - mz * q2q2 + mz * q3q3; - _4bx = 2.0f * _2bx; - _4bz = 2.0f * _2bz; - - // Gradient decent algorithm corrective step - s0 = -_2q2 * (2.0f * q1q3 - _2q0q2 - ax) + _2q1 * (2.0f * q0q1 + _2q2q3 - ay) - _2bz * q2 * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (-_2bx * q3 + _2bz * q1) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + _2bx * q2 * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); - s1 = _2q3 * (2.0f * q1q3 - _2q0q2 - ax) + _2q0 * (2.0f * q0q1 + _2q2q3 - ay) - 4.0f * q1 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + _2bz * q3 * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (_2bx * q2 + _2bz * q0) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + (_2bx * q3 - _4bz * q1) * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); - s2 = -_2q0 * (2.0f * q1q3 - _2q0q2 - ax) + _2q3 * (2.0f * q0q1 + _2q2q3 - ay) - 4.0f * q2 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + (-_4bx * q2 - _2bz * q0) * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (_2bx * q1 + _2bz * q3) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + (_2bx * q0 - _4bz * q2) * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); - s3 = _2q1 * (2.0f * q1q3 - _2q0q2 - ax) + _2q2 * (2.0f * q0q1 + _2q2q3 - ay) + (-_4bx * q3 + _2bz * q1) * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (-_2bx * q0 + _2bz * q2) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + _2bx * q1 * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); - recipNorm = invSqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude - s0 *= recipNorm; - s1 *= recipNorm; - s2 *= recipNorm; - s3 *= recipNorm; - - // Apply feedback step - qDot1 -= beta * s0; - qDot2 -= beta * s1; - qDot3 -= beta * s2; - qDot4 -= beta * s3; - } - - // Integrate rate of change of quaternion to yield quaternion - q0 += qDot1 * invSampleFreq; - q1 += qDot2 * invSampleFreq; - q2 += qDot3 * invSampleFreq; - q3 += qDot4 * invSampleFreq; - - // Normalise quaternion - recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); - q0 *= recipNorm; - q1 *= recipNorm; - q2 *= recipNorm; - q3 *= recipNorm; - anglesComputed = 0; -} - -//------------------------------------------------------------------------------------------- -// IMU algorithm update - -void Madgwick::updateIMU(float gx, float gy, float gz, float ax, float ay, float az) { - float recipNorm; - float s0, s1, s2, s3; - float qDot1, qDot2, qDot3, qDot4; - float _2q0, _2q1, _2q2, _2q3, _4q0, _4q1, _4q2 ,_8q1, _8q2, q0q0, q1q1, q2q2, q3q3; - - // Convert gyroscope degrees/sec to radians/sec - gx *= 0.0174533f; - gy *= 0.0174533f; - gz *= 0.0174533f; - - // Rate of change of quaternion from gyroscope - qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); - qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); - qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); - qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx); - - // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) - if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { - - // Normalise accelerometer measurement - recipNorm = invSqrt(ax * ax + ay * ay + az * az); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; - - // Auxiliary variables to avoid repeated arithmetic - _2q0 = 2.0f * q0; - _2q1 = 2.0f * q1; - _2q2 = 2.0f * q2; - _2q3 = 2.0f * q3; - _4q0 = 4.0f * q0; - _4q1 = 4.0f * q1; - _4q2 = 4.0f * q2; - _8q1 = 8.0f * q1; - _8q2 = 8.0f * q2; - q0q0 = q0 * q0; - q1q1 = q1 * q1; - q2q2 = q2 * q2; - q3q3 = q3 * q3; - - // Gradient decent algorithm corrective step - s0 = _4q0 * q2q2 + _2q2 * ax + _4q0 * q1q1 - _2q1 * ay; - s1 = _4q1 * q3q3 - _2q3 * ax + 4.0f * q0q0 * q1 - _2q0 * ay - _4q1 + _8q1 * q1q1 + _8q1 * q2q2 + _4q1 * az; - s2 = 4.0f * q0q0 * q2 + _2q0 * ax + _4q2 * q3q3 - _2q3 * ay - _4q2 + _8q2 * q1q1 + _8q2 * q2q2 + _4q2 * az; - s3 = 4.0f * q1q1 * q3 - _2q1 * ax + 4.0f * q2q2 * q3 - _2q2 * ay; - recipNorm = invSqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude - s0 *= recipNorm; - s1 *= recipNorm; - s2 *= recipNorm; - s3 *= recipNorm; - - // Apply feedback step - qDot1 -= beta * s0; - qDot2 -= beta * s1; - qDot3 -= beta * s2; - qDot4 -= beta * s3; - } - - // Integrate rate of change of quaternion to yield quaternion - q0 += qDot1 * invSampleFreq; - q1 += qDot2 * invSampleFreq; - q2 += qDot3 * invSampleFreq; - q3 += qDot4 * invSampleFreq; - - // Normalise quaternion - recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); - q0 *= recipNorm; - q1 *= recipNorm; - q2 *= recipNorm; - q3 *= recipNorm; - anglesComputed = 0; -} - -//------------------------------------------------------------------------------------------- -// Fast inverse square-root -// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root - -float Madgwick::invSqrt(float x) { - float halfx = 0.5f * x; - float y = x; - long i = *(long*)&y; - i = 0x5f3759df - (i>>1); - y = *(float*)&i; - y = y * (1.5f - (halfx * y * y)); - y = y * (1.5f - (halfx * y * y)); - return y; -} - -//------------------------------------------------------------------------------------------- - -void Madgwick::computeAngles() -{ - roll = atan2f(q0*q1 + q2*q3, 0.5f - q1*q1 - q2*q2); - pitch = asinf(-2.0f * (q1*q3 - q0*q2)); - yaw = atan2f(q1*q2 + q0*q3, 0.5f - q2*q2 - q3*q3); - anglesComputed = 1; -} diff --git a/Madgwick.h b/Madgwick.h deleted file mode 100644 index 0c0f336..0000000 --- a/Madgwick.h +++ /dev/null @@ -1,79 +0,0 @@ -//============================================================================================= -// Madgwick.h -//============================================================================================= -// -// Implementation of Madgwick's IMU and AHRS algorithms. -// See: http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/ -// -// From the x-io website "Open-source resources available on this website are -// provided under the GNU General Public Licence unless an alternative licence -// is provided in source." -// -// Date Author Notes -// 29/09/2011 SOH Madgwick Initial release -// 02/10/2011 SOH Madgwick Optimised for reduced CPU load -// -//============================================================================================= -#ifndef __Madgwick_h__ -#define __Madgwick_h__ -#include - -//-------------------------------------------------------------------------------------------- -// Variable declaration -class Madgwick{ -private: - static float invSqrt(float x); - float beta; // algorithm gain - float q0; - float q1; - float q2; - float q3; // quaternion of sensor frame relative to auxiliary frame - float invSampleFreq; - float roll; - float pitch; - float yaw; - char anglesComputed; - void computeAngles(); - -//------------------------------------------------------------------------------------------- -// Function declarations -public: - Madgwick(void); - void begin(float sampleFrequency) { invSampleFreq = 1.0f / sampleFrequency; } - void update(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz); - void updateIMU(float gx, float gy, float gz, float ax, float ay, float az); - //float getPitch(){return atan2f(2.0f * q2 * q3 - 2.0f * q0 * q1, 2.0f * q0 * q0 + 2.0f * q3 * q3 - 1.0f);}; - //float getRoll(){return -1.0f * asinf(2.0f * q1 * q3 + 2.0f * q0 * q2);}; - //float getYaw(){return atan2f(2.0f * q1 * q2 - 2.0f * q0 * q3, 2.0f * q0 * q0 + 2.0f * q1 * q1 - 1.0f);}; - float getRoll() { - if (!anglesComputed) computeAngles(); - return roll * 57.29578f; - } - float getPitch() { - if (!anglesComputed) computeAngles(); - return pitch * 57.29578f; - } - float getYaw() { - if (!anglesComputed) computeAngles(); - return yaw * 57.29578f + 180.0f; - } - float getRollRadians() { - if (!anglesComputed) computeAngles(); - return roll; - } - float getPitchRadians() { - if (!anglesComputed) computeAngles(); - return pitch; - } - float getYawRadians() { - if (!anglesComputed) computeAngles(); - return yaw; - } - void getQuaternion(float *w, float *x, float *y, float *z) { - *w = q0; - *x = q1; - *y = q2; - *z = q3; - } -}; -#endif diff --git a/Mahony.cpp b/Mahony.cpp deleted file mode 100644 index fea00e4..0000000 --- a/Mahony.cpp +++ /dev/null @@ -1,274 +0,0 @@ -//============================================================================================= -// Mahony.c -//============================================================================================= -// -// Madgwick's implementation of Mayhony's AHRS algorithm. -// See: http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/ -// -// From the x-io website "Open-source resources available on this website are -// provided under the GNU General Public Licence unless an alternative licence -// is provided in source." -// -// Date Author Notes -// 29/09/2011 SOH Madgwick Initial release -// 02/10/2011 SOH Madgwick Optimised for reduced CPU load -// -// Algorithm paper: -// http://ieeexplore.ieee.org/xpl/login.jsp?tp=&arnumber=4608934&url=http%3A%2F%2Fieeexplore.ieee.org%2Fstamp%2Fstamp.jsp%3Ftp%3D%26arnumber%3D4608934 -// -//============================================================================================= - -//------------------------------------------------------------------------------------------- -// Header files - -#include "Mahony.h" -#include - -//------------------------------------------------------------------------------------------- -// Definitions - -#define DEFAULT_SAMPLE_FREQ 512.0f // sample frequency in Hz -#define twoKpDef (2.0f * 0.5f) // 2 * proportional gain -#define twoKiDef (2.0f * 0.0f) // 2 * integral gain - - -//============================================================================================ -// Functions - -//------------------------------------------------------------------------------------------- -// AHRS algorithm update - -Mahony::Mahony() -{ - twoKp = twoKpDef; // 2 * proportional gain (Kp) - twoKi = twoKiDef; // 2 * integral gain (Ki) - q0 = 1.0f; - q1 = 0.0f; - q2 = 0.0f; - q3 = 0.0f; - integralFBx = 0.0f; - integralFBy = 0.0f; - integralFBz = 0.0f; - anglesComputed = 0; - invSampleFreq = 1.0f / DEFAULT_SAMPLE_FREQ; -} - -void Mahony::update(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz) -{ - float recipNorm; - float q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; - float hx, hy, bx, bz; - float halfvx, halfvy, halfvz, halfwx, halfwy, halfwz; - float halfex, halfey, halfez; - float qa, qb, qc; - - // Use IMU algorithm if magnetometer measurement invalid - // (avoids NaN in magnetometer normalisation) - if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { - updateIMU(gx, gy, gz, ax, ay, az); - return; - } - - // Convert gyroscope degrees/sec to radians/sec - gx *= 0.0174533f; - gy *= 0.0174533f; - gz *= 0.0174533f; - - // Compute feedback only if accelerometer measurement valid - // (avoids NaN in accelerometer normalisation) - if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { - - // Normalise accelerometer measurement - recipNorm = invSqrt(ax * ax + ay * ay + az * az); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; - - // Normalise magnetometer measurement - recipNorm = invSqrt(mx * mx + my * my + mz * mz); - mx *= recipNorm; - my *= recipNorm; - mz *= recipNorm; - - // Auxiliary variables to avoid repeated arithmetic - q0q0 = q0 * q0; - q0q1 = q0 * q1; - q0q2 = q0 * q2; - q0q3 = q0 * q3; - q1q1 = q1 * q1; - q1q2 = q1 * q2; - q1q3 = q1 * q3; - q2q2 = q2 * q2; - q2q3 = q2 * q3; - q3q3 = q3 * q3; - - // Reference direction of Earth's magnetic field - hx = 2.0f * (mx * (0.5f - q2q2 - q3q3) + my * (q1q2 - q0q3) + mz * (q1q3 + q0q2)); - hy = 2.0f * (mx * (q1q2 + q0q3) + my * (0.5f - q1q1 - q3q3) + mz * (q2q3 - q0q1)); - bx = sqrtf(hx * hx + hy * hy); - bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2)); - - // Estimated direction of gravity and magnetic field - halfvx = q1q3 - q0q2; - halfvy = q0q1 + q2q3; - halfvz = q0q0 - 0.5f + q3q3; - halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2); - halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3); - halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2); - - // Error is sum of cross product between estimated direction - // and measured direction of field vectors - halfex = (ay * halfvz - az * halfvy) + (my * halfwz - mz * halfwy); - halfey = (az * halfvx - ax * halfvz) + (mz * halfwx - mx * halfwz); - halfez = (ax * halfvy - ay * halfvx) + (mx * halfwy - my * halfwx); - - // Compute and apply integral feedback if enabled - if(twoKi > 0.0f) { - // integral error scaled by Ki - integralFBx += twoKi * halfex * invSampleFreq; - integralFBy += twoKi * halfey * invSampleFreq; - integralFBz += twoKi * halfez * invSampleFreq; - gx += integralFBx; // apply integral feedback - gy += integralFBy; - gz += integralFBz; - } else { - integralFBx = 0.0f; // prevent integral windup - integralFBy = 0.0f; - integralFBz = 0.0f; - } - - // Apply proportional feedback - gx += twoKp * halfex; - gy += twoKp * halfey; - gz += twoKp * halfez; - } - - // Integrate rate of change of quaternion - gx *= (0.5f * invSampleFreq); // pre-multiply common factors - gy *= (0.5f * invSampleFreq); - gz *= (0.5f * invSampleFreq); - qa = q0; - qb = q1; - qc = q2; - q0 += (-qb * gx - qc * gy - q3 * gz); - q1 += (qa * gx + qc * gz - q3 * gy); - q2 += (qa * gy - qb * gz + q3 * gx); - q3 += (qa * gz + qb * gy - qc * gx); - - // Normalise quaternion - recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); - q0 *= recipNorm; - q1 *= recipNorm; - q2 *= recipNorm; - q3 *= recipNorm; - anglesComputed = 0; -} - -//------------------------------------------------------------------------------------------- -// IMU algorithm update - -void Mahony::updateIMU(float gx, float gy, float gz, float ax, float ay, float az) -{ - float recipNorm; - float halfvx, halfvy, halfvz; - float halfex, halfey, halfez; - float qa, qb, qc; - - // Convert gyroscope degrees/sec to radians/sec - gx *= 0.0174533f; - gy *= 0.0174533f; - gz *= 0.0174533f; - - // Compute feedback only if accelerometer measurement valid - // (avoids NaN in accelerometer normalisation) - if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { - - // Normalise accelerometer measurement - recipNorm = invSqrt(ax * ax + ay * ay + az * az); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; - - // Estimated direction of gravity - halfvx = q1 * q3 - q0 * q2; - halfvy = q0 * q1 + q2 * q3; - halfvz = q0 * q0 - 0.5f + q3 * q3; - - // Error is sum of cross product between estimated - // and measured direction of gravity - halfex = (ay * halfvz - az * halfvy); - halfey = (az * halfvx - ax * halfvz); - halfez = (ax * halfvy - ay * halfvx); - - // Compute and apply integral feedback if enabled - if(twoKi > 0.0f) { - // integral error scaled by Ki - integralFBx += twoKi * halfex * invSampleFreq; - integralFBy += twoKi * halfey * invSampleFreq; - integralFBz += twoKi * halfez * invSampleFreq; - gx += integralFBx; // apply integral feedback - gy += integralFBy; - gz += integralFBz; - } else { - integralFBx = 0.0f; // prevent integral windup - integralFBy = 0.0f; - integralFBz = 0.0f; - } - - // Apply proportional feedback - gx += twoKp * halfex; - gy += twoKp * halfey; - gz += twoKp * halfez; - } - - // Integrate rate of change of quaternion - gx *= (0.5f * invSampleFreq); // pre-multiply common factors - gy *= (0.5f * invSampleFreq); - gz *= (0.5f * invSampleFreq); - qa = q0; - qb = q1; - qc = q2; - q0 += (-qb * gx - qc * gy - q3 * gz); - q1 += (qa * gx + qc * gz - q3 * gy); - q2 += (qa * gy - qb * gz + q3 * gx); - q3 += (qa * gz + qb * gy - qc * gx); - - // Normalise quaternion - recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); - q0 *= recipNorm; - q1 *= recipNorm; - q2 *= recipNorm; - q3 *= recipNorm; - anglesComputed = 0; -} - -//------------------------------------------------------------------------------------------- -// Fast inverse square-root -// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root - -float Mahony::invSqrt(float x) -{ - float halfx = 0.5f * x; - float y = x; - long i = *(long*)&y; - i = 0x5f3759df - (i>>1); - y = *(float*)&i; - y = y * (1.5f - (halfx * y * y)); - y = y * (1.5f - (halfx * y * y)); - return y; -} - -//------------------------------------------------------------------------------------------- - -void Mahony::computeAngles() -{ - roll = atan2f(q0*q1 + q2*q3, 0.5f - q1*q1 - q2*q2); - pitch = asinf(-2.0f * (q1*q3 - q0*q2)); - yaw = atan2f(q1*q2 + q0*q3, 0.5f - q2*q2 - q3*q3); - anglesComputed = 1; -} - - -//============================================================================================ -// END OF CODE -//============================================================================================ diff --git a/Mahony.h b/Mahony.h deleted file mode 100644 index 37712f1..0000000 --- a/Mahony.h +++ /dev/null @@ -1,72 +0,0 @@ -//============================================================================================= -// Mahony.h -//============================================================================================= -// -// Madgwick's implementation of Mayhony's AHRS algorithm. -// See: http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/ -// -// Date Author Notes -// 29/09/2011 SOH Madgwick Initial release -// 02/10/2011 SOH Madgwick Optimised for reduced CPU load -// -//============================================================================================= -#ifndef __Mahony_h__ -#define __Mahony_h__ -#include - -//-------------------------------------------------------------------------------------------- -// Variable declaration - -class Mahony { -private: - float twoKp; // 2 * proportional gain (Kp) - float twoKi; // 2 * integral gain (Ki) - float q0, q1, q2, q3; // quaternion of sensor frame relative to auxiliary frame - float integralFBx, integralFBy, integralFBz; // integral error terms scaled by Ki - float invSampleFreq; - float roll, pitch, yaw; - char anglesComputed; - static float invSqrt(float x); - void computeAngles(); - -//------------------------------------------------------------------------------------------- -// Function declarations - -public: - Mahony(); - void begin(float sampleFrequency) { invSampleFreq = 1.0f / sampleFrequency; } - void update(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz); - void updateIMU(float gx, float gy, float gz, float ax, float ay, float az); - float getRoll() { - if (!anglesComputed) computeAngles(); - return roll * 57.29578f; - } - float getPitch() { - if (!anglesComputed) computeAngles(); - return pitch * 57.29578f; - } - float getYaw() { - if (!anglesComputed) computeAngles(); - return yaw * 57.29578f + 180.0f; - } - float getRollRadians() { - if (!anglesComputed) computeAngles(); - return roll; - } - float getPitchRadians() { - if (!anglesComputed) computeAngles(); - return pitch; - } - float getYawRadians() { - if (!anglesComputed) computeAngles(); - return yaw; - } - void getQuaternion(float *w, float *x, float *y, float *z) { - *w = q0; - *x = q1; - *y = q2; - *z = q3; - } -}; - -#endif diff --git a/examples/ahrs_calibration/ahrs_calibration.ino b/examples/ahrs_calibration/ahrs_calibration.ino deleted file mode 100644 index d03bb55..0000000 --- a/examples/ahrs_calibration/ahrs_calibration.ino +++ /dev/null @@ -1,86 +0,0 @@ -#include -#include -#include -#include - -// Create sensor instances. -Adafruit_L3GD20_Unified gyro(20); -Adafruit_LSM303_Accel_Unified accel(30301); -Adafruit_LSM303_Mag_Unified mag(30302); - -// This sketch can be used to output raw sensor data in a format that -// can be understoof by MotionCal from PJRC. Download the application -// from http://www.pjrc.com/store/prop_shield.html and make note of the -// magentic offsets after rotating the sensors sufficiently. -// -// You should end up with 3 offsets for X/Y/Z, which are displayed -// in the top-right corner of the application. -// -// Make sure you have the latest versions of the Adfruit_L3GD20_U and -// Adafruit_LSM303_U libraries when running this sketch since they -// use a new .raw field added in the latest versions (Oct 10 2016) - -void setup() -{ - Serial.begin(115200); - - // Wait for the Serial Monitor to open (comment out to run without Serial Monitor) - // while(!Serial); - - Serial.println(F("Adafruit 10 DOF Board AHRS Calibration Example")); Serial.println(""); - - // Initialize the sensors. - if(!gyro.begin()) - { - /* There was a problem detecting the L3GD20 ... check your connections */ - Serial.println("Ooops, no L3GD20 detected ... Check your wiring!"); - while(1); - } - - if(!accel.begin()) - { - /* There was a problem detecting the LSM303DLHC ... check your connections */ - Serial.println("Ooops, no L3M303DLHC accel detected ... Check your wiring!"); - while(1); - } - - if(!mag.begin()) - { - /* There was a problem detecting the LSM303DLHC ... check your connections */ - Serial.println("Ooops, no L3M303DLHC mag detected ... Check your wiring!"); - while(1); - } -} - -void loop(void) -{ - sensors_event_t event; // Need to read raw data, which is stored at the same time - - // Get new data samples - gyro.getEvent(&event); - accel.getEvent(&event); - mag.getEvent(&event); - - // Print the sensor data - Serial.print("Raw:"); - Serial.print(accel.raw.x); - Serial.print(','); - Serial.print(accel.raw.y); - Serial.print(','); - Serial.print(accel.raw.z); - Serial.print(','); - Serial.print(gyro.raw.x); - Serial.print(','); - Serial.print(gyro.raw.y); - Serial.print(','); - Serial.print(gyro.raw.z); - Serial.print(','); - Serial.print(mag.raw.x); - Serial.print(','); - Serial.print(mag.raw.y); - Serial.print(','); - Serial.print(mag.raw.z); - Serial.println(); - - delay(50); -} diff --git a/examples/ahrs_calibration_ble_nrf51/.uno.test.only b/examples/ahrs_calibration_ble_nrf51/.uno.test.only new file mode 100644 index 0000000..e69de29 diff --git a/examples/ahrs_calibration_ble_nrf51/ArdPrintf.h b/examples/ahrs_calibration_ble_nrf51/ArdPrintf.h index 092c6a0..de13f2f 100644 --- a/examples/ahrs_calibration_ble_nrf51/ArdPrintf.h +++ b/examples/ahrs_calibration_ble_nrf51/ArdPrintf.h @@ -1,50 +1,50 @@ #ifndef ARDPRINTF #define ARDPRINTF #define ARDBUFFER 20 -#include #include +#include -int ardprintf(char *str, ...) -{ - int i, count=0, j=0, flag=0; - char temp[ARDBUFFER+1]; - for(i=0; str[i]!='\0';i++) if(str[i]=='%') count++; +int ardprintf(char *str, ...) { + int i, count = 0, j = 0, flag = 0; + char temp[ARDBUFFER + 1]; + for (i = 0; str[i] != '\0'; i++) + if (str[i] == '%') + count++; va_list argv; va_start(argv, count); - for(i=0,j=0; str[i]!='\0';i++) - { - if(str[i]=='%') - { + for (i = 0, j = 0; str[i] != '\0'; i++) { + if (str[i] == '%') { temp[j] = '\0'; Serial.print(temp); - j=0; + j = 0; temp[0] = '\0'; - switch(str[++i]) - { - case 'd': Serial.print(va_arg(argv, int)); - break; - case 'l': Serial.print(va_arg(argv, long)); - break; - case 'f': Serial.print(va_arg(argv, double)); - break; - case 'c': Serial.print((char)va_arg(argv, int)); - break; - case 's': Serial.print(va_arg(argv, char *)); - break; - default: ; + switch (str[++i]) { + case 'd': + Serial.print(va_arg(argv, int)); + break; + case 'l': + Serial.print(va_arg(argv, long)); + break; + case 'f': + Serial.print(va_arg(argv, double)); + break; + case 'c': + Serial.print((char)va_arg(argv, int)); + break; + case 's': + Serial.print(va_arg(argv, char *)); + break; + default:; }; - } - else - { + } else { temp[j] = str[i]; - j = (j+1)%ARDBUFFER; - if(j==0) - { + j = (j + 1) % ARDBUFFER; + if (j == 0) { temp[ARDBUFFER] = '\0'; Serial.print(temp); - temp[0]='\0'; + temp[0] = '\0'; } } }; diff --git a/examples/ahrs_calibration_ble_nrf51/BluefruitConfig.h b/examples/ahrs_calibration_ble_nrf51/BluefruitConfig.h index 93d50cb..7506ec9 100644 --- a/examples/ahrs_calibration_ble_nrf51/BluefruitConfig.h +++ b/examples/ahrs_calibration_ble_nrf51/BluefruitConfig.h @@ -2,37 +2,34 @@ // ---------------------------------------------------------------------------------------------- // These settings are used in both SW UART, HW UART and SPI mode // ---------------------------------------------------------------------------------------------- -#define BUFSIZE 128 // Size of the read buffer for incoming data -#define VERBOSE_MODE true // If set to 'true' enables debug output - +#define BUFSIZE 128 // Size of the read buffer for incoming data +#define VERBOSE_MODE true // If set to 'true' enables debug output // SOFTWARE UART SETTINGS // ---------------------------------------------------------------------------------------------- // The following macros declare the pins that will be used for 'SW' serial. // You should use this option if you are connecting the UART Friend to an UNO // ---------------------------------------------------------------------------------------------- -#define BLUEFRUIT_SWUART_RXD_PIN 9 // Required for software serial! -#define BLUEFRUIT_SWUART_TXD_PIN 10 // Required for software serial! -#define BLUEFRUIT_UART_CTS_PIN 11 // Required for software serial! -#define BLUEFRUIT_UART_RTS_PIN -1 // Optional, set to -1 if unused - +#define BLUEFRUIT_SWUART_RXD_PIN 9 // Required for software serial! +#define BLUEFRUIT_SWUART_TXD_PIN 10 // Required for software serial! +#define BLUEFRUIT_UART_CTS_PIN 11 // Required for software serial! +#define BLUEFRUIT_UART_RTS_PIN -1 // Optional, set to -1 if unused // HARDWARE UART SETTINGS // ---------------------------------------------------------------------------------------------- // The following macros declare the HW serial port you are using. Uncomment // this line if you are connecting the BLE to Leonardo/Micro or Flora // ---------------------------------------------------------------------------------------------- -#ifdef Serial1 // this makes it not complain on compilation if there's no Serial1 - #define BLUEFRUIT_HWSERIAL_NAME Serial1 +#ifdef Serial1 // this makes it not complain on compilation if there's no + // Serial1 +#define BLUEFRUIT_HWSERIAL_NAME Serial1 #endif - // SHARED UART SETTINGS // ---------------------------------------------------------------------------------------------- // The following sets the optional Mode pin, its recommended but not required // ---------------------------------------------------------------------------------------------- -#define BLUEFRUIT_UART_MODE_PIN 12 // Set to -1 if unused - +#define BLUEFRUIT_UART_MODE_PIN 12 // Set to -1 if unused // SHARED SPI SETTINGS // ---------------------------------------------------------------------------------------------- @@ -41,9 +38,9 @@ // using HW SPI. This should be used with nRF51822 based Bluefruit LE modules // that use SPI (Bluefruit LE SPI Friend). // ---------------------------------------------------------------------------------------------- -#define BLUEFRUIT_SPI_CS 8 -#define BLUEFRUIT_SPI_IRQ 7 -#define BLUEFRUIT_SPI_RST 6 // Optional but recommended, set to -1 if unused +#define BLUEFRUIT_SPI_CS 8 +#define BLUEFRUIT_SPI_IRQ 7 +#define BLUEFRUIT_SPI_RST 6 // Optional but recommended, set to -1 if unused // SOFTWARE SPI SETTINGS // ---------------------------------------------------------------------------------------------- @@ -51,6 +48,6 @@ // This should be used with nRF51822 based Bluefruit LE modules that use SPI // (Bluefruit LE SPI Friend). // ---------------------------------------------------------------------------------------------- -#define BLUEFRUIT_SPI_SCK 13 -#define BLUEFRUIT_SPI_MISO 12 -#define BLUEFRUIT_SPI_MOSI 11 +#define BLUEFRUIT_SPI_SCK 13 +#define BLUEFRUIT_SPI_MISO 12 +#define BLUEFRUIT_SPI_MOSI 11 diff --git a/examples/ahrs_calibration_usb/ahrs_calibration_usb.ino b/examples/ahrs_calibration_usb/ahrs_calibration_usb.ino deleted file mode 100644 index 5bc5105..0000000 --- a/examples/ahrs_calibration_usb/ahrs_calibration_usb.ino +++ /dev/null @@ -1,140 +0,0 @@ -#include -#include - -#define ST_LSM303DLHC_L3GD20 (0) -#define ST_LSM9DS1 (1) -#define NXP_FXOS8700_FXAS21002 (2) - -// Define your target sensor(s) here based on the list above! -// #define AHRS_VARIANT ST_LSM303DLHC_L3GD20 -#define AHRS_VARIANT NXP_FXOS8700_FXAS21002 - -// Include appropriate sensor driver(s) -#if AHRS_VARIANT == ST_LSM303DLHC_L3GD20 -#include -#include -#elif AHRS_VARIANT == ST_LSM9DS1 -// ToDo! -#elif AHRS_VARIANT == NXP_FXOS8700_FXAS21002 -#include -#include -#else -#error "AHRS_VARIANT undefined! Please select a target sensor combination!" -#endif - -// Create sensor instances. -#if AHRS_VARIANT == ST_LSM303DLHC_L3GD20 -Adafruit_L3GD20_Unified gyro(20); -Adafruit_LSM303_Accel_Unified accel(30301); -Adafruit_LSM303_Mag_Unified mag(30302); -#elif AHRS_VARIANT == ST_LSM9DS1 -// ToDo! -#elif AHRS_VARIANT == NXP_FXOS8700_FXAS21002 -Adafruit_FXAS21002C gyro = Adafruit_FXAS21002C(0x0021002C); -Adafruit_FXOS8700 accelmag = Adafruit_FXOS8700(0x8700A, 0x8700B); -#endif - -// NOTE: THIS IS A WORK IN PROGRESS! - -// This sketch can be used to output raw sensor data in a format that -// can be understoof by MotionCal from PJRC. Download the application -// from http://www.pjrc.com/store/prop_shield.html and make note of the -// magentic offsets after rotating the sensors sufficiently. -// -// You should end up with 3 offsets for X/Y/Z, which are displayed -// in the top-right corner of the application. - -void setup() -{ - Serial.begin(115200); - - // Wait for the Serial Monitor to open (comment out to run without Serial Monitor) - // while(!Serial); - - Serial.println(F("Adafruit nDOF AHRS Calibration Example")); Serial.println(""); - - // Initialize the sensors. - if(!gyro.begin()) - { - /* There was a problem detecting the gyro ... check your connections */ - Serial.println("Ooops, no gyro detected ... Check your wiring!"); - while(1); - } - -#if AHRS_VARIANT == NXP_FXOS8700_FXAS21002 - if(!accelmag.begin(ACCEL_RANGE_4G)) - { - Serial.println("Ooops, no FXOS8700 detected ... Check your wiring!"); - while(1); - } -#else - if (!accel.begin()) - { - /* There was a problem detecting the accel ... check your connections */ - Serial.println("Ooops, no accel detected ... Check your wiring!"); - while (1); - } - - if (!mag.begin()) - { - /* There was a problem detecting the mag ... check your connections */ - Serial.println("Ooops, no mag detected ... Check your wiring!"); - while (1); - } -#endif -} - -void loop(void) -{ - sensors_event_t event; // Need to read raw data, which is stored at the same time - - // Get new data samples - gyro.getEvent(&event); -#if AHRS_VARIANT == NXP_FXOS8700_FXAS21002 - accelmag.getEvent(&event); -#else - accel.getEvent(&event); - mag.getEvent(&event); -#endif - - // Print the sensor data - Serial.print("Raw:"); -#if AHRS_VARIANT == NXP_FXOS8700_FXAS21002 - Serial.print(accelmag.accel_raw.x); - Serial.print(','); - Serial.print(accelmag.accel_raw.y); - Serial.print(','); - Serial.print(accelmag.accel_raw.z); - Serial.print(','); -#else - Serial.print(accel.raw.x); - Serial.print(','); - Serial.print(accel.raw.y); - Serial.print(','); - Serial.print(accel.raw.z); - Serial.print(','); -#endif - Serial.print(gyro.raw.x); - Serial.print(','); - Serial.print(gyro.raw.y); - Serial.print(','); - Serial.print(gyro.raw.z); - Serial.print(','); -#if AHRS_VARIANT == NXP_FXOS8700_FXAS21002 - Serial.print(accelmag.mag_raw.x); - Serial.print(','); - Serial.print(accelmag.mag_raw.y); - Serial.print(','); - Serial.print(accelmag.mag_raw.z); - Serial.println(); -#else - Serial.print(mag.raw.x); - Serial.print(','); - Serial.print(mag.raw.y); - Serial.print(','); - Serial.print(mag.raw.z); - Serial.println(); -#endif - - delay(50); -} diff --git a/examples/ahrs_fusion_ble_nrf51/.uno.test.only b/examples/ahrs_fusion_ble_nrf51/.uno.test.only new file mode 100644 index 0000000..e69de29 diff --git a/examples/ahrs_fusion_ble_nrf51/BluefruitConfig.h b/examples/ahrs_fusion_ble_nrf51/BluefruitConfig.h index a7d99be..55e3691 100644 --- a/examples/ahrs_fusion_ble_nrf51/BluefruitConfig.h +++ b/examples/ahrs_fusion_ble_nrf51/BluefruitConfig.h @@ -2,37 +2,34 @@ // ---------------------------------------------------------------------------------------------- // These settings are used in both SW UART, HW UART and SPI mode // ---------------------------------------------------------------------------------------------- -#define BUFSIZE 128 // Size of the read buffer for incoming data -#define VERBOSE_MODE true // If set to 'true' enables debug output - +#define BUFSIZE 128 // Size of the read buffer for incoming data +#define VERBOSE_MODE true // If set to 'true' enables debug output // SOFTWARE UART SETTINGS // ---------------------------------------------------------------------------------------------- // The following macros declare the pins that will be used for 'SW' serial. // You should use this option if you are connecting the UART Friend to an UNO // ---------------------------------------------------------------------------------------------- -#define BLUEFRUIT_SWUART_RXD_PIN 9 // Required for software serial! -#define BLUEFRUIT_SWUART_TXD_PIN 10 // Required for software serial! -#define BLUEFRUIT_UART_CTS_PIN 11 // Required for software serial! -#define BLUEFRUIT_UART_RTS_PIN -1 // Optional, set to -1 if unused - +#define BLUEFRUIT_SWUART_RXD_PIN 9 // Required for software serial! +#define BLUEFRUIT_SWUART_TXD_PIN 10 // Required for software serial! +#define BLUEFRUIT_UART_CTS_PIN 11 // Required for software serial! +#define BLUEFRUIT_UART_RTS_PIN -1 // Optional, set to -1 if unused // HARDWARE UART SETTINGS // ---------------------------------------------------------------------------------------------- // The following macros declare the HW serial port you are using. Uncomment // this line if you are connecting the BLE to Leonardo/Micro or Flora // ---------------------------------------------------------------------------------------------- -#ifdef Serial1 // this makes it not complain on compilation if there's no Serial1 - #define BLUEFRUIT_HWSERIAL_NAME Serial1 +#ifdef Serial1 // this makes it not complain on compilation if there's no + // Serial1 +#define BLUEFRUIT_HWSERIAL_NAME Serial1 #endif - // SHARED UART SETTINGS // ---------------------------------------------------------------------------------------------- // The following sets the optional Mode pin, its recommended but not required // ---------------------------------------------------------------------------------------------- -#define BLUEFRUIT_UART_MODE_PIN 12 // Set to -1 if unused - +#define BLUEFRUIT_UART_MODE_PIN 12 // Set to -1 if unused // SHARED SPI SETTINGS // ---------------------------------------------------------------------------------------------- @@ -41,9 +38,9 @@ // using HW SPI. This should be used with nRF51822 based Bluefruit LE modules // that use SPI (Bluefruit LE SPI Friend). // ---------------------------------------------------------------------------------------------- -#define BLUEFRUIT_SPI_CS 8 -#define BLUEFRUIT_SPI_IRQ 7 -#define BLUEFRUIT_SPI_RST 6 // Optional but recommended, set to -1 if unused +#define BLUEFRUIT_SPI_CS 8 +#define BLUEFRUIT_SPI_IRQ 7 +#define BLUEFRUIT_SPI_RST 6 // Optional but recommended, set to -1 if unused // SOFTWARE SPI SETTINGS // ---------------------------------------------------------------------------------------------- @@ -51,6 +48,6 @@ // This should be used with nRF51822 based Bluefruit LE modules that use SPI // (Bluefruit LE SPI Friend). // ---------------------------------------------------------------------------------------------- -#define BLUEFRUIT_SPI_SCK 13 -#define BLUEFRUIT_SPI_MISO 12 -#define BLUEFRUIT_SPI_MOSI 11 +#define BLUEFRUIT_SPI_SCK 13 +#define BLUEFRUIT_SPI_MISO 12 +#define BLUEFRUIT_SPI_MOSI 11 diff --git a/examples/ahrs_fusion_ble_nrf51/ahrs_fusion_ble_nrf51.ino b/examples/ahrs_fusion_ble_nrf51/ahrs_fusion_ble_nrf51.ino index efbd1a0..8ec8e63 100644 --- a/examples/ahrs_fusion_ble_nrf51/ahrs_fusion_ble_nrf51.ino +++ b/examples/ahrs_fusion_ble_nrf51/ahrs_fusion_ble_nrf51.ino @@ -1,8 +1,5 @@ -#include -#include -#include -#include "Mahony.h" -#include "Madgwick.h" +#include "Adafruit_AHRS_Mahony.h" +#include "Adafruit_AHRS_Madgwick.h" #include "Adafruit_BLE.h" #include "Adafruit_BluefruitLE_SPI.h" #include "Adafruit_BluefruitLE_UART.h" @@ -75,8 +72,8 @@ float gyro_zero_offsets[3] = { 175.0F * rawToDPS * dpsToRad, // Mahony is lighter weight as a filter and should be used // on slower systems -Mahony filter; -//Madgwick filter; +Adafruit_Mahony filter; +//Adafruit_Madgwick filter; void setup() { @@ -257,4 +254,4 @@ void loop(void) delay(10); } -} +} \ No newline at end of file diff --git a/examples/ahrs_fusion_usb/ahrs_fusion_usb.ino b/examples/ahrs_fusion_usb/ahrs_fusion_usb.ino deleted file mode 100644 index c2f397b..0000000 --- a/examples/ahrs_fusion_usb/ahrs_fusion_usb.ino +++ /dev/null @@ -1,167 +0,0 @@ -#include -#include -#include -#include - -// Note: This sketch is a WORK IN PROGRESS - -#define ST_LSM303DLHC_L3GD20 (0) -#define ST_LSM9DS1 (1) -#define NXP_FXOS8700_FXAS21002 (2) - -// Define your target sensor(s) here based on the list above! -// #define AHRS_VARIANT ST_LSM303DLHC_L3GD20 -#define AHRS_VARIANT NXP_FXOS8700_FXAS21002 - -#if AHRS_VARIANT == ST_LSM303DLHC_L3GD20 -#include -#include -#elif AHRS_VARIANT == ST_LSM9DS1 -// ToDo! -#elif AHRS_VARIANT == NXP_FXOS8700_FXAS21002 -#include -#include -#else -#error "AHRS_VARIANT undefined! Please select a target sensor combination!" -#endif - - -// Create sensor instances. -#if AHRS_VARIANT == ST_LSM303DLHC_L3GD20 -Adafruit_L3GD20_Unified gyro(20); -Adafruit_LSM303_Accel_Unified accel(30301); -Adafruit_LSM303_Mag_Unified mag(30302); -#elif AHRS_VARIANT == ST_LSM9DS1 -// ToDo! -#elif AHRS_VARIANT == NXP_FXOS8700_FXAS21002 -Adafruit_FXAS21002C gyro = Adafruit_FXAS21002C(0x0021002C); -Adafruit_FXOS8700 accelmag = Adafruit_FXOS8700(0x8700A, 0x8700B); -#endif - -// Mag calibration values are calculated via ahrs_calibration. -// These values must be determined for each board/environment. -// See the image in this sketch folder for the values used -// below. - -// Offsets applied to raw x/y/z mag values -float mag_offsets[3] = { 0.93F, -7.47F, -35.23F }; - -// Soft iron error compensation matrix -float mag_softiron_matrix[3][3] = { { 0.943, 0.011, 0.020 }, - { 0.022, 0.918, -0.008 }, - { 0.020, -0.008, 1.156 } }; - -float mag_field_strength = 50.23F; - -// Offsets applied to compensate for gyro zero-drift error for x/y/z -float gyro_zero_offsets[3] = { 0.0F, 0.0F, 0.0F }; - -// Mahony is lighter weight as a filter and should be used -// on slower systems -Mahony filter; -//Madgwick filter; - -void setup() -{ - Serial.begin(115200); - - // Wait for the Serial Monitor to open (comment out to run without Serial Monitor) - // while(!Serial); - - Serial.println(F("Adafruit AHRS Fusion Example")); Serial.println(""); - - // Initialize the sensors. - if(!gyro.begin()) - { - /* There was a problem detecting the gyro ... check your connections */ - Serial.println("Ooops, no gyro detected ... Check your wiring!"); - while(1); - } - -#if AHRS_VARIANT == NXP_FXOS8700_FXAS21002 - if(!accelmag.begin(ACCEL_RANGE_4G)) - { - Serial.println("Ooops, no FXOS8700 detected ... Check your wiring!"); - while(1); - } -#else - if (!accel.begin()) - { - /* There was a problem detecting the accel ... check your connections */ - Serial.println("Ooops, no accel detected ... Check your wiring!"); - while (1); - } - - if (!mag.begin()) - { - /* There was a problem detecting the mag ... check your connections */ - Serial.println("Ooops, no mag detected ... Check your wiring!"); - while (1); - } -#endif - - // Filter expects 70 samples per second - // Based on a Bluefruit M0 Feather ... rate should be adjuted for other MCUs - filter.begin(10); -} - -void loop(void) -{ - sensors_event_t gyro_event; - sensors_event_t accel_event; - sensors_event_t mag_event; - - // Get new data samples - gyro.getEvent(&gyro_event); -#if AHRS_VARIANT == NXP_FXOS8700_FXAS21002 - accelmag.getEvent(&accel_event, &mag_event); -#else - accel.getEvent(&accel_event); - mag.getEvent(&mag_event); -#endif - - // Apply mag offset compensation (base values in uTesla) - float x = mag_event.magnetic.x - mag_offsets[0]; - float y = mag_event.magnetic.y - mag_offsets[1]; - float z = mag_event.magnetic.z - mag_offsets[2]; - - // Apply mag soft iron error compensation - float mx = x * mag_softiron_matrix[0][0] + y * mag_softiron_matrix[0][1] + z * mag_softiron_matrix[0][2]; - float my = x * mag_softiron_matrix[1][0] + y * mag_softiron_matrix[1][1] + z * mag_softiron_matrix[1][2]; - float mz = x * mag_softiron_matrix[2][0] + y * mag_softiron_matrix[2][1] + z * mag_softiron_matrix[2][2]; - - // Apply gyro zero-rate error compensation - float gx = gyro_event.gyro.x + gyro_zero_offsets[0]; - float gy = gyro_event.gyro.y + gyro_zero_offsets[1]; - float gz = gyro_event.gyro.z + gyro_zero_offsets[2]; - - // The filter library expects gyro data in degrees/s, but adafruit sensor - // uses rad/s so we need to convert them first (or adapt the filter lib - // where they are being converted) - gx *= 57.2958F; - gy *= 57.2958F; - gz *= 57.2958F; - - // Update the filter - filter.update(gx, gy, gz, - accel_event.acceleration.x, accel_event.acceleration.y, accel_event.acceleration.z, - mx, my, mz); - - // Print the orientation filter output - // Note: To avoid gimbal lock you should read quaternions not Euler - // angles, but Euler angles are used here since they are easier to - // understand looking at the raw values. See the ble fusion sketch for - // and example of working with quaternion data. - float roll = filter.getRoll(); - float pitch = filter.getPitch(); - float heading = filter.getYaw(); - Serial.print(millis()); - Serial.print(" - Orientation: "); - Serial.print(heading); - Serial.print(" "); - Serial.print(pitch); - Serial.print(" "); - Serial.println(roll); - - delay(10); -} diff --git a/examples/ahrs_fusion_usb/sample_config_data.png b/examples/ahrs_fusion_usb/sample_config_data.png deleted file mode 100644 index 02c3c49efce9ca460c5152b651c9cd3b18843e34..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 219474 zcmdpdgwvNszVj!B~XwEkf5NTP^2WqK0`slN+qJ4!7euIIK%C#{Q@v%((ycI z>jW7~!-p!ew5iqzv3eEF8Y_iK@paE~58v5{R1roj3*qn!Tq@;Tj?K;7S9z6>t9wT- zU+C@_<&m_Xd7t#9QbBQ!P$C=TV;j=Ex9Fs>P{?Z`)a+39c4Vto4YF_8R?v-f5#OM1 zAR?vZc8emV<#$U-r{o2qhulI%585HK|cdCu+7Kh9r1%kxaY-KFY zS`B1roHVRVJGA-0p%HrQyk6iCQ}hnCc;v0F>IhmWaojvr3@ugE*+DJ!dKho_rRepx zOhPsNjStb4n?Aem=Pf+np}2xie%nqS*@pU?kkDAH0q4#T(=J5)TchlnepUAF5Li|D zcQtkIl(I`$At3 zMKY58kSqxrpBveDp5a>+o zX_}zYgd^DTu0;J(5YPs*S^0jADDUHn3c_LjZ~%UmhNZ@43rR@vuU3>&p=F5M7XjyE z7SpI4blwEq_B0sTYT&wJTf=olSAJI}iO`H$e-{$Zg_j-y-*4ED((lyI1!dC48`h5W z0jc*BrYNeuxOum7xP*Bq&luKj#T#4&C~WgAtMK-W9Dzmj$BGjH{4%9yT>Eyfjth1J z>f>*&C`%m|hifELi_jveFcK{EDreXdZ+`R)PXzK0zfOL|*kqmdh4B>Dm+W=F0DgrA zrX&JKymcI!`8&c9m~c^gIt1$a~@H#h*dOS9^x$= zZ$z5d7-jn)a~>(a*prx04xY5Qi<0s*e0qpyuIzgxxetZ8yt_W0?{jp zo(Tu}s_&EzLp-Pe9Kb68bp`xvh;>(bzi!v%<~Mu&Q|vax6^xT`^Yy7y-kbTG&)#o+ z`Jd3A-aHZbLOmynknQ%|T~ml*P9io3HU}mIjs~^|Vg>4Tf9!r2Bl(_!5A!k9L5xdD zoQWDhbxcD-t4D*1z8d#la)(O&GY@?L6$LZ7YK&_vFoq?LBu;#~Zn_NY4c?e;vif9I z3T`N_FV+1_s7RY<)K_9BKVU^hF*oPUUv9__dg|-C~#9az%igflr zSTWZJd8XWbR+gL6iYw;*SgTPheeq?7dK98%rNyO1u4PjWr&X^NTo157v7V~at=p`- zs8_c-nHH*i6bmjg&c!O|0n<-d{^ZTSi2gQFWIs%P`tkYk6xcFs+xl)I&Mq8UHXr&O`V%4-g^wE$ ztu_o|4cKS%y7E9KbJHX5yH#vjCVs{5IdS;ZlGWCD0CL& zi(|=CpHi3#W|C#1VBW%U!CA(kOl(LTN|a%`)>^6k+<4wF+)z@tUqwJ*CnRL{(010^ zzuKTyd)2U`ZC7<%=WA|k9cNX$Q~=%yEzf2KHO#pt9qICi>1Hi6wR*OeUcq|V-3#20 zUJ0TW1q8#aX3wn0Qtt2W(b+E@&hftz?lS*s@!>I$P~L>LKskGgrO?;h2Vw!C9xESX zr3GdtvpF2~j)m&uk-Q-{Cfo#u13@N9)GS9Vel2`Wjyl%5l`Tq3-OD&F_08>$ZqATq zJBQ9a(Tk8XjpK>+v-v5I^2Yoj?=I&Gy3dH+Vs7nah2YBOsdig8i z_W1g-XMBit+^%pnPO2f!J+48{bJuQf{HpTe1UU=A1pWd0C$0s?AZi(!H@eB&UX%rr zU&)r^Bc{h@9dFEFWxk@pbt0dkq>wsNU?WGqW=1|jokEmBEk$f41>k33bufCO;olP1__yzae~3U1m6!iJ)X9vl(vd`i@p~jOrTE0?q1=&H**|mNp7v4sm__3 z;Xxk=)5djUUE%Uod#F@?t-Mh?}}lj1PT)5TZNWg@6z@l z=6K`iV?2DyPBdOS{<7X?Ry$)O3Wq$df?hn~3H9{WAz0n>KRo(THq;yuJf7N+RyJ*( z55o>=d7pR>9N};M9~hpTL_@N~PZ_w`-K>vW+nU;lJ#xEM)>phg`FDS+`l2U2?$|!NXe7 zi8+bcYQEO`+Me1c>qEi(3y%wEkNXb?KuR15tEhcqT_4#;jiKs^&Ax$Pg%AY+;S{HH z!+{YXf8nIOuAtzy^L0uQ2W0G9rXYCeP{4QWc`4?i1A?Z1+VRtK;=)KKNn$p8Rlt{j z`e=UHap>T)c9epG*Gb-raS{w`W*esG_Mz$wIDFQq@={Ns!}p@Uj?jm@nLBd{bH&r8 z_4H~m{gd078|c__xwOU3vGYm)>Um)iGVfL=T-SLZx)H#S#*3Eu$ny9&B{D=goLe%m z6P23LB*e>(Cp35Ayg%h{zF|%|E~9VJIrnSwc)LsZ>(efQG$DaIwFl=NWO!D*(yh(G zZ;Fjb*!$V`X)(sl^dxeH+xPV8=Pldi=4Q-%W=Lj<@S-2!8S`@c*y3roD4E%iu@V~3 z#=?~g%J2BgNw71Nh2W{Qlxn+Dd|=Uvsx<5qV(AK-^jGdAKKB#3pzFyZQ>f`*Fb0cn zjvAoQ6<(1IA!Gpns|$EiwaYrH4TD{$R*rtozv@w-dR?Hr^*H$WJ`3~RHNS%Q!u^6p z0bYC!#k(Y?*bnsp^GIkUudvEsRX+v=^(wuGrrGa;(s@Pxf7(YaCWxmV`X)7b7OJiV6k&FXJzB%xVwSe10H>ERgxKEkatZv|;2*F4Z^-{> zs`-CSxjEkdXUqS1^LI-D);}cp4~hO#*Pl;c^d*EO!1{093n6iCOR7Rai9kt-iK@82 zI&4QaQ0cpUdKQ89?;RwDeoY52$6(QnL=i@Z8-r9wXT(%QCKnFJpcZ6BXxj;`#-R8Z z@B|waHr(e(-w&NY5kiKmBpQIJQt<)qt??J?#^?KtWvQ`@w07!LdoOrb^PP0Jm6Y4G z+IfzXu@snh(NKv0e_UymuqA1gFv4=1G$&KA8KbfPBiIj3>8xF*qifAsTlu*jVH15e&1Hmpg!mwnuK%O z(|maqj8xD6it$2?{>neh(MlzL`Smw7E^sXv1AWw2VoGfu2yGqnKk9qA{jo=jE(Z~R zZ>x%wQaj3v9{D8R^X+j>Y%yb*YwCBsv-n%^Q|B165^!}B`!)X>OC0j?xYNvNL27Kf z1i5_CNP(67^1oM(SXSFu*!eW8!ZIC-a8nA0&$)iaQ$jvKb03yg7D0wih>7+eihLa< z@`(q3*r=AtW#lzTd3LTSx`~1adScf?^Zu<=yQK4xF@v>WD@uXXKgN^H%0Y|=<750u zwaNTK6hf4Cl`OW~?;eDOgg?e=9=ZX9SSi>30!uz)zhU}zLq#yR+ z8PU`V3_d0Vmtu{HA{Ca~A1Vg_gM+mtDs<*xQ6AS1d$51dOVFq^Kkk0Yv982T__dc& zBr)mxZn-8tAs>k4`HoOtcjx!o3p_A+U4UD}6s%(r`Mv*Ge8T zT#*NU3VTCg&rs`Lk!-+JqWb0VAg+p1X;n8=i z2d3g0!<527Fc&n}d%JAXwbj>894g{UWHs^|uUQC7;erG^=@!RtI@ab8wuR^wb&|m9 z;J>LccQ8LCK1%Pj1G9(UEQqQyTcKRxY$`k5V@VkeR3?$qa{*&~ZZ{kKj$5Wty)m}6 zwM9~I1-`RPU{H-6{uG(;8>3qzqES>)ao(M)HYPPQH?KTiZoMw0l~21-`sO9Aw=Yo5 z&vg_63(L6u>UjD7+2wHVOv)j4>ou}VY_e2+=v$?% zx?0%_g2Ow#(AJUol)3T@dPem!MkaalDt<0m;SWP~OS^MZTB|Ix)qU-kGuoE8y3P}J z0wieX7Z-a(O44us>0PMM1HZ5^{p771%Xg74cd}NREoXGDu+8)$WW2g<7A)TuU)>d_ zsGTkTS$90Dq|}A-rJcFav5-k)MQg(GuLI zlu`tFZ0A73X%(*#Lj5s|lmXlFnpJJ|9MuiRlUEv3Y#T&UNao`)InO=;-IoVSr%!6w zW+ydwdYsK~jVb_9CAzIS(mn8rOiPX3SO`ka7H~*UjW|KVho=jzRh&iydch1*?Mn4# zarSbWp1}gaRd>6K?k9`aRUF))*nFzIjqfe9SrYApG1vn>=9JLVrhm96o=8}v3jw+! z90Z>-f{%5GTU~Lu0Zmq(M`~yO12r4?wQzqrF@KJLFJtBTw4R0E#_C6xwE1xd$#eMn z*^Csd(-l3qi4*1nroOe8$y##a9ia~wXur&MsfFF|8Us0&KE>vx>s`q5-#;RK1k>!EQxPsS`A)+rHIjjP`n)brr$jggQ$SHFEdOeso#euat2 zA_6AxOie5k<=Ybl97o*)6Ltj$k9;SYn1m2!1*70@eb}zPneo)EdkCCGVc|WGXuKC_dDVFj zGLP*b9BtE2S0XX)BLbxbWEw*JH$#{&IT8hQ**fSeTG~P{r*t*pjm=dP@5(;@xhmTG zVp&Y)Nrj=`WVVfnm-oNQF_2xrUj%i_m1e*jgHjnENlMzBBgtYv>$i(K_t4kyGc5gD z9$q#XYjGuxL&dR9xny9P*3N}S(B=J1HWrgtd7Z2EnNkV6L#S7^Pt&mr4wp=R7&TOW zq|)!LBXwxKqgWcHRCQ*KmTtAWhGSdFOoW8d2WYE@Q~DPo!+m3N_1N8E3>TnHWi_FT zRj42*#0yDbG|;Mu{&CUQrZN9wt*;Xz9s48rJM|wk{v`(U_P)K6araS|kaai1`_7Z- z>D}Rqs^@t@1}~5tmKS)l=6Z3p9<(agZ;B=ybUfPDg5o=gp=52L6QeEw| zlRI+%e1WOE)eE*C?nBUXadKpC~6&-Z&vexC5rSp&#Lh+UhFhXQ@3x40Zh4-u$6@L9=_F(7 z^1bu6Zt^4pJ<~u;>MMT6M#tg5oh2Ep|3-7eM+Nf|tsR`w68b6UthIton%Y@3RlqDt z3a}x7N+V#w!Q6iM&?AnkdWLgPv3jB$bN`B|(8K1n&;V7(qg|f1VawRQ4HuKI+ygdhA3yZQsSw^={PnF&DQhok*bU8;gNv z+das*LSa+2_y2VQGfq3h%=3|8b?<$bz@Mw6NH1&{x^k}M!$fM;?S*gCC9R7L(;(Gt z`!+(Ea37nh>cE2%i_)2lYPr=O_N@^aPC0;xf#uDmTX4~VIh{%YdS1Jv0#>x3) zmEEYb?20{g2El53uTtJ7!zNu`NrpR4Df@Q=&c7VdMe3I^t5I(qDGRMm-4A_$7T1&l zPCWjVwCiO#Gu9|AzVE1*M=zg4Z6|*Ig2vXU-g*+?K&B~)AT_aLJ7dc^!*;3rKK@O& zTUsARcH@dSZOf-eJ7#)Uskg))vn}QQTD&>n%RXj~ z{nN2SdySfl2EL0?mvZlsqkMw6ab>%PquNJZ+Dxh7FD(OZ+5+4k{X-Sc1{8ojIgBSi zrmkH+%m`=p56FEpv@lyfvohuFpU*p%BmFwr>fIx_A2u4B^6yO(r>NI%^7-{z zSJ#H~KDvK|x+LYs=bl%u-SUYZw*?i)VQ~;uD!DzQNUi`{KSpcx0m*WsVB~^j7fF8-R@MFq#W?W z?xY1SiJGLm*Vxhp?5PYv4Kq>#^ZAOCY^7l&P-a#Rl=}G*uMmT^)^R(Vv6ht&v=dNh zBk}*9p;>QWosVtx0N_hxanQ06*e!A1^!to~a~tnTYwAcm0wV{XVc&#vbRalOK?=bD z?W#>GRpU~2ff<#mb}JiDJ%OTG%4K)h8gj17lpGH4VzKLxkU-VK8d~pR9m3htLT(Li zxok65cIr=*es5bYjUgO*DD&A}lFJUoP=VVd(r)^v`mA-soXqD>zVH|I+4r%B4}2gk z@xv)2u|Iveq8W71AirMVf!_+Q^@>KILdWsftH@qM^0=e&XD$DJ;uZ?S3(vIJ&h?<% z=N{qb)AuuV`=R%w$6vn-`+oBn7m5n@B?>JT?j)Lxy5n8(xk7O!bro*Wn|{p}bUQfj z26cb1rRi7e_Uy%wF%Ii{c7WjUX<2!$%77r_si*PgQQt4rO!eZl$KUO2j2_45Z3(_JB zk7%2d$iVd@DURqfT@0GXE6+W35}{`cUf;5~Z^5Jop~jiz0}-)64omsyv&KX-@G+9NUc2xysSoA;Oy%*l?l$kkTcOyK z0eyYFaRt=>~OFP+KS(;CDSUH*!U?Ki0nJk|FyF{Lfx9yP;8dwJT;I{vaN9r zdnf&ef0T36dHC11urO4Ep`7qD>-ECRol$rEs0R&VWrWu2qrm~0(}!5Mv+#S;E`Zyh|N&2%*x%GZPNyYF8d_n3oIdOX#9%^jC+uIj~A?<7u-Kdngw%wyowmv`@C}V z9kBb(55-a7mR)|W7lXb+ovN|4HwPe%CYw6*5<{x>Nf~0=Jk*CflSZQ^+nb|-DomIF z1lFg%XboLKoThSlV1&x0XF;5F--|cS)=nM*#7Hb{Z*=*fo`O0ewYX5f+e{A-7CAyIec1T9qIFG&U(GQko*@jd+-)T@Z1(#4RSv z9)=T+DFh!Tyrp%dHoFvCDJ#X`+^)|DUxsoiE~8(ulzQ-X@Ho6~Aup|mgt#Eh1G28_ z9rl|LN(hJbqAO}c{$w^Q`AdZWI<1rv#e&O8fXCEx0E~~;`T)v>;`AL!ofTdb%4fi1 zjXpM|gRV+x4kKP0yw!9Ca}BG*(gM#kcj)-+Tgn!sK5OkG+#SefU@yx4Aj2nRUK-TP zNLx+8tZg>-nClt1l0NXKi5RRwET8%v(vs}k1nxCGk8Ka&=Ab`Qo8Tj9@|8ES0B=D) zXTj(Njp2oWS2@?6DLo_dx#Dya{+1ceDi5Z;l(7SpCL_njgzMn)+{M0(`$i0R*)TDn z1*`Gbao`R5W~bu7hWYGDLtZIeXOzQMus0RB+Nblj`0d6)l$znWjNPr&;(M%blWvu9 zy{T6f(dfg&QyX+%e)B*%?{*xD6((Tj2Mu`!iB$oKnkxINi@A;VxPe(c!YxM1&FJEI z<2~C2I~xWh&#^6|)dm>J<0V-&SSdedEH;ak7EaW*7Bu0jw%(|OM!1f+zaT{sG1y3ft(xRoo2n)IZg#I*{^r+>^~{u&b0voLI0gq*JuQ2EY1F;yvf@=8;orO1 z?AL>NdMYpFLyC{Fz$OyAb>ULA^*R2Ulf5PohW0OJdC6u@kA$I`vPzK-PW#K2e(=i?v#$*i? zq!%kb#S^+2Zw;|@f~l|~ikjQ!jB%FY|Mj?CICqYw$);qVQm;QC*E#%ynci$_>Vvxg zT#=e?y69vq4_sM8Sw_gnjO&Lf#+a*n^LJuItOFhMLF$EV5gwtDY&oVOXGt~I_^iI+ z<*Q3Aku*+INliKGAfx8v(HhGx8J^?^r#DSGPS6|RUn z6t9I@JLEbW+x=|_XZrooGZhA8TfM}N#JlNb3&iXj8c{9$soYBSY!jF9Y;JYiRi|EG zb6`?j^qwVvk(Z_BEA1(-GE7o~-B&+fZ>Yi+&P(2(NY&4^ME6lnm)Lz3Jc>_Y_d1ldUTLfA zkh<^N$zfO2alZufOm1Lq5%ceGX4gm3>uZ5jBwS$T+0MV-ac@{8lty0%%wb7{m`c+h z$Q*^r{_$3>UF6KAzG6W2mi|WRzVH%Ej+tA{%B;z(ObkXb33goV%RkwO78neGK#lvK zj`>61wrUaT9`Ao;PDz;qH=!+XCPa#DzodJAJ{RddW7e@O1exP>1O%)?*0h_qw=$*u4g9DEK`<-lF<@mVE<+y`iM-dG+o zSVgK`T5Gi=X5<5aDQXE|6198rf`$@uNRO(!<+s0Q z%G69})#lpuhQ>3Fc7AysBMndVwu{4GB_E_ntO-9*bT!S3V)1IMj!#n-{!nmiE)I`FVMHQc}b1(98`(NkBOS zdiMz~OpkZlc-kRO1v8(D=@u>-)Y>`;S0Ua}l?@f$OU$2kr#gb%a`if$=+QZbVKNm= zK5_{lxTB`6LcWZAa8cX8!gP>qo^S|PHT$~2-Ic*rBT~Jmo^>959;PF@K@`Ga$A>Eo zV4bZSO0CoGXex6bs<9l!pN-2OZhU%kpTzPppj}^6q4Xtk<=nO99Pk_I;~r%d&)&rj zt*~3Jo|2a8@TA<*b>_Z0@j|>*@U;;v7w0wsXElPicAi2gn=o%jj}uGx#cNhe>;xO~ zmF~(#ZD8IM3&U3WUN8tCc)>Cd4gWE#g?vD}1yTC1pj#S)E`CwVq!poE zPE_wwxl)|JEtt<|fpQ{NRWxUMf;RlEn)O%m&6AJyq0eXvwwgAYR!bh}B<=N)CtSg> zbp+1DD_XxOGH&dlp3V(uRg#1^S0cHMf10gjzAHL~YZKUh_HMTb_Iim*zN<`W^C6Y{ zh);6^o;q-Gq_*AXceU@=XHR%^?o$yQHZBX#&Zn8Fsmt%z+yWM)^h>0*qolQKPdAkD z`)pCXsw&GQqZ6nc`O!?q&oNuM;BzJ*9j}rvpY{5UpU>3fI*w6)DHJnqO8h*7B-Ln7 za>iLr8@?0A1$Y0N)el6=#-=t_ymNO>9CbjB3G}t(-bnHA8%PY&a;AjWnZ@JxCal#` z*gea4QC8+aeMM*KK`@q&aH`U8yt1=^^5aHZ*(K||Q*0JgLr_8BOxggdPHWPQGBy6S zN2$hgc*?F_N#GOUA($n|UboZRHBf3}DNOw{~OM&lPvzq<~ndldSnTv#;;kZbsurwE=T za2C5I#xhGAYGm(x_g^_idr!oz?IAt#nqF3Uz-Y*OY-!zjENnJ#iDoz|Wx3t# zIKKllNp-Llr-P{6nE}t&2I>x6O~lVFBiZ|d!&5#2MvYdSDo*&u9{qNl@sKXWYJIXd zo2*5e-vf9A&S5`m;^B9I1MPOnHdTCUNFzY+KB{rsCgf+5M=oN2ZJ->B7Fagr5(lbo z73P+|rTH6q&k7WgmX_up+IuXiDK6MPRFnw5pr#Q1FJ%cf@#-ILznbbFLRTag6V1Al zZ~jx4jT)w|9$9TMsdJ9eCZ?vgC~WXJe}@78onH(ji~jz7K~LoauVh3(_c4zW2;f2K z7JkHTzQA0`j#A)b$MW_1e96c-4F}^rq>!MfBZg2SxY*=;%(1miMe8KS__qKz9rvsI zH2!3^^pMo%*8P;w=9m;m%Erad#4o8AT8);GOVBgy7#+u}^k70-DJt>9G4yit zaciw3f|Nx53x?8D#R*hQVwI{jwF>surLFYp1(#vj6{0EzeV@yO{kI5wvSCW^ME_n) z|1**B3Q?svN7<&+Ak)c<6dIy#V;a$u>ns(D)r;4_|4BuETRvs^C1KSH=-sp6mmDEm z<}(_WwQ-i!Gme{KH(%LJo!cc4oNaP4_Yfe3`A4Sdi93QrkH$Ln(q2uY^S7Alc>%p|cr*r%_^#?^CcHiLJxfu3&)O{_ zww*b7!P3s@dV@h4c}b`Dfz2_sRuh)cjQrAsu=tGUP**uztNpqBwHp35bzdSBw) zamGC3AIZ{}#4(v8^jLG#@>d^#-B$mZ;rW=x0UmK4MYD=>ORQ-`!*kc*z!-c% za~o&X@w{|C8d4x|f>~Kd2^Ew3wfIhi+(6{g)(d(Q`fJ-P_;=}4GXKHXJdn+T1|K0i z1#6EyAX<6li)0JzUGXX2DjQ*r(SeJ+v^=8-Ud6gz%^a1ct}nH1|H6p=J3&6I@Pl`i zE9ws1+yuWlce*1DiCiLCB&M?($Y?xJb?4JUg@x&vU$@^X!IB&Yj8~XX`WxMg)-Hxf z-?_`9IywS#$rxrBRtBHYxHsZH4&+Y$JbNTH+N2H6F$x#|?+Jw{=IY}^bbn1$UD0R1T7(u?-`59M5(8)G>8LH5 zyuj~ zGO)atk^n%zljOjzvn@i9H>?`#c%aMM?h<6DALTZ)3cO+0GOl+@`jUag%A~P*@|w2> zu{KFk6rh)1(RAl}p%LK&F`)i&_3W+kA;9MA-*aJ%9NM(Kqv9LQ5UvK%;cP*5s9dxL zM?sqRL+9er705CfEVZUXZjfo6S_d4>8zoxWIx>}q7w6V#R%YG5omwZW{`l_aAv#j0sciudQeUj=Gx|-iPxmnct{xYW}?=LsN_)`KNrxk;l$&x9Ul+%k? zNRxZf{Dg(+x%b}sCSyA;y4t41ci)CE{O%L{B?|*=3Q?A*R>~Zf@HH31;U~gJ+`{0v9M!r zp|6@7ILeLdK(Z?l%X$TtUR6o>&B_CVj7&nrsIeje4lqW}aw$6~R9-g2N7X=Pt4&6p zV$da^&op!a4r_nyD&oyAD~za*2L+o?o!}p3+ojc>w?xyvu1xHSCm4OuM2qz}G7U35 zQ>E(0V_0(U4Bh$mAIx}HJgiZ*SZ|S6;)g!_)8cA3b^tveGa9za^=<^ebuOcWRy`0d zGAtrH-{_mli71e)1|RCII-*wlm<*_G?PHg%QK14Jxf|3@fT{ShnuT77DVaP}jY(%;yF0@*%8YUrtv)~Gv;CYdrbQ&k3jExdEIi=}+y z{-LcSo39@%E6-JT`6opT2g_byQD=d4bZp3St;o_3#1ow@cH zx=W~q2*y0{(R36a6Q4A9l-)jRFlR<>*8;jpg9XFJ74I(AANhY0g{y(2OB>DBLBgm# zgc};ad}(HkB$mdjw#rp^GY_wW#Sn)73UOahTVj93+1dL>vyDyhYoi43=ZcKV+3#3q znnNe=^z`~>3q)+{H{E^CC7LWJv}Z2e4|uUo&F?R7fXHm-L)tgi&n8U^FBS-?Kk;zW za{Q5vnC#Kub8M?n3O8z9H9&L3eAdB#Fb|TK;j==8)jv53;IcF?D-p-B`dMP`EXOy= zqe8fz1WE%5x>s%M%e-3~;fplCzum{>!sRXuIF2?M(hhleA{SH?W;ZW-@7tcx<~cMzSNBtA-8?bV@& zRL0Q_X-Sr)hTz?Y^%-e%=lFUP?dz`~vzr{wJ))q?>pyt)FY$_y;UYEx)*gSPC7q_E z39Q;a;Xe5+EB>-jMp!YW@*l4qU)2tO<<}0A1cK1A?G-j1gbMMv4ntnYkB?W~1G+vr zX3R9VF^bc0`}=BL`L(I7#GPFRZ)9oLV>G+urw>@r#oom{MU4V2K84h!i#Ch{-{2RkEz8ipZ5*C|aWK!9W{ z-y}2qzoTPnMQ>&uf`L!V;v4=XxJCgl=HmXWtRyMY;o_jHrA~c&-oEm*?)7s$hi~Tc z#@5lc+7$%24Hf_DBIrxVq7ch|OMz;#_}r??cn4kSgM!#kg}&##w9Clr#fL2g=IqK# zuTCUPnP67e(L)GzEhr;KQX99N-EHX;=T_8V5h-w#MbQ+DX@}Fl_b5lMdX7`55-vpF zxQ8m~BXH?eDJ5U|N;yMnl0Kq({r2`*jjrrmn5U+jD;dG;p2GxViAV8cdSHB%tMtW{nZh*ME@1 zhUnOUbK)dW$nQ2(H|}{qk>PT(?1$)I&WH8c*>#opwE<&#DnF%f)C!z>6p$vx z&4gi)Mk}`%fe2O7G&shR!UJxE%FwYG6JiOoeLrLF&sIjo3vsX=R09>|GOhb2!y}a? z3{m2}`HY#Gm{pKvR!-bBx7CoXBE0eQflqxu%>8B@$IzL zk_ag1r7j6_$464!4+&httctd8+C1~U|E_uSzeo@{Jve~2NfCSl^YlQP7FHQ$7I}F; ztz-U8f=RrR6zJ7CaWuQB#c#COc7=k*S3iaT?Z30^+U)qV4c^?wL>xfRyYe-GSLLxr ztFp|6`Q!G>e(I7&vfp{KR~-E2$DrJbW`##9aA@&zd9nalt-ixk@kw2CwHn8AoM`|9 zB(>3%;lgV0^K_jjULPyTwFy-w zf^z~Mq&wb9^jdH5#s;CxZ?HNf*VOpxz0Ld}3scvMdh^)rGE>f-@mN}Z|BjnPAOf6o zUfLR*B>~|oN?|M&8BwVq(w;c<-4lR_F`ee8iP^W-l4)Zjt|Xcr*4-FXlsxe;j1(ITi#Jo6LH z*P>26*WlEL5#tUIq>0hM6X+~xr6uZ9oNY8XlDLVDJ`z@4iTKY}(*k=B(@vNWOl1RP z9EkM>*qaqJgwp3aw^x%XK>`)>YL#YqqGOjPyt8h^3S!#Lh0UAWoYjUy_ophj61l4o zO4Ou=4%B&m;O0g{OJ)?)s_umy5gna_TXE$#v}`gK{>*X&&af%(Di+aN8C2;VsMIELkBw-fI_!IeJlsGsU>?ynl|?Bn-V1xGh?Oy=b4UHF|!S zOX;g`(!5$2>aX%$xxg8MdFNymn?G3wQlu)3?7QSA>EDOI8$G1ao-P^&tO=^do$aP| z<_6s`yMlsL&VrS#7KA_ERbM3Dj$LN-82B8D39PNBG|g#=Y&_pKEnmC+xWA2$y89B$ zc1f|^IhAQg!S6hCp|>QTreUv7%f)Ybeq4vT}NlGv)FdFdFP&An3cq5 z>lWH?e;(}RW|tXU{jf7RyII5aRuE=>r~c&D`-9`*I);6!9ie8-c;Jw=+7ttKwQhkW z$`yNM@BJ~2TipCXJY#u(4+@|~K4l0Y{OARz^V%E6q2#uFLH_wK?&8XsTqSZTC4fvx zJSFSyK${WLIPDWE+Eoe7+ zHJ38ec0rwElp=)?UN8GnF$K?^qCDWL?ORMC?C)T8g9wU2G#l45`-^f>rq$dTGy$Ge z1+!t&^@cc+e|Y{trYyScFjGJ)s`?eDe`u#N|Eu%TCoSnw`j8ko!*n1;A?gK{qU?`t zfzqiw`YTjIAW2-@CuVIupVPzh@bFStxxrfqWEZ)JDRcA`8%E3iajD5-U=R|XiHQ3S z`|pzhB2du&m6h9f?>CUA?GFM=A*+^p_jeZt$8D4bJ9A^aO<$`()8vNdG`3NZzGMSI zGbkzrE|e&S^UC>(uZ#j=@DX6jMzm~te=X!zI zF4#>8T89p|`z+HRws&@NtiUBT`4Vk!adFv2q0RCAySqQk!_cns71keYyTqPeI3%V+ z9kTo_e7rwYCFw9!q^jf^5xHXjc;}+`;^6z4tm@^7^$~4p^M%xv*v}JPP?N5QmW{6U zOS?^dfbD)Dy;Fa|5~q;IIhB#I3&*E0R&AS!fXXiwCG<}yfK#^N^0gLixq z*}>mn?T-|NFSBUoPi#hLQdv2#(+QS*93|`9lD7mZYr`oiuk`|``E!&Bz zfdN!1h08C+=W%ZRWV8*%@ zUJBYaMABVfVA3m3Ei*k=kK#H9AokmN_2>A{xnE$%kf2|Z)@h5|drj4bjoKt$Wq+2A z{4u8e4n~#Vc2 zZ}H;@koIvMu4@McG1aar4*!I6M@-O_a?uiyN8mwD~K$NwM z6+fLdiK+N_8eb(g*7g^0sI>yvDQDR)9EabJ|7(}^pCB-mq7by%ifv{lzi9znt2|lC z1l#sRh@2lqgQ^;WR1?Z4ud4nG{HmeFdt(!th9tJ%!?Lc>W)&~6EOkOk((tnL;ayBY zuI+f`W0-674JQtjF~Y72GQyW)JLmN3DVmG_8vb8A#bDTv)u%h18O+G)76Pl+Eg&QObb$OSnx_7!l1pc z65;zJ+aR0T)=y(=H$IqFtsDG1aQy`qeL<=hXzUvE*eM$eRR;#sEgRd0-_ISmQ|G@N z5un!vk%zuiAQ^HQa4pFPmzooNev~{&Zi)EK34}io+bpJwGkeI%`hG$=1gMp8L^iRL zD=1PZIJ&40By3RulAHVyxynTD{I|MnEHyO`f@(mH|8k4}@ez4e5#wFP zh>P^dJYFiS_YrC~X)EavLiH&P&4$@U%!$qaA06KuAJ@9J-Jp$a+l}osPNT-QZF8D7 zw$s?Qoi?^Pv2F94?z8tfd!O@uf6c5}zcp*E=elk@w**ECipBq^=wbzE9}fzIKeLbw z^lu#VbE!5A`O@zat_DCf>xy`Bl>cmiXjUZTf4c4ad<@Jtk^bGT=84>GsFsWlogbk}`Y4 z;Qi&1L(AI*1bu&KhF9eCc`6asm~JKuag8;Ri=dws0$}gF4^!Y=1a69S0p9)Kn}cOo7OC#Qt7a( z_Z5gX^h@rK67uy`#*QwmyM~7ASzqsnEEN$<->cIv@H*A=g?n~_#yeTClXVz% z*(?~o?KT2TBxqiRE0oH^s2x8iu1OZO)=RbM5p~+2ia+)ZY4lGfIchqU>ek-lJJUtT zU`AYV)L<6>r8pAgx<=Y%t+v93?&T8q|4PZL!(>>PvxM&nQOv$*o(RxFPRce|z&_AM$<|y`cugf$1 z?8GM5M7>|`mE`$EJbIkvp=b;tk{8HH6tB+ zt)_Ce{0pMJ;4AFwf5DG+BAuS+_gIOs!i!#;rE$FZ4)>ai`*r4Ij?o#M z@b5rGIMl`tNG>&cykB;g(4{Mjj)cvuaT$B3J#{D@PR=82ZB(+&&9G4i+*V^Tt5HU& z287#O2OdwaIfK1Mna!qA-#@EKHv9A~kL~%t+-m$;g)0PJ7$a20?N(J&m1 z!Y%ok9Unl99{gnog-uN5w}^Ay!E6%^h(>KFG5H*PFt*VPdgRUM8A{{YCyj&; zLto8s1b4jDfZi&8*Q=d^?RDE0@Svq>xO3aSkXny=A&=PW{q(IFy#XS5#sr$lkfx?% z;d{P_6LT9djD_TGy`6J6cQ83&q1BC1RX(bJB1Srt>a9=4cZ_qOIFps=sEVVk2s5Z(`Udj2H#mNWN`ldg&bxT{Sol=oeK-1O&z$%KpY<06?QRM~4oS}UU7F-Aq>sqh-_9-LtD)xqbHrz{Q@PV4UDI&|_i zQ@lH;MpC&*ug2^vX1Db7#d@5^Q@jXXv(j3cuIfu!L-7`ZHWj#>rAB?&iP9&utn2Bpu&^!%32OKO!CwzCYxQSu5 zqA1ZSO)fKdSaq!Sp0U^8wdAhQ)1O?otJZgEh=0#3w|eDz@yfB#V1+d|N)SX9G*&lO zD)hqOB0vSnGk4qZZ^yz69q`5J>dQ`{50hCyfG7#gfW3ZTuG3O>EyN${mj}lCW>pXX zsAbBsQ6itQ1pGWu@<-UTN8an*-MPwxUx;tU9#-`W{V+B8aOM-zgz3Y)bAeZV)(KZ_ zKZxs{3o+oPA-92-O!dS+B8+?5Sx%2?xHZ9XB4%uopPTV4u;#RkzN~0Pgvp>CT%YL! zHZxajy1xEEn0ycXWUfF57NHr|O)2}>xD~A&y+e}h-|E#M&QB8-A=}qPgOokj@fLcr zv%o-GPd^M(l%$SVTz{CWn$`mN{FTZJZP!8&%3Kg_!m|q+zTeQ>SKZpnv8R{?bwz7N zSi5~r5^pv?FGq`(5=9W@VP8 zKy7xqkfSeRKcwKs5=`&C{;dedE+b}V|I5n+8wnUa4?>?acTZt_rCzXDw`A2ei_JEEq>TaJQEiVpfqNJ@(*!yLg60$`mqPQ5}GJYXC{`PUg zjpqalvmP>-v1dNki}LID1UxfCb}2FSdWn6Ue^e+;v6bbz zuplwd##>>rSuBZ0%0sZ(up);g3Iv)mg9^{nUaCS1e3ob1ps)~j?k!h1Ag~M$;;m4K z&egfSwlgc|4VXL!4-@Zd*ZOl1+L@X}$o$?9hOB|Djy;8LqGolZ3i({Dt}5bP^x=>p zqv~j5TGCH6AKDbVI@E%ts8m{{_s~oyz+$(a)HKz@mMHN(;bq2_fj(Pv(R)kombO{OA@K3E;y@Y2bE-?eQ%oI zM?C4i@}90z24U;z#Hlrefe`t`t!Vzq4vmG0uGS|<0+FGcv34YOA0-DmtN+Y zy-xLJP9%140=n|lOe#1fj`d`&>d)_+PfWJC^d+N6?tPaf^Wu5J9R+mg8buKF$hV@G zS~!Ef3uSfvumO*T&!oLJi=BcmkEr+B^c6?akjAQHFelsC{4bBVN0^mHi*(FJ`CLr+ za+CuR23LJi{k!TKV)3s`1p|PUDpDX%5;y_XbdX|4B5@|Opj{$1^un29w2W0asMdfy zIx0#RKjQk6U$^55)bJnV?%GWbGfmHKl1l9WeQ$y3Q6zM73YUK8-Yr)MqL>Nt&{x45kl zG*~W6A4q<{t+2s&=Dk@t*3D zb4VbdzQlcPTQ!!3u5jyCm%nEtiv&X{aZD`tn`bf`vn<1{rsfnwJ9&vuX~G=m6NQcg zPc@eKtS*3qeww}=fD^{V#Etl#SB$KFJCr;7Mo0!9RFu5#XnTZaYAtf0%CR`P z$-KhFDr{MdT*>1tOQNXZ4iSU<6v9M4N`A62cb-yly2`x5-EdnKbKWSw09A8yzFUd8 zPMXfx*wmmZ_}ga(b58SQYu{F|&W@cD!xa7)@6=!okgs|ND&`F(7t%Y= z&-58i#PQE%y!*hVrht58*Ui&sJF>}S|48aR;ecFr3KQjEvB^xcGg}mNt2QrGscXZu zbohmFF*2{xrQ(Bt9Kde@`Wh!}^j0tvrE1OfmrPt&vwT*|jf5FoZrd;`tG0WE=s6AE|_Mf^>i%8g>LR?ki})+uHuWlm%GM+hF1 z_Tae|7Wv!tso8Jcfrvt(uh~h_m44A51cJSuTyJ29?oZQQ@nNq|bj3@{Tr*Ip$MJQJ zFw^C9H=I{x`)OD`ewSS~52iMiR4!+LW>N&SJ7*Usf-3neI||xjBk{Q}OM1XW*|BQ93O8rsQK3Q@+;zE{Fm#X8LohCzhWL;6HnK^!b{e@5bfTH>XqJIGjP5rF z5F*t%w+O-G-l$hKiq+TM7V76p4?Ck%35~jr3U7u#wq9+O29hB^qft{+3mNA4&?;$C z#gltxMtz~Ley&4~<`?CAzZq|TJe=(_nADC6yDeW@E3-pdw-Sq5vNt7Op&kpg@}9R} zg68Jz)41P^fMQ=MdN1h^UjkHFz#}nmGA6m(1baRwf?51i^a#EAB4mI}bTI zJ~9vqU9TUhXC%Q-bS)mP%J{h)n}7VMNTHpkw04415KYhz_kJ&IRif-^{)7TgSn#Wt zY-e38hGVs8ACKo6q_tMIm+RuMN%k5?N9v_f?H~!Q4m!lQi{9_;lpO%yRA0bkSeV%6 z_1LfSkWBr<%nuvfjPUSSg~I`x&XXJ4M5}=`e*1cg940ic#9o0O#y7z$w_PDA$%&Mu zayVmn;2YkrNAs0_h3_UQx~R4()X=Hx+CeeATTr;2fJD5&;z}_^3TTA#G$^}DubT3q z{0!c<#*n~;I!)>)m*UVg)s{I;R7A~u#BA%lELRA=hRRnZkAW3tq?PR`%c*ZE>g@*X zrm~X4eG|6Hl+qD9TkbU^{pUZq$Zkls=E13_XN@@ z(!6}#CtPgBwB}hXqc7)$_5{EBW0TWt&X-TB;XP7B(n0U~OX_kc7P;jU0Z2Y_s>{nK zek5l(m0K>nna($%UV7T$kjU@rbUq87-`63L$m4LowLR@)cW>ZR?)-T1g&aN5l2nj3YjjLObM$0W7iD2@+>&m!m9$7p#^gP`^VUjNcFGwKA7W z0+muf=Gv{;*?g|)6`M-_vl6g!kXGL4DO;c%pWiqU@)=sxYLx(i$X~C2D2{s?pL_>r z*rKu&WL#`?!faAG45lAdlDS`9je|uz%kM-s%|2j~}`B$$_e_H&xFY;E`)9^s;m_xlxcxzc+Yl*F&?u7^0SeM$}i=^b|#&}^j$0-djfYC+sAZXxY3i&VoNMO zJ)Q`OFC2VHlDAjwLMfd_np9X6d*yxZ3VUhP`3Q1`^kAa zTD<-8=le1Lt5yH6d3;~rj<=`>> zy0?j=$o(f>)y!(@yRGC)gc@0>R`XsV^y3Zrzc~L&rm{lsA4aj}QXRhsO(Nr#>msv_ z2CJdFZu-Pp<+NPS#iOShfBhrmDE7#(1E-a**W@A(D%38Ud2{tgv>555ma$_kT=+uh zj$=EQxrd9&_4gkkqy9eJq}+izo7A6F#V=m9#i`8t=dq`YGs+Wbm@k-*qhC^6;7^TP zWd*=&TJP9kDIBzo>Jn8*olFuW4~QF~Lv#1NG!iPZ-7T|LZeB4nP{PF=zVR${c?s$D_Rz5 zvzh==2}f0KDZb6(bYefq>GGAhXCzS|pm;z%=6%$$*yal_Wz?Rhnk}php7m3}fnNVJ zbJSIEZ8RO-e8>H0(2a>X94&S_Hf(lsW8GC zDut+Ov%`*|610fD%%noXhwzSdSXn^TTLj={Wlo|&{aV&JPSG~1;lNqSSmQVj{_WL4 zhvXJ}G(;l)a2x52S`H;#&Z=}Dj10g0Zy%b($%j?TdI3iHXG+&FW%%q8wx@gq>R#?U+F2HwdE5PCe;f}MJcpU5v8 z%4DCi5vi zW1`XCN&X||0u#DCIiIx}Ogt@}O@#aXTxYFnvs}CLa2=H#KYjW4TpGA8 z3H|(I@w5I1Ee5fi;Xg7$6ly-o`_!*WBy-cvce|kVsxdU4I1k3Bx2nY-FQ3d9XF!gL zf{*?fyj1>o!5-i2i&;OeUB-*+ z^xyBk6JfGzYrLc`E`0)UiCE{J-tVMiwnxD(fTU*g~^c*3WO#2Al+iBcO(jgvA|D7m!Xbs6Jt&t!^ZbJC|31BoK$${TYAP-E1a z>nSgf+&wH!DyWWIn)@R+x1}^96>~WbXJI?WdU=T(-F(`b%ap4#uvI-bvm0S{q&14D zDw{P5jzMz*$M)84ll4{_#3>tmLG2)I9?q2^=`1T=J@F|Lk3SaTEsniI2INgIZL5da ziV)1~<1mimU-Qth(%E5LveNiTM*5XA_#q7C|B*{wA0gJ~7jIWqGc@@=AP`Qp3bzG? z*x%H$HUt~nJ7+@&p)?|npHG{BS;YED*97jd=={7;7pDG@gyd^Q^PLot9bwaG6QqwV zB?OFULf0ZYryGvvx_o%pr3Nw25z>H0SF#TI-?EUPijGjBunxbjz>(DRRf$ZJ{%QE> zz11MR?U>G;+fQjK=nERCMabZLGx*QiPSFcdO@u{Ghx&_9{cQixuF*nGkcN|WE^5n^ zj3C+r98tIm_ZD0Hp#IM$B+y9FdB}ZY?n)#w_ioe3fOKF zd=LH4wwynU@ca=`GyaH||NDZ!zU=V>oE~U65*+Ot?bdWl(sOch6j@+Fj;Bh=y&$>8 zZgy%`jZps@Z9p1c$8`5hrOpew;?Z8V$P|pWF6Y}aL@&yJ&;RVw5b{TirN+E=q$L08;1J~F00ZFo0f+_?H zbL}74gI*}>5_;m3qDR@{6t`Sf))y%AD_?awG4BlIi{Rw%Vsk?%qroK@gC%i49K`M~ zL|v?Tuo)3!iN+ih@d^KfN16v@5 zX`k4#t_{^XK5+bVDpRJ*PK${>zj5SPU@(!Yq%xdY~K4}y$ zk3gjDfz$azuFqt{Oi9$lBk$fD&NvB1?Hs+xIHp6FPCHY9jo)>q2k))Ga{XmsUm}P+ zq@-OK?&i+weAn*6wJqzy>M@s}nh5pXk9uvJ4P5{WI|HhU+t5!?<8H`U-5`*6yf zN36KXhjH%vja)qv<}}(F8Z0mu@AzdSBYXmi)H+X2`&r8H5jM5h`4=hdzdr`8zmP9O zjhkT_oJlo~K4)iH5L?Am+L=N=tc_Mmj6b(aE{9Y7&^a{EBkb$Sj3K_;r|%SC7X zZS}gwM4PmpoVA;-$_!6JG*4xKz-ImD1TgoT0J~7Fu_T}aB|MXf%K5M$W4D{C#kPyz z-Q^Q?hSB^%aL^g}Y08tXgO-dkK0xWxrce&`>8N11M1RR2yJuMby{-oa9e=%_%CfV@ z>?Y8mjK${>p_7^J^xY)OU-I4cAWNLhzI(P3*4~h`!X2Cbz~vc%xi^qADtWfVMqcXw z=rB6bip6BI%Cpdj_h8(sUA>5ipkoJwS;WTxp+pOKM?kI+lonL!2BxO#fYLVXba}p& z^wtZ96gIuhi5HVzj}rI9D5m+8!c}Cmch+~7>e|;s)VFmKRa<>?l5&3^^`da+Hrz9b zV!F~ZsQ%=D$-$5wUVP`=$6tAR8&UFMNgGJy?i4h>fqL_EDl5Xj9;Vd2@bc0m3dO;B z-)eTR3nt|4u@;+L6^bExUg^cqUeQ_AN7ej9#PHzpa3?J7@7={&jxfg>>^S^WW?ILZo1yn3mz$ zC$l18F%vK?LTs)XCxq!`rRlj|tDU<#9hCQ#6$w5)aS|8|F`fk1EBAe>_McTZgtAdk zoQ$a^4nb{RBZZ70i5BvI^SR?*GuX3tq=0Fx&nP=??>u^3Z66o#YB%!%Wj|{+i zgxrBRu9TEc!bOXVqWgG38^?{=E;wvlhD@%Hc<Xb&RIRy%9BEQAKL{kYsmD0bj*#i1!*GU%8nW-v9z^9 z6ReNi4eq$V?LTkv`(|b4K;wSv{xlrcN!k2Z5`7w%6Zxx=7b2Fv+k`U5y2(wSBSyN zbYK~k;%+x# zZFW{(+WONVuS8@%mtV3=yqH*;ECT*o>OWSzt2s~zJ_JR}XBo#GcA zu*Xm47#;K3Xf6EL^IsNyfVyNsQxNIGG!4_5(Dzto{LMrvR+Fkp6*r%kJ4ofhEtRY_ zkCxS2|G92|9I<`#7mH^5_9gDBb#vG2bfYb4P5(tOq6>MX$7LSeI-NH|$(R4J@lx`zUnDGE7wcMph9@L(ccfBOJ% zNOYZL&(3<}v20kJa!sjPygIubH-s9(tf~D_+G+N&0nR%eU)HHih@QPX-7)Sq$Q2hA z2|eA?uJUPg`tq|p2;68Y))N}>>U`H7PgF3+?_K5(K|45pUG+C8Vf21j=2M3=Z8_>Pf z97Nf|??OfbZ~UIu6OQ~|#hSN@f+)ko4#4vl$$rPE_|q8zE4+@gsk#JF9@m4{@>_}u z-F517K}Ah!y>9_h(qzcIkWOz$%<&z~k<7#qNec@LnvfD(R*s)kd4BmiLLPf`1G5Nf z!|^R(qYD)pcHPk}-L1F^=mk#!^trKGEMhxiCl;hqbyx-FpCy2w%%^;=qDoCC)FWEBZ)(q$p|Zp7f?FS zxv=FnF}P7ikP2wd%*D{fk+ymLW&aD?e<8hu4@M@rgztEC?k%>S9E|cllzXZhfo- z&?)r`I=0x5#)=gANr_61qB{-Lf2iTSxVa9Y{$(#S+Weu^bWi{FI6=MoRVq)yPfh;r|^yn zXKi+w>JO1xXRyas%9yL;(srJd?@2})6L;=Q<@JKy`Q1@2%l+E!t#6GMXtC=iP=^6w z3G%(!cCY-z;cMj(08R*irdPD=Z8HH^o(*&o;#f7*GUq1^iSgen*Cnts89k+F0knsyc6Z_uy+C7L4WQ80< zg8Y{%Xw8_@m%F=)iH~>Ie90-hi66fC2j5Eznkt|@2-oi-RQx;QLfityz>76_J^~{)<(SneJpBu9x zwJ+Jm1Rl^JoW-2^M#%4JJekq1Jc`9DKC4B!%;7CKRqb_Gc$s&q4m|fsDkvwPs+PX9 zt7mk$0ha*0#Y_o5kmCOrlmEbvs}m(yx;yp+SiMq6D)B`r6wB|1>$N8Ta{E4)H;Xl@ z1d(}!TpL%xcjfZE`{9jE_7CO|nkJVid;NYe%^}wMo8XBQ$SkJLmf$wrF5JaPnJ#Uz=TX&e_m07D%cBw!q7nSh5-q!gOCabT+H^XF^y%mKKFd z6hxI80uY4eN|1FO5+bO@GVVWkBkNRt2(A#cmglJdx=Ywq_OR8{Y8(rez9MS%v9Uow z{i^S{K{}Dl{S6`8$O>d!qj&yo4$O$a8$L)~jZ2w$;FNHcQgR5OI7HmjG-qG3YXkG1 ziK%9trGyO40dc!PGj;^PoM;yFYxhIP2Prav+j0-sGMoR<>E8x(3=wiuG@R{ceBh8o ze{URih@Ehl>dbEt$iYK@F){yNI{lA}*T0H)LC3;9UIW+vF8%-hW6){}L1TY1od2gM z^KTbYA6okybl&l&9{7j9{rF#!3cCLPdlGd0f|fPIy>!>Rzu)x_HvmwxIe#${o3NmT z5%!a;BhbziQRL)qJbr6*FSAeD?pVw^^Ywlz83sEgR-MXz)}+_{B89@;$O+>yPd9)W zt&fC)Ird2>UDbTe$$3*l1?#($EzCtH=a_EAHU{NOx8904`tTVM6$eBlqAQK zzqLgO2_GYFn@06V<2)3>N94hW6(arYN#nymjPr*mH8oNc=gH7iBcxTZDm<3;=I4jt zwyqk_f-L)y9uR(QElR7aQv;6^R};f}0&`qZF&jz%S{oreGJQxXJP6wroWHr_f5=DI z;x{1*T~9VFY)&LG>D~2L4SBZr5rd+i z%)v+{Gx5ySNm4(K1}#?E|Fz=zh?r04Sp`oxTIQ=Nt@D z2Vs((TvP=SecvW&ik9mUC@6XdGI`;`a1>(MNx2uGICrd=U6u@u>C-~k82A(&So&{4 zcU^}kK|Z+h4wT{cYw_7Tz?VtY`$oeL$82T1CXP^6FJl#&k6(+LOp1Cp2mwSA3MN-qTOPp7>G<)J79-roswW2Fol zxLGIJ{l4IzqG!$rKC5*eHzLDu7qekuYWhKU)zJ}0m0h{b`vZ#;rqOQg_hjTBL=gA} zkT8m7q;{9)*RnFAml0^^R~}pUU7a6Vg^|uT3VKMa23@V!ItWtdFziQT`NET1mbGg0 ztWWG>M%iUAeIHeN9ERj}3IV;kNDf+{+-$%G!9q32BdTKp7mu!E$}%}C>tPA+{`$RH z=o8{91HVT=Da}@noZGF4VBoe?;rOTo&Xd~pz`6o!lUne|PZ_;7z(+@B)9cpv!_v#L zt@xD;$tWejv$6iF3O24F2@|^%z_S|GR-!(zQN|Az_*JFUt-RN$!`JV2CN+Z6Ruh}h zYV5z3f{PWpC*J^O5Ecbfj;b*InYo7i&1_&jJ}E_dP5d_EmHHg}y8SC9lrIEAZ9A+) zx1w{C?E^U9&11tCIT=G(+jKVk1&4PkGAmc7R=T=!rY)Q%R4)6Xp5Wh;xxAq}UV)om z_<C9*e{pY=uvR*{e3{ezqwdp%hU-8-ddKafxu5rz>LOj>%S# zyp7OuSLNm+x5h_K{Hw&>t&U2>U0(!_D+cc@TA`}4^e1|mlotj^tR179lKf;%W+J1& z)gS~y7{ve|v9K6^6Z+Fpz3*T1JtWl=!=4hO%}FpWH_I-PqqNIBy$Dq4e}sH*Myn?O z!mOYA!uc=rVU7lAnUnLb&}J&v#qeJyeF7V@q5TnC+=LObV5D2kQzfgZ2^)_CJ-1GA zd~*`pw;$ZrY-@6FO%z8jugYr0ahWrMgjmV;qF`g@yuQQjvVXL2F7ZPPuob>J?)2BC z3-F7^=q29eMbYk(cHA~SWa?!AXfOJB^NC(~66iTRYX6Z|J1Xf6RQ))p+6O{P6AVl% zAdlh`y%&`Hxd69QFM>5YV&k~M{c3mu_2}nMNwIIgg!2p!oNAdqW-JbBxbynG3q`ze z(Pa*4I`v$E<|KPKWV@a<{PJ@h`P5^QymN5t2PGUFGj~(L;EQ~DS8K6RmFuvGBwD6$ zN{S#}Es?i*Jwxc5|tt(R;oP%3%gxFflqVdQX`HNxUD#YmPA6k9l1GF_6 z%`cqYVA=H+#g}I2EJ@VSaz0mhE{B{0%%YAw0>3>j-!=~$NKNy}H!5>AWv9OB994Cr zKlCsg2HeR%-~+nPDToLD@0f#?1K}c zCu1VLO|5Tvmt9e*2W||%+NLa$IZVGLRr+-oZfBoU{k-{XxQS9}=1W!Wi0n_uzu8_1 zm1O-}_RX~*N2F~(wKbOe4u-YSdFu0oa+x`t)qpqX`gbNShsf+Bf<{mY^myg3?DI1X zL(-$}gfzUS=A)(*tCYvZdBZjIIp64F6j+B`@@8oNgiLRVMOjq%8SfrGsO5j>Si@{6 zSrKZuJj1u_Hva7$%2xh@;J-8uU`}|QJ@!LVwZj?5xE?|Fe52q!F_R0e$HgdEOLK$dC=&AY{t@ARo*`b)6w ze(jCN(HMB;$QZUkt@qT)jOa9{b6($2kLdZgUpbu{l{*>!C0QlVeBzhu$X*kkN>D{m zQtm{HEg1QFFSO^A5`d0Y+Sq8MQBt}*mx1Y@4Ko>7#?+2GFLwaCO88kWMR^}JbH-u( z`A?`J*LZfu?p##gLKn;(suPH9*I8O10vP8IS(C*g?>lt3)qR3YmD*w7~*TYvK zXKhkXhZt2sZpF2QoUP56g;KSbZAl*l^^D(|ndY}1Tr^!N}7+>Bdjn=xb0CKw7{)j$mCzp>0QKzLZ zAZinPM(gdbXo4mhKz{MQU%CBRAIXI(mrY=y9Y|Km&muBybJ~h@zc}u1yQ2P85h~k0 zS>vfVXBJqUzLi;XqxXvH{^G*OBesT5N_!Z`ZmqSGN9B65$)XZ&j>8Vy^tBYJWKDmq z-{;At{_aZ^eY@KRYsoQhb$}C3rpE{OEdUOV(%MDn-ruZx7p-8eQi zkARp}-w}U2CRT`KW?yv7QEfni;Ql%a4)f}hpHcL~IWRduYG4e1BVkVz=c9J-jRbaa zIhD>N0ifombw2r*+&G7|9BrA5_=xNEna`ts&x=V9Uu^%wsQ7A^DP%%G_5hN?W@c_E zmxX+6F2rDL(O%{rScrclK?-j4xFoXkm8?ffmysg&z7WCZ*(A4Cfi!ComJB)=(#P_~ zHZ~MyKeNS+jux5AZI}Y2b={9DDCF!P(OR9Tcw{pp(b5pfNVgzwsE1u52&A?e}Cgi;e#E%%OGNG3=# zzGsWrr?$wP)~KW~lu!H}F#F3r?J5SvFM`q~O@2);JLHv5Js*I=h#0-79hGc_Lrzai zmoznFMoER`zAcCCes8b6%X2gs7#Q9RDi;lLmKDZ2-3N>g%(8ohmiHOX{J{-oT&~lW z^I0viGM}B{$(mDDYfqx9Gc-{FM%oZrrNVdeBENU?dC0zKBJ1Gd`g{bhVO+l4FCoe( za4%o`KdX&MQZZz$q(Jt2cw{~xcPYc%g0A!h{5OQ;gi@TMG})Y{@Mc~lm5H&0kSkA z=dLh01#}rVODt5XY3!eyOG>!K=tcY$LYpy6uN>^3t}mHVla-|}EpodHO8W|-s2XAt25aOePn&|S-dG=y=aQMQ#5kdf-L0PRu7{h|o@xf*}M zMb2)85)xc%1p@=mBzRmqGpXedBkK{?+$@$plM=K#zo|Z|$plE(=W(TgC+LA~OaVomE?(^xW} zW)&~m%IaW96bibpqSf)1(=iM~ooSj$d_&cgtkYp-8>(9n4k5cdbOgTFWNG@Mq20Sx z199Tf3z}j9oc+ba7{XZ6$ zf=U1B`+@cc060ugtd?Ox$qwSrAMK&7bGAO_Y$6j}jHStuf@i_aw+Dw70@qsI*6CS2 zZOZddj0dl*8NZ9|9G9w&P-R9Z5Ysa|l7CVBm7pr!?k&c(f5OP@Nq^b}=sI5PGKz8- zJr%A&t`kP&e>xg;^eSR76q&>&B^R|1?)g#|sO^VBOiI6?NUsndL@G~Sq9y0@EwHo_ z3Owc`EnSTvuZrlmrB!(q=U~w-6oqV-jF;t5e}@y7-3}`yj$+wGd+6X1>@I~c?|Zx(&l2d6E$1QYxs3pM-h4CqF8cl%ad%2q1kCTL>mr;OEybl1)INQA&cQS|mZ?CVfKR*hC>; zZn@wFmw4%vmFd6&tVh3C%I8IjE>L+tGw0~~V4Udrru3EG4w~bfb^Xh+{WFe-EZPN) z+KT??R+m8?vO`wli84|*vQ0U%-KmPbJQuC7RrHFzjjCx?0=>{%QrVXA=q7SKi|);j zRbB!9@hb*1Nzya%VB(m!QFxlqtlPJ*Lq)TevQ!&DL!L_Q5c3!^Ypnyvdod<1QepDQ z0aO(H&;?|Y4QNQL^6ZB09fAfof)horl2RU0`nrVR=Py9i81#dgs3Jt97>pVTqvAZv z$IzbIbgfwwoV*SlUYmi2(+=JzcOWJe9_t{bn{j1ePoQ=D zCC}q*;2bigEUq_3$~TilO6x24LRGSa!JQ47tq#b#BtWD2*zv8dxr^rHZrMB1Y z3QN+Up|KFMUAObXmXRk(By@g*%r6!&fO$h9q3ar46hqGdE)v-e4ZBks+3;D3AcX7# zxJ3P1D|PHrG2qcsL^M#;1{R7_H--c^&Kd(O_x1ZM@}Z|Cxq?@Xjv^5^Dm6;grx&Z1 zNPFaJlC*D0${ZoY3aPkm+I^78CYLDI@R(@BWwVI&J()X@KCo1k%duFS@Sqj% znux<3CQ(S|{Ls2{2^VU;v70q6v8^B!Qk?CsFqvppMkpOfDb5mT)cV}V)?!i=eC`}y z{7;*YsDK=f?c*ecmmH3~A+(qrS8@a~s~NFaNK2^K)&`v)$I(SL5fVmd0FtR~(h~bp zXa8M4DNgzdVrsjCOy5v^-ypn`X+j$A{$@6$`bE7VtPq!Iv4P`!#~W8Am)>crzk- zq10&f7?Wve;`+l(X#SPcNL!Vi0k*c0hk;WAA_G2(ZRt7ytC|CTOA2rzQ#H`qg@Z@tv>$*}({6a-f+tVlGUB zPXCXpw+x6n?7F=bkdPdtq?rLhx?yN!=FyQ;8M?c>Bn0Vh1f{#X8-|W|yzl2Z z?>S%RfKHmF zDG1Rg1bG|?k|yPYdy_i&0a3;=KQS2Io{9|(w$nb8t$h8bzVS7u@BCikXr8s!BG|#Q zZblntYipCK&Gy3-mZCWHr9jdt?Mmz8Xk9MgCbDrpw!eo~e5Z1_rh=a^mRa%dd_?&A zoBm2Rl^9?WuE(blA^a7mOsm3AbX#NixY%GnYVNSx&)FbeZVrE?U{d9@)Pp4PsHi0M zkiPr1OgeiOpyGHxbmO=mPKuhYni6o#GG3_26$ygR+$W%>r0y)7C$_ zKO8QQN7z8%s&8u|!dA=(Kwtsma}bV5Uhi#*)F2|C*3Hl^Yhzv-Pm^Bl=2Q*=}}he;6@!?PjQ1lYZ} z=GIg0S^UjOyDh~B`Seq+jM&;&o|7DcK8dGCA)0PH{e}(i!L^7`#Z)+SV~UB6!wXwa z!$o3Qa^dGj8Zkx+%x#kkmj0J^YkzHggz~?~cJMWJ82)RW&nKzw(SPPRA#TdIq3ZPI-NsYz|i%`iDr>r&Vpw~8|uii1`gP29(Q6}BG5 z($<^5umR*E{hg!dPr<-jS)9V%{3L3UA0sA5{42hfIz6Y|) zLPGm@9JZMa(0kM@;{>8yUo|visTo$iC2;$xTc5KGik|YyA6HH~R+8lZVfC+?W%}9) zxQJJEa;|3OA*@O?HL|HWNi)0MWZ40^>Ji{3FVuY+WRCUe>3x|fP zO03s3@R+!;tif7ysU=m|%$0@g4%#Rb6|<4vFlsN-BWGqM2r^PM>JAjyTjNG;(_&le|daU!!hwQ#&-2F|1O1)AAiz;=fYmGhen$E z4Yzs@UFSs5!I!N+J!SUTeMx4utif(DgEq9(r#AaI92u_ZM53(t5bF!)v)3;CBn;*+GTtwn-mBimk4TM+v{x4lPrO-`;#F8+k!h-?#LoV( zo%Z(A@nDadA&a^<0F0j$5s3vk8M7G8Rgmhyi(VI; zF|Gn@>Dh!zrg#6W1rF4~QUcMueKrbJccli^VwJnSaALlG==!(gU199UyU|W{O*R3@ zIThXx6XsFy^Wm-hfsU0L<32%>uOzV?p(rp!uQ|I63Wz0MnAM1-U-^Y~!Xtilpevs_ zFTO0j+)tO>MnltOsCj7jTTx;O-$v|MK>7(0mY9H7bzyk>!gWB=mLLCu#p_+C?h-j@ zaLn^*%AMM_q-^y|B0g1KOUXzf&=i7)W}c}jehi5V{iVDslEOcI$3kQGa3_%;*8NG% zegV%)_Bi#wdqL?hw%G-yNo?|KIq%%D!ynBa_+R3e8gEV<_l}#RWe0|R3U4+_dGaMc zVe8!_RvGbL3M~xqzXH)`8RhgQ1c%3Pv12}|N*K>L%eL`^H61LB{K@_c6O4;xw?QCJ zNe%1f5?^`Rd`b+zz5l7V^x8m<5a&oUfK=R`8Ipq z&=p>j38JU-*!CA3q5yLTK0j7bY@LzqSyzkmwB~FHJW!+@^$!aL1Zy?O;?+>YPap^3 z?=&}(_j@*Ye}0RMKVr8AH$GjX3`O-kX3L4lyqHG(X-3>k(b5p#Bo4LC!Th&ANd7s! zX}i)2HVt-Zf^c2w7b!w>5gY&n3slgE71*%Wng|D&iL=pEzbiS*B;)Wi|DuZN8?3EICTvp z%i^&u(m}K_2}pYWf)1;`8Ddl01;=)zl`3S5V#LM2LaAj7c7iG#rt2#&nHstPAnzuY z<;?`@-{gL~$rnq>%E96OO9Gt#{1}Z-Icc0yJNneGc7y|rSL|1{yPqQ7+!{N%M|Ykz zSF8k^MVlIp<%kjqc(5X4lbyIjami;H zFn27Ss50|+FI(*H9I90E@zyWjPH+NFLqsahUbg3A41?AiurCK;B6g$`l2H;mRVioP zE9b?W1uuVBX`5<^SXy+ddGNnb{- z)gOmYr9Z_<9*~yc=>KS0=Di9>-v;h4qa-i?-gt>S=OPvQP=xgOikkpY5E7Af%Ky$_y^SB#@SiW27I7M;c4dpd$}Ftx#W0TpX(zY4!xZdFWd$+JPR~QuyAh( zRHuZ(%liy?0pc+VCE?DBmwS8O>!V<~e(bO#Xt;sbm!<^KvRseP_%w+>N>Dj)4F_b} zEP@F|H(W_3@iiUHdv=~^D@wp#GDyFF%N>VCK#f?%1u7d;BRbCnY*boAm(|pQ#N#Jg z={K;#%0PVyeIQ>_kg`TQVG8nAVr3U|+@F>qPl^aSxo8DZ1qJ$@U8c^!0q6Jk?1=kY zstPkDkmsKG>Z3GIk91|~8q4Jg(t3?``AL_*{qCqgi7~PnF2%9KGCVQ8UGlMpvS8Lt z?r)eiG#c@y6;Rc!2`cLrYd~UaHezt2vGzD3gW;M~I8gE0P7+P5PL|tVa-SBZ&2T5< zF3~%@+OGj2^}p31uRBgjG&NwJ5=BS(J#%wT!ic}6Ss~Ax&3CwzKqWN=>ag%U2TP#( zkW^VhyjrQ>&U;e-LnhK)IJdWkpG(QUrhUL!CPg60IR*VZ*Cj1P;Un@TaH_YDkb{R( zlGtGc=D`x;$5EFuL?AHz9MZ*kT$MjV19Y!f<@zfHgZ1Q+N0m=C45p#I`)btFTBmJV z+s~jP4(Sn%YVe{h1xmzZ%vA?`d_4|&K&xD&F=7CS^OiByg+`LRuE?CIGW<$u`FSY{ z6>YVw^nQzogX{}Xit~%kX{rC}dhRdWvVWiZ7dJw)>b3YxDHc(W4$tOh+&pe*?ixE-(I+J#bu$StTqGGC*Q=<7q)vs5f1t|VGVm4!?!&B~yqI7Nvc1vuH3h8GEEU+#C z>AaU7^a{eLRGF$>2VPcDLDJSot<)xyrnED5`I zFf4JZfz9zJm#q>cvH;M4<{jv0(OPBXL((iBd3-=|hy*XK{#_cDidbB(s`h(6p(oA- zHW_jB3i{=b?uU4Z;}u%HQRJKA6NBWXM{xbakrC9Snq1O81hsfCi+=}N{N-VJwNudx7{yM+1qQ7WwWZvw`tmASlUC6o}}?f zSU{nuUq!t>ZU3A)al`LH_ZK=dwEQZQ(Yxv3SI!`T5jB5s+MrTH2u_{ zz=+!{4jsROtei`%ys#%>4T-J%3LV@ujc*OURAMtrbFWfSz0W`yI*{s4Kq_Qkvo*!K z*gY5In(Y7Fp4^=i)r#LJc$<_IU^tbKVgqN^QVvso4BSkaS>=4LA}P-Q{MsDJOc8P> z-eTPH>?(Xe zWDC$@ZXQ_oxxtB1gn(wh#&Z&i|CfXF#v1>*I6G4+>ptL>i+y724{>!)nzu(nHj&dCOb_dI{u`;(>QBTBDDTMSHX{pEA3d)vI6@?gS-gr zXd7W1*nZBO`#}Z9U%+}RSedBXTb0u6C9S)IG9o`~^C-Zmd`w%02K`<_rvN>kb#+cqA47Df98b!i7yD`LkGkfiDINQ z7VmdYMB>0tApXDN>YQWF@?7-qfw*MvB-slCYKl!~b82duQ(YA;8B>(LSw#^Z_Z*e3 zd|gB_-#9GirebJno3+O%w&sgx2+#g>a7ARJlNx;OsOg?=(8;n`cQG z^zD{WX}T^qi~uhHuODjRw2vwNB=zc>@x9x6k^ z+vTVFi`66TEqO6?TEt74D8&Mk2w&q@!3>$3QT5hi zXajx2iQa}?>rvF`0>o;R>kqU{9B!Rw|20pH0FmYiBQJnU}NUoE^v#4N{+KZ^SKovpE9hpFBhEZ@_L{-pZR7r$J=VVbz``mr~K}S z4e`j%Po~eQz0(A#fy=b50z}%nI(T0dq7Ou`FZpV6UFn$Gm}P$tja)&prXhZ@heY7TC_5%&0~m{LrR7T$Rs z-43hhTntV*?I18%J2zvbwSkqF6DquXqlgKm!tV)on{{gKN!caLBn*|J0)SLPgqIoq zQ&>yl>}B7*!`tzHW4-e53V&KUrD2c4fx|GM{9(?M)=_hxcrWla6<8z`{T>dbuH?^W@|uRiIwFfbh$x36W$hwU=U z^W|EgPp*%<{u16yL9)tZlE|KDMlT60_}3lz2TRvxEnym^M&2jHXYuTe|3PES-yn?d zrMrPXD2@7uimpEU9+H2N10D=lwip*=prg%7Z8rS6#C$EN3jgOKB`C`>$zO(*d=t=5 z`z$(MuOsHeGxuE8{O5bWf|OxsGGQwNLY~A_(pTgnu0#&32)02r|6%4a0w@s%_EPGL zKUf@NRL~Y`?jE$qXZ*Pt_uD%5HVeGTn|wWT$~*is8QMFRIaWG|y!_MUG>#Wn4Cz%V zNwnU$hGDy1GxVUObzwrob;~0h3J_h(qa`h!2(UaDt*c;Hz`_kDGG4Es?Phh3rp8sq zGkOF{nxZ=k)(n97wKSdvKg6N~sUGuwhGr<4Mo7i6mkk}TEs3|&u|$4 z{IDVP11cr3s2BlV8PrV@Eo|uX+c^!4ayf6tfc$D2CTnzJw~5Xf`ta}2U+6_od&E*S z#5`Z}O!gl3zIeKq%}V^b)Yiz6fz9Rmk~Qy-@qtF!NGfX8%F%4CzG~uC5t;nzc=IcO zgZa5mUY%-CK=pY6z*SHAzfi${+$WJ?;93@!PQAMIajSTaz73B(@!$H1w=So<2vUBAIkM z>5~or%Ds2f%_|Z*>zDtq@Vxi|n)_;g0l&kP&LBvkx_SwoJ}6DQNG&ZRUy3lTXa-aj z8r6U*qU<4QB5mnq0)^IsnBd(gHTWzl6G>tVLrWDf42Y_B{Yu?k9sC4D%;2ctR+oST z7sQy54%(82=9LVyV8=kpH9V<98{lID9(6RgRg%=RYhDl(dcK{MA zU0*0%J*aM`n5s^69r-;*AuQU2r)$bm>mD{lHL8U6(?+L(X;Ah~sA3 z?XCLpZ=tqpUJaz*e|ZomixD}#jD6NQ>dEZ;bn*Jq>s;!(ev+6@M@@GT>nIg{dPbdP z>g)0U59f%4|0CPO#k{h3h^En!F-}6;(x0QS^Qt<(hPRy8g-`QVn{#jC{h>JWM-;Hpd zzzHCXFL4?6qos24Z%!H!J_gLwfPuNp?}stKQ%*C^ z--aS-Yh+X4uOMm#nQj~nB-)U1Kh`2ifh^+i6rdgipi2a)f104W6D#A^!fWeIh|8qvv6_R_m42S=Fc0PL4P4|<7jEG1Cu04U`*R0EW(R|*auaxV_sA^cdt zhHhTxj{>tSGsRZFqko`MzlD~l%s;CEL=R?32yLxK4_WRN{Xb1*zmQT&rtG#c4M@iQ z$z$SSe^MzstJ-liSFpYy2>0EisfPBKAcA@7c)1?I}AK-oT(~&BsO9AQ6s!&hhP;#eeZKG0NOHQrbdWq~tKse1zY;IxxieE#8RDU`Pi2$~9+!25aTnVruZCsKAToI7+!7)n_q za=fSTk5tWV?FGy|+?@L99w`W9j*XfnOjo7E8pnL)L#Pg%cB@rjtDBgE;Gzj(d8g6s6U1 z@Yt%tq9asq@vkvgO4|CxK&^}t!+D05sS~t?B1>boG~A+wQ;S$_afoshYg_(lhG*#i z4F&38!T}l`%!SLQbvl=0u2(!Txle!D1Yb!|HH-baiP@7Nn>9zBSbm)^<7(`()Xy$PcMhHseiF?*)`u_LT^4}X`@jq(j z25DbNCb~vryA)^LPuxDkUSRT$H8_1t!Q_E|c36LGcBaYi;?J{&n216NDmFOMi5y>a zEO=5nBfs1`B10RT>C~LqkxD<{DOks~&BQn3RA!c)VFG?|n%Lfx!7ZuT{reeQ7|N;q zUJ;LrvL=N+{utv1d~IMnCoJqp`Dq7KCWUj%9|+<7O(4#8R2)^rr|c_3=JP{Yk>Z~C!g4FJ;aR2Anv3~mw+-bkB zKy;jU_ik=;467`B*toIO^u^AU)2^G;t-i^X6(bc=IP>&2!I=|!kg$uOwuJcxX&w;oZ#Q+7U54BL)%=$ukHZ?c#c5u zi(~N~$whvDft?MBSq-U`XSA{F0g3=1YbkM8f-$ty3K_3IeU5V$5GSz7v&w|hw7UiN z>G*IYF-;ubkQ#Q>GSTW`ovR##yCh|=)l*D|<4DO-5BHqL-I3TC%?c3qkiaA3+2^^`FS6kZJ7G4fOuMa@9Rt*RO zkQSlQ-r|x1VF&B#PQ^xiQA&6_lnZ6*w8G|eV1fH8=HugTXB1hk6fVJe!B5{=vyOfS zSc9seHX+pp3yav&Pf%RK2W3wHkdMLc1$e?A*b8uzyBImw@3OYXj$Y2xPoXmwpR|QM z?)&Vg5&Q%uqSiKq9`h`$Ex`DG`Tr02^S$#;6uf`8*z>i^=ajQzpEVBnpBV7#pbl=E z6Ny9>vb!k^~>maGo6J9 z$B^+xFeED6fz&&Otm%8a%1Fm%l32z@%IAOcl>9168q_uv!EXYk$Cco==@)^7Pgj<@ z?W@1MJa=-8zM}A#!+t@sdixeN>B_LR%9_mUD8;LRO36S5ipS za&l|9lafv&FD|7(+s6Su7UJ~q6py5b7ioO3im0nQM@7T9=O{Vk<;0!0>!Y%=fVslT znt~0F3I^k5+h6fR56({+Pky*Pg~6Kc`_DD>n-e|5Ehhf$<>l5gv+HmsC=O9=LWq1k z7Zo?8P2!e9K(k{@L)9}Vq*5M0y--FL%k-}(*a};~PvWy*Ecr*~jP;|cB?JA>C$*kd z?0T`9(X`zaL~4WzT%}z1kr|&x39F6l@o|x(JK@j+#NYoe&FP2l{u@Sb>vzWQ?l-^d z4j8$lwI3@a4%u3tA1o~IflZO@27h6%T4muNkB_*+F(85CATX#w|3Jkld2d# z>Y-YxzkTG>aejV%dbo=hBs<_g-Fo}uo7i?rB#TOea)Z*gk3x}`ujQf)(A|&0l_ODO zQ&&yryMMusl5oKV+n96UHc>o*D9!J$ARrQvc);pQR+Zgv+IOGmA(oM=v4t}Nv4uM?IV59mGYsc}X1Bn{~aq=Nz`rS6_NHAifp zJmu$S>*yB6aljbdjxXPG4tx#;!ZBi@TN6zVyOJrk*ky~euH{b^qEEubo-1<^{}g)8 zHvwt39yVu6rn@7w;0Y9xOD9%(SH7A3A_7q>x3;hyIXFyJLB}(fmYB^xZa+A&U-iame%=F_TzbfifQO!sK z{;oqu8uEA~_FkgT+T!oTL+jh{|+3Em#Eu6)e&)$bZ|1eQVUK3YlIV_npJY=K}{ zGI&2r9E+J*M)$^M!f*WdPBAb($FLZ>&w@dy`jP5e3RB-P;bGsl&wQH4g}(jm54ZP5 zvB-sCu6eG)+eths2tEZ#6`0&(BCmx&5PB)4UjtP&=7}5>FVh zCPYuz08n?(|vhixfkb@tofv&RXKpi{4`0_k^(tpekXJgyRI zQQU#heDn)~jfF$;D5;HDFPH;6Ml<4V!Ii7&AG*#z=ICP&O&InS^oDlf$Mt_2N&3;O zpGDG(H^`$&WA7XXTX(e!m@}XaGSBaSe++1uJKK_NI~9By{6X1&=B2s*o@63*Ukj_^X~X|Z zb%Oz15?MPE|4euqDV*f#v;pCk!ei^M6X)a-?MN5~U+3{RCT?~l(&LInD|lf|6DE=> z02qC+VAtZLgPu_!BdT51sQQO#ecMnMB~Nh&o5E+q1MV_Xg&PUL$;?L`BIj4mCQT_8 zQw~CdRuvJmhBrgr%B-%uc}~!6&f&Ynq5Z^%vRG?UATlR%DC)b!ab8ZlZA(&>(Eg)X z@ug>dv;<$Z$lsCLCiq}cbn8&(HESB~O_8mL`viGOX^TFGx1VQkRtJ0szv@7Q z-y+vZobfEFGqBi&bE7V2Qm#RXj=L?Dt?6^cM*zR(kq-GM#j^en)V7vcOX50U_F32Q__$x=X~cxTCbYAxRh zelwzIgI=R$IhXhgbo=gL{HP5z3Cy9J8o){yEb|>6^lDP{_ff!wA zX}I71GPb&y`{1rWdnmf|?)nG`it)UF-^krhJ50-1M;?S?tousEwyBoWkbXe=UPV`3 z2cyUfLB&UiQJ2~hd;Z`9)wfra_I;p~m=y-K!a}$ItQeJ=ozF=aRZDBWgfrw~7!wll z;B}s@`Z!x&ow_$H0s`Oc-G_T9eMQqU9FbbBwoXRigLF2r-Vs@J; zcz>x3MchzZ?5OL5nrsq$4<1y?NNTH-WlS4v)U>Ck9eK+5&8=o5)#nD~@AzSMW&OA4 zWm1)krI^2OEDp^W3#>(L$u^pr_Ij|#E#X6aBSmV|Pr{+WNlEvEbeSfxl+A9gPy57G zil)Ua8r_Tfooraf?F%^H(`4|9OU=R(?(S!Q3!Te&t-lFWnCgMz6Y%^??7$9?;VblZ z_$5ZGc04zbK<_gMi)nURFf0y_8`I=5l^I>BJ0-Y(lpzfu1sAgd=s zfMwR#*LHic|F@@{w+iQ$D-%vy$7Za6mQDvXX9LllfnYGJI0$|gQSWq!CaN+`m z;Sj$0)t{iKarulSLWS)z_|mab%TkGC^b9C^n^u^B72VPrF*hd{@-8af=?0s3`|EyN zF4So80?O_EcWmme5T(70=1clnkvrn@{tp6KdHs7C?Dv}n3j7y&kts7Vdp@ChPP>x6 zp{9r3&TA9mHpf)Yvrdayx)rJ$;#~VWKSGq|e%BDzMh$sW6M<9|&eATcJbRA#`qm4q zB}`fa=@*y8*xVHXM%rC|+vTO%HYep-Bj2F>Mn!d2)S1$2bq~{34uPfycxZfZZAQW1 z^@BO8UJ0t2eOHf*47$%I1&492djcCRg<@3nHR?jxsEhmba#=m3dG$kd=C{YFr`UKw zG^>wX41||oG>jK&NUX$>dJE-uK0U^JUNR1(hdZ&dZH7p#{6eziB4PF3@WIG#!s~fg z-h?z+yhb5prY1upJn6{9c3jXmu#BVN*qA0K1?X`sqb>G?w1k-c^=lnYH~gX?Ox{m* zh<)hj?IN&YjKFIyC_rIN7~P#FUq~%=kBqCh>z^Log4W*;4_`Q4z2{!8vwKfyOBUTa zyxRY?!p9|VF%VYI3m@0a@qfZ?bnsq-%fgsroXh$kFj@Cvc$4ojesC9x5I9@~T#>9~ zSRBTS1O6G=oJ=n{1|GLk99id31BbwagBSUqa6o zMAa$yl0((N*FgTIo^KAfAJoS&_%!WW?QF586Nmh^4@s>Bx|L_Y_tPsI5+Bk|8Q3t$ zs7n009-b&9WtCj&BoY@uBIiJaL^uG=w%5!2f>Nv71L#SZC#LXXb;8;`ZkG8TJc4}< zM=oj_G7qR}99boC`Ya{L&u72t|Jc#rEn}IG;2qRhcYCis+lgF8ok`!~FD>}T&sE>U zq}Z7nBeD3W6lszAk#N-Et&2_vIU7*YNAUTktx=$_pF#t`(Prfi{SMyn@*iF&rG@+17m4ZwQaCs(a;Vaw7i4K@b<> ze%5YMhPAJo`(_IxqD8d4yus*vbC_+dMb$B%kmg-v`~LeC-TNfAnts$cWPl9};RNnl z@$(t-kLCRsxV4^8enu$l3oiKZUBnqMwxOoNbYIS8Yx8qv2WSZ!;Y0w^-rjy=QEp=) z#sztCgoa47TqDT>`K^!aP488 z)@bo9yJm@}#HoJUh5wUiRQ`gs)D~1m%@FdPTu%J0OM%Q)%Z6PUsb1k>@?*G+%-DWz z$XI}B43q-g?F8NT%LdknZH3!R*4FnkT!qvrJCT59bo|R5V1D>IW1lWC6*4F`v$L!X0Ibm8M+ z17C#%;h=lZvI&>SeI@}isX>fF4)>4ITv*ep?Lz!O!f6Ro$9>3z1ouJh2Z8Aj05wuq zFHQ+cKpOFKDdJ5{eBTD^L1pS1zh^A}59|{%Z}9cwwq?X9!-lM+AL3mtmzh0~|A}g; z+6C|d`!HB>Ww__|eej^K8`lT@j4??5^!RH=DS2#kvy$L$sLmpFn!^`N-COFS5}h+8(y( zkm!t3#}JtJkdYjx%+9V+e-Y7^FgpOTWoqr|(a>}JCr8z(yNshOJVdE=cc%XI`f*=* zYmlmaSwz9sUC74uWGQvj_e6Q`@qKY*0StiiKF_)|!)Rgw&f@=_Zq@aN%=83DbYfxo z)gX#=G&2CdR#o?3Y+s#3eb3nGsEHt5%=@f;%n%XZY;hBFkkZKFYO zmJ=+BGV#Jqx*V{pbebdM@`Ib2xtq!X@2-Q?I2Kn$@`@Kh%=R}{ES*d|2fZX$z(O!m z)5O-*aDY1hw^BbxtXg=dW7&n13z>4~GLBojRq_@Gjj;gZM7?vn}YbUHFHFR-4J zcErniY(LBf51faB4BqEssR?ge(^RXt8L#vAuQ4)2cs@fZ!m(et;A}Y1AMwKIpb)&+ z`c88Dyp0{;diW`pWtPpbCX(J=d`lT&w8C#(-M?F0>$-4;21^sbeV|ysuM=BQ!=Ke0 zUMA^ONLKV0joOHBoIuj56g$y5&sy1)Q=_ib(amT}%Dm!%$|qH0$kBlO`?;hXNw2_s z#Ycftht2*HY8cD377aaZhG}vCiT-BS=5?>=J`f;&RH8UN$yIWwY8rz|5UW94dlpv` zVe>DFEua|y-S-sSVLDn1Cr3+=CryeBd^0^bNFLpHwM(PzoV2knx3Wt&AT&SlkxyKT z9{Z6lEe`fl{dpJr?tTF<2$MNmWfEW6uIVBZ=SkOe7MkB zD@WhJ;mH;?aj0}F_Vr$*2j3(U6BF0TcZW}MZ~Y7!p+SSx5%ei!L=ydSKhm=CTW6iZ z{{Bxu9=3w>!~!EQP2z?xWB^{tG=C>MTs#WsHdp5I1hR)9I~t{yUS8aJ?e(h4=zdxR zt@--%jM@Ib39Vk&sQ;VL3PY69A7ED06=bF|FswmVFCTUqVHXP*uJ!$ShaY1)dD z{p3p|iW}JNmiG0lu#V{{d3${V_I&1+61OU3#dR7lXfozstm@q0*8b!%$v`?-1B`d#7QZF%9 zj0xpoWX+?IBrX{$ZMU~KMdrKz+sJLBLEr5zT3w=QgRKAfmDLeWKUG2DYnC?1X;XI( zkUJ2Qalyh-D@gNpRc;InaLhe-Ct^d;CyI0o+TBtoA5Pp8KmPQvQKB3%)0yecz7;Tq zl5g8ONU^}3V0QmTUF*6a%)tpMbfk1J{2Vg^6qnhpf{o#%%AEf}*-RC?Yy!f(M_L{s zRc6#B)c(oaY~WQ{`?C6gzWWGsCI~<*=Iizp3`1s@KX#uf|6bK0B!cz)xZ60Q88u(G zbtym$Q7?e53hD2rs_AQvXc!f^7!~lh9*y$^w_Glefo@UT6Ia zjNopkVbIXbYYn58av|N=bTO|ov?3DJEIlolyB*xNE>qTc{zwuk?qlq;_fYVxF)CvB zZXgnQSTjGvzM?cVO5C{hM5|Z^9(jo5YU2Y0St);NW;+sN>-2~Jnss!v5hd)B(zBdQu(}%|wc6_Pxp~TE@X-Y_A1>>`R0Jbb5*qS9--dEPbDq zpK;Dd3faM)RvjAv@5g&w)~LG9Bh7-(D=PtFZ~d~4RhB0VUH{ak+=U7p0hua@tZeNJ zt7W#Z)6>=jq2k68c8l$Amcpc|`PDU#hmwxf=5-XNVFk`blCChS3|FR5i#Q8`u(>%= z_>TflmBokZaFT67oge5y?d&t#CaJN9DFs9n$2ecV$$WaS))x-Y32^3%b-iH|Eg9U& zSA*$FC+=y@{(_Rum$6BiMT4YF;}3?J^^^b8Vx5NC8$&c6(iDp;f5BsboWjdE-6G4aumDR|2>O`XToG=n;l{;%u@#b06pZ-RSG1n5)I5omP0G?z{WAT>! zB~8XW=zy{i+`(7^(cJSP0$Z~NI0LV$Eu0zZWSX6)fW=T9Ga%jdi>{#v1x=M@;gfY^ ziNCaiUcSepIQd%?*lZ@!R4kWu>tNK0j+)vywGK(RrNQ!-4S>R*2-6PT`RtL9>J!n# z+DZ$OObYO2_otb+6(F6Gk2(>YCI+{nQzH6ic>B z-N!EY5V!p_HUE=)7o<=SO#<_sGLA_sJv<|X8=BJuEn|b*DC^RiH7&CK0j?4kw=cEs z%xCKA<_rE*RD_>UHAPR9l$2U?0)aY-SiFUq^oEX8(NV{!lfM(Nt{9%Ia*v^trE`|4 zALUBrP%I8L`*rH9tSw*5R)oEeC5S}@0E76~fe;KF)C<8E*O9mUw6wo}2bUi{J+0K< z7^9CIi2?+t=b--5g+yl+xPb8w#mtfpt|JttjNT`VNxtcPnH-uLO8A2Q=3(krV ztEZah--@i;Rew&D!7y@Xp*S8Fn6O=HS>MnKgLQU0;`cZc) z=JUe2KKM8Xb8!obfMag}Ngn~Zp^_TDG|xZYed&0})T*_py>NY~3xe1K+ergQO@LD* z8-6M*_thfwfhVoSu5<-g$m;O2}1bDnsxcV)7(SE`0 zbRSet$vQ@RVwQK>wtMhLs2YLx`fsdaQU?PqX^o<SafGL71>Sp$PE_f%jE}zKyC122(9o88X$z6#J}0NjB<#aqMw; zOGq|w?`mvlB{R~2*-Qf^EF(vN3u^LBDC>bZiS~;x$6BFH;G6&bzH4G3A~;fMbK8Wy z4-yI*b2Io=E&BsxEwE}0{6*VM-9=mT=;7l7p<}Xr3!vO|T=wHv*+!Ecg6ZpO$LbMQpizsf7IT7pR*Kf*(jXh`aH+|;aMI$OM-yA88ei46_=O3Ms z4@2rrn@3n~Nq-vd*lUV=A@i0t&*;?8<@HZ8vBq!UVGzK*IFCN81^HWEN59b3drrmr zLuq?S^U`QTf*$yHA5$H#yq#n+n&c@%x3J+!filzC$=%J#5f|k6g3P9;t(!=QLyt`v z*SHh|R_VXLzN%J^O6lUO#T5wng0>zU!4DiUVfTr;xalCYCb0cd4@8jerBmc`L_kAI z7Z{8`yP1A=d-Fz}gWLk$%q_9lczBv(md=>}OU)Trk34$9g#Q_i;;>zDnE~l3v2c*D zV_Xk9e-LzA5T2JU6uI`JIN~5dHzQe*knI`L#-fF=?-8jG@|k&I)JOni8-wV9{Sp|H zll{~i$*Hb==Lrin&G%2G%7@p0WCK1*d-z(gp+jdgiCJ32-gE_4wK=g=$56mPf{ipB z)$lm&*0#wcHDS>oC0+lsK`G%o2TF;96o*PgF*E&c`yrFpX+LIt1{^ZnAvEK9-y z%fvr*`N3LNiGwI8n=snRH`0+U*Q>Ow6$Zbk#Tu2m=QQ&DkLby8j26kK~o&ziNq^rmNwT!y}QS7fU z1Q&+qzO%bSoNd1#nyIjAdhB8&*N9^3WQ8h0Vx}}=oK{GLw>qB^$Jbw_vr*nu@xM$4 zN_%|C?q)3hhM@OU8;zS&u;dY2pq65Gv!>F{iot&Abn6{qJUBavy(ElA6U^=lw#OAo z%qQb_G?==c9rD|TH8D(QOQ#aCq`|lw)Yem_0J@)BEZfb*UYm=kf*U9_26Zoa^`Bz{ zyrfx@&{qrZ`@{|bP2o%g)!b@K)Ig!@X6ST>zP90*fY)I>(90$U_!srlyb7Y62?`P0 zSGzW+83Pb!VPi4ndp-vL6Xp)3+9Ri&W#^3AsL9A6u$@spd?%8lv=XB=-7L*<*Y0XK zwz|FG(8h0L1F&ac4Q}jC12sP`V|7GzD;s(DbaV~Or$}&EdaXL1(05fE6+P9H|Ka~9 zAFl$OOEYOjnLTMfIag4To$2L6EE_zI!P$wp<77#nn6EAITrm>Pza!Y>qmIwp7EWgE z?7vAHV2oRbiW9^k-_lahrMgmwIyTa=m$F@bm{&mSi^=IL3M<2uzbN}SRHBkfTVIm6 zM0e^vg$e6W6_7z`{GLeSg8d3)$03D)h;%8}bdp}LLfS_sUjR5QLxZ0IgB5s4`$$iz zX90M}!{q_xojGLR$B79Y-)~}i`N?&Gp?&!ICGadK{a9n6QAa9RC;yr;hxI4+SarU~ z??LpJ7d+JIr_w%USa52NeN2kA#6P|AJ$_2g$)uKQ%wCQd-{oFew7 z*XZF;6YA$r-K)O=Pd-~~MEAnm{@FOHWOq58fWJ;jO{ODb1Xn>$+&&tCWJ=MmVc%MD zS^wu~|GA){)bY{9e5_&E_nq=T-b~&?Q5U*_k3JqQPQNEc#~LtmT3M5GMC`M4YU*=x z?iW+;#5|%RAHmkEB*JTFLLE(REW+yQ)*T+HdU1g|OYV>EHZ7JhU5}w_TYj1xPyw$2 zKD#T(Q6~l8%|3f7D7uM$G+C)D6QrS&=0(0dAFtLRbls9A1liE(?3jz7eSC{mue!tt zoGjt5ayClEpq#F@4yC61=d9TPRRm^TGJ=0OD}OjFEIMNO6$g2QO8lYL93!+5 zDD*V1(z*_RvHS?e(m=@%GR5tw7E2q>@lc~EjN_5OJ+&pWB&8)gmk|J`+#SR17v>^W zji`!~5zN>KsV6jYsP415x^xi|LI${5=(NshP=F9FBou4RPYgs7xo+EI?XUQqPXZQ= zB~GpG9^MVk1v#J5i;Fu12_~ln6(Ur6zbDsu-1y#cf^Ijy&8*yGM9sSlZ|ECMrWj|i1w~1R+%wzJEo2y9D zd@sl#@{|Qs1zzuNhrW%Y06w16#Aq*H5q8;%`KTz|_F|B@#*}4=?ISbOt8&?MAE9EbjGkR?}0gZ^c9H_6WLEghhG$ zy6#wJ4*;!W8-V1waW_F{=JPHT@C!R?9_K8|`Omqv;!*^3;I3}GP?6|X_I#z1^D3y8 zy$zV-`?9&WY=P>EbnAfjDRth@*vVGZzT4LXSruaX{Uqp>T!8d%rLEZ@vCGFh@O+*E zH|?fkbIj9kBjzJ=zJThrxB!Y9&(2lY>fz4vZyswy>SV8aRu}P8+@IL>Hx44q*HUPR znzOyboBg_!II9_Ts{RA=yel-%1-=a{r`TqvX}IxU60mfLT2qIE{wdF5WPZ3t`PuY- zg647QY$)&>@Hvkyr~E8ztvZHAS+u)6`HhUAo z&*Qog&2xB&%F0JUE2~OESp3v=#*apj-m;_IlR$?#Y{NdzEH{#T{-qtiXVc#MX{{|n zqB0wE{;$R@J>_D3r0a4^*CJonB_p);NREFnUBA{q>r>a67h?rL(O72I^h%JR!%;p6 z+K^h0L71EHvrFc^?DyueIzF%VGV#={F_H-Hja>v5FcXMo1CH1((fYB z@^>a$RbQ$5*rpE zJSq)ljWgTQ*Q+f^NWG=m_wdbk#}EOl))ZS?0WYKefnMMQ$k!>;oOYx>27}5 zp)q+FmaPf%kdLF#dm5q{N|l@pX@Zx6^RF2b+h{8s$MUzNy0`lb;Bq>b}C zlm4I7ScnW-o?ks4M0(p5M@P%D(0+Mvtom6#&W$+KfnXSee@TUZ&~G4y@8OL7GH*aF z5!{gJsqTeD5`S2(WuD1Y{Q%BdRc3?h zCUCFKnrKO`0{8Ko#cfIJX)(-R8uaESJ7#xZr9@!g77--Z7_YY*qJ_3MlB3q?0u(U& zKs+okMb*|F5+>!G&$cA_n2asa7TbuLHfzfJ@kXN7KrSDK3g?0H~#AHdj%!+53L z0ON2(N5&zY_=DH5iB_{QPHj;4MIvxU*pw*Xe!F~;wExb}>x*}Lu2P%sXjV}R(!&8X z><*trrS0K0()+WQiT(!AO=ptd+0ya71dB15rATv(@Wv-n!CUUE9sBAa+5-I3TgEp% zN%ZtWoL?^xdN>D3h5guz8+c*Ozml1oyxSz~xl<}mw={9x z07SSsj-^qgAvF#gv+O9uE}cAyuAJ(Yr@7{-I^=?MGIxV8@=om-V_WY)WYz(~?(uAX zhjaGn1mgF8KAw-d1`lwKrQKj;(aTIJ(yv<4Zt?QQJ$*+?CO(*Rui8iAdDS`&j-8mj zZ70>UIBnX-^8_Vhx2bd6pj*?y&Ax+^VB(lcokpiQ~-&W!FpG( zUvOkIc_T`$(C0kg_-W7#Zhd9Uyuq$Z>zjb5#;o#wfej*M9Z!Zl7m8x_4=x47c@5gS z6*uprOc4UlaS=So@SWeuRQYDH={fPaX2wQ@yORqj8}u~Lk{M>lcNJszq=+qj3G!~W zSY&LhihWDJ)*=o989mzv;R$*GNZ$JyYNHnAx&@TV-~MhLX62tJI0YKl_bT8x=$%A`o09#i8*uVol|9eH{}QR zzd*l-2C{z;W1+>h}lxFRMR!a_h6Uv zXy;MCoHNs$XS7h6Gq0u_6|DZwXU{=|lWpNG2JuTbm2hdlYXy0%(b%tDUoV1vd|0SY z-x5?u`gvY1rP+FJzT)Mk8CrLBxOr8fZ6l;DcT}!5h{G9s$XveHv{#S5nC*0B4e&5i zzDxb5Ioe3|N^)~J$WT(lU3|^xf|^3YP_U|ptw(iD{V1HkqdH@X3b%*z=>`G-jo^HE zcx-%c7ELh~xpAoXC{<-(=mR`dZ4(QKIweB8bhe_-CBrKY6QCvGP25$Ft$8G4D)BdL zbk?2`1+{FwlO|)Y#=*WCrM?7^5<$sbVaTfRg=#m#s4Yn$=PLhOay$jGPXcLK$oO`NT`w)hmkG@8zfRsAOBV^TFeVz5se>n0cV7iOZVr@Rq* zA1zX8V`afA5jVPC!32$i3w{VAgox-n@n-BPkJiR8zCQO8z{arobLLmSAtCsj&bW7E z!{wd@*jlA9j@*ivmC6~D_R|-GNROpc?IqAxQk$bfuo;v9I#+171ozSRNLJAMTVuGH z%RM1W^z1el9i*h~^Wgfj>8AJX>f?C2DR$J$G+{32-nsGC!2_0zleS2m)9qE}Ji3tv zznhRh^jOa`*E}Y&hoka+m?>l!U-{C!a~D8Vn?}9rfaUHzcGTTn3H1J>KI5QiS?O5% zQsHiWUfc*Eu{j8vY%+;X{H2MoHdk#Fhk&ZjN84Mx0<>ji`?E(;-JLmG;6vhx8<=LcR#IT%v~Lsv}KT8S(qkmpGURALYg@ zoS#)suga#@%ISlUNsAzQV!xh}ywMq}_ls%l=B<9I5X`lB?H#B*CGm_>iIyfAxy%4W z32LM4i|OrZDa8I}Lci+F16)W&GYje1X7tNDHBa@en{|wa)zVtorp<3JBaatsg0;q9 z^2av`TI@3Kv^T-AL6ZiSIr4A5%=!-#7u5%4A1KOCG;MwA(wfLai_326d~j{_If_tO zf4*uN9FrMOhCpFhUL6J$^w4IUq324^VplPo?CPkc?3T4@cepy^K1idrQkaMFX@le9 zFhUj4dnxBsi+sPvn+nuqA^Ik29svi@0;Mll*P;oJ=3}gBerg+G{>MybxIF99d&V3V z11Omni{KW%*(UKEH0i-M1GbIyDph_fIp~&K-hq7TZK9GtQ69yF*R!9}a$O&{b}eWz zKDMEZ2RfwN`s0*u&+2z+>$Y zkL5S{Hy7(b)p^2gQqRE}5ykC}@$R`)Bp3?@t zKXj_Gx*wHip`(bRS8Kp1qA-PFzTfnx!-y62UOmnX^jWZ(we zE=aiAAJRafTdgEqO0TwdYFW$p`d8T?duq94XWfQM!1e(>i>GUaLENqI67TE1&eP&q z9#>ZL4F{Y2aU8Qak?;YmEn)b>;onyhP2HO}z9C0M$EpdHrCa5|K9pZ$E=0yyVjSD^q}|AMmOpRzx~ zxK%u;+nOp?^@s8tYDMLMJ~GJ_GAXbPnV;?pY^x@B@;@JiZs&}2D9?S3j6Yc%_`-v+ z)VtR4aSq~B=m(_}At^eUkEe0wD!;@tu4EO-3BxysxbL6o?96 z=4Xh1PgcmT!UbSB!a&@If2poYkbd7X@ES*4yCII0ykPxQIYM@oks_Au5CvZ}jttpdAI;KBhL2#oNDQl#hlr zd=5m2D1MUOa%7&e_pio?G{?@$pu7bui}}ZWC*L}&g9+|%efzqiR+e?md^`BwPmZtr z@^q^9_*oQ3W@qP}!F6djEKayRO%TgCP1CDhLMV?NnJrO3Z$XCeCOTY++?LiWeur}F z7wd*IE6xPbc6vc{_DyN?k{bCEqIOFH4zXzKwX#L4sc;+K5MT@xY zI7sTFC7y4Ft-w|Ddk!j8znYwGggG`*h-W^{9*{Up1ti*5)%o*b{|?~Q#lu!eGCk=& zg1u;)yo`v^Ohejr-+D77z7gsPaaRkA9I0NX^^oBydfHj6#4^XWEXbx(X@$RfiKVGa z*Ac4Na7h|!8{~Jjh8`;{#=cWxH@A~9X^O5kBpYx31Z~B{FW4kEa`gpN0Tsy25s=!I zZz=HmDt}opF!o%F3g2EWqsAmiuyeQ=f6N&3RPK+EU==)SGAs`F^qZH)3BP8%MfIxs z%=6r!bFxI0=BSB({Gr+*R$fEtU09-Q!T9}_&o=f>SsE&G_T%rJd&KC8mVgQwR;r5& z3%`x<0s#wjZoa+%;J|`y&XcFCaoVXW87D2)kV!)J6TSG5uo-LN+x#W!b@s6DKy{PD z)E^$dJJy@I$Au)T%7J9|IvB5C$KoHhW_Qb7{6J3&NTk1HOVFGIx|E6mfYHQ5NXuJ) z4oFtls+{YNXgoFmkT)D9F_fgJFXm;fRM=%zA|)U)x4$Wx7^C$Gd3iNV{z<^0f)sF1 z=NKyCB-o{Ke)-1hnut=ne5I$K;i`R=pho7YM%@26&ToFmeqxkdb4Ty=$#vP}p}^1m zg176>*OJvC9oOmQ#d>j$x`(Ot#uS4q123;~wybL>RS9A*;I*cfLrL?FUCRW$gY{DD zlr->9B%8LLdI>Sd%;8#_^$g?cPH=Hxz&))2iWH6$7vZFzbD6%$UiK4jH#Y zj&`zXA8^#yfYRZQ(AzXL5E$o|8ATNnplN#fHx`A6EfCgZ_mPhpDDi{jzX7%<*V{9U zix@+f*5%jHoXIz?y8npJwvh)9(RGo(W5X%l6($ALhIbGgofpQtD$ooS+Xyz2fZ(o# zO2!F{94%@}!~T9?Wx7*P3PxM-@8+aNOoaL3Vp{(#hy`LbzZ1wTg6Dm#ZGgF+Qp#T~ zR7P>=#C)TaP#n*>5kosp6NaK>Y|h_tX?L^M z#zcz+zGCEYTL*o#geyAB^o-&PJYJGp8FN3hKaXRdc;baEVO^-W!9a7xmE1+}55FQ> zddj!GSV=Om_I7z-(Y?L8furAuZM08rj6~h(;^LUGrl(u(x1v+Pu60*84$Y(3Y{Qhw zzCH0TJ0Ee)Ukgm>_-$i+cu~jDhH%qC=MxIZjyM-46+dUXpC^jNe59mUWNEYLx@3(?Si0LV*pawj_zs~9U$LQ06FWSs zo0>loNN^hQ?WKUJj2(3(RW; zj@L~a{-*{Uy=`t!S!OverZYohSXS7hTPxu(cDN0)5V)q;vUd{N1@Gx8M+cmvm z0g2StHj^1S3wC*nFhYLUvyf!3?-)!y)ZYG@u!DCyF(NXBRbictD>%|@g2ZkyTkv*GKQZG-bMfrndMFA_Xz*hyk&*<-?lyrxwEYDIE^eR&r-N&aI zKIHLt?K7|5W!5b0_E=se@RhYsJ#pi3_d?R1j98jcST1p%KUB;V zGc!hsbhyv(f1w{#XhLwhL!nV#Zi_w>nDK{U&gZ^&m}{nNK;!bK$|oPQ-evk5Q1^!D z1XrVzLYh^xI$Jls#Qj>9+Bn{TK`}f-LAR6D7(1(+Fta@^h33JYA!MB}O85G>@?$`C zK@m$F?{kFFsDiDMIr~W6H6fO}ABaCQZZgOPB5-99bvn4Xv3LV4qVUf)E;>Y}xmerlmc zBR^EIR_T=@O6mScvzFbq)%MY9(0qx7yLz$Q$_&x37s*I^GjFJZ-)6p?>^VosouroA z13LA)Oiq+PM>F5!NdqQCywY|0kky+{mendrQ@f&~T_IKaJQZhYw!;fpMimiVX`CT>6ZzRYo zSo?Y}LfjCTo*p`;SAVp25|%XX&z%)gHaF!x%{E(w^gE@_@ICeRVP{jfUSvTs{RaNn zzbSp}*iyd_IqQ)^xR7=5dz!0h8#=6qnER31Iq+f}jCJl67L$_dt4R~JNeMo#u4n8i zaed(@pHW$2uvFAr}VmcHG&E5;pwoI=N`Q zn(}BSUSvc?oAt6Hx5GU@^K$n6gq+PaoZgF;xHTA!C(dwfyNaeu_BvTjS9*MbHZxXi zuna3!oiX~(JlYS5c<8O%?Hb*tpgIn9$Ri2D7ZDd&gY)H zh9+TMiQoNlRGR&OfcNG4U8g*3wHB+yJ5Dj;!}iun+;u}Re8ljhoAR*yOC{`yB7yr01x1( zK^@P$dhdcLRg-FLNkzuJH9{eC5Jgh>OzqT{X6~soG7#~_I*8U87AJvN|Gm{sUMQ0? zKwt}5F{qc?USe7UM_xpd&T0R3M9@P5RzIdx7@ciH zc!Cz&yNOLR4!bA{8;p%3LhY(xq^OqRkivdSUmCxPD|oCeSVj1}EpidxJdI8^J=IN9 ze5;F#TW!<~^M@~u8lTPHhr9kAck|m=mRuuxlr)*bWLI&4{oHPW=vUSpU4&VN*vqYY zjLvAOhVie}IVSuj@Xe7mL)JQ`P~3m?3o$8p+>+M=yxa56a1!#UH1Sb+d1Xw~GsN3I zJKySiDUII@6LbsW`l_Ou+yT4J+8GpyVOmzxbdE}E$kVymYRN0U$w? z!mKX)411&G!emj=?D9Q27VPW z_P51Q;ivIemcumv-~xq!{lXXK7g)z8=K?o0uf~(N(AS%M)Uh6E9-APL8^M#+qQbM3%|c%mW0RnD>#K8j#>q1x?)4lY;so0jqI;$3;f+fHfc z$(Fze3f4ql?rYPuVePBYeC1JRr0hF8^dbjq1(LXKh1vYaWJOV8oxw9qdivOKO@=>* zwUcxm0)N6-3(aAoZXqGG$+xuYZTX0dF1zay{3FR?@#|17v&SS){a zb*?Z|aWip1lh7-YaeEr~d#LrNzz$BnfE>=9E3X*#01>6BS`QEA|3lEGtfpe1AIOghX>DR2qFiD6iN3} zsa7Su{fvBO$7+KCV^JRV`7pZ9>p@(a${H|LVBpM?fz{ zq7mIORcY;T*jJw|=@%l3Mi&cSgb}Saq#-Qmr~Ev9^sJrjBoj>eCdXZg!TcMONx;WB zu}>YISf99QpJnbT2ahXzKeFvnQaDY29Z3H~GsVuFOjlx+<$o!+{>$k%RN&7d)#Pry zAKKNH2S% zq>UmyUfou>be;3)X!&aSqY zRB8?RuVfwbgYjIh_9B9)ezIb5p4@OzFpL(4ng-2?)zPv6i)vKUab4ue&Njo^C7SFY zSucDNM|^xL$XCudOC6FWdodDpcbG^UACJ7v<3I7iMMldtHM|9@*5Ni8<{d@TG&4P} zunqkfPTl!Xhk2i}@nT>Z%O9%}rq=UeT#$}< z1Ig|?Cl0d4n>H9@kNQ&u*`_hS%+=TQT7EAd$stWe6OXIgyV~!Z`%qQ5wFgQobbIjQLAc!Ft%>4Ou*wKkFn?ky5K9_vM$pYK4_04jk`>_k$^ zedpV6ck~GL*2^Dkc@TpkV=X$8b7L(DLfFVIC=Y<^MK70;B-^{!ftEpJk}=L3@kdMV zUZC+kV(&AcJv(q<3;=FDw zPeJE-_L$s>obm3nl*JCSHE*bYwXc)9$jS9)*5-}d*^=vB!YPz%%6E@ll>mXUpx2HVx8ryzw*oGyhdwNwoq8N6U*1uCT649Z+2 zn)s8y3RyUaR8jFR1Hm%q+jwzT^3_bhi(3u8BeqP&gM~_?g6Sg{VoC@{2G@ycCx@@@ z*FES7jm$>(F5kiLP=!F$5Ba<(wKs+Y7{o_quqDyATYm&} z3CQZ-J=H6S+wuHUhe-V>m?hx2i|FdKF15Ps7#ULQgxEW=L&a|Df8^3s%nkzY{mjOYx=aO zx`df>*|^^Ah&;C*B<~L!D%Ra8C+mmpNqu|X`rk8mjx&=%5s0sgIe$VLh+}&Z>iM@r zP*fMa+xYYNmZl+gvGlhKRy@sajT?tPms-o$5b^eF4+$jdfR*~N^weQ~NLrOsq_A0) zQ}jJc{0&kRIL^plm|8!GzwlOOp^$hAbAQoz&1g;2Kccht!QIO*HQi|g#4B3xRwmo! z+wXem3D)m$7aP%igJvTdn=w<$;c|}KPncJoC&6x8A6s2bdiGWglzUQq(n6ztP*N^9 zB~6CV#jdcUgDO>i1GHO7YoTcd<;J1tJJEA8(hB*MoiiM39!k1Pr5sPmwYp~V$q<}B zF}=Z5;ele1i#dHUWr-C41g9@NE=kfPqT z+)=|E8gO{`-Z52`6>jU%4HE^PW&m3pKDDuBiB8GILR&`G4fZAiwcyI_8afXjeNKh* z8n|v}4p%`&?$f@DFWi)UqmFAcPGbRM>7sMW2c1Wij#3pOi@eOP{$osNW3+_(-WjV7 z!#m1WU58_UPgwY@6)hsHsObsr*4QPq_1WIU0Jg50MbB~Yu z89gsM2FBR*jQU1mpDGl-B^W8)#br*Jzyl5BgvkoqGAMvbdc_eonX~un8sjPl; z6X(7m#C)a-c`gr}L4}3cdMc*qxzU;fwPiSR`qm)NPGV^A-%$ex0+jpoIcbV$hr6E^ zw_1P16_$(kXgLz(W9s7?DGSlFeYIKO@o%F!=urr;1)Q+odv6%<>BvLArv+FQdLN8k zWlZr|4U>Z)oju@ctmv|-*v}in2$ubbq@wkzo(-u@tjphN zVJF|=FS#eJK+hXh(teaHbX{h6xHfId&1Libt-N)5Ope8Y&HCPx{1I^l=-%&+ThGvy{7_6KD&M0tb6+sVM_UBeZQ{Un{C;v-IYr|Gs!?vfk*?wyv9Df+B&;N z z=>IbvbB=E&kam7p>XT+OmR>Vb0TRLg?So0 zrDiX&v$`C83s65APm&m>-J0c~&TLA6ACK}6uO}Q}WSU3LL1|i~&|aS6Zh`H`CFe{&%g2POwLe#8Jx# z|0d0HvA5b#$N7%lQoRNHF~6o`Ph#Hn+gN(nI$aK%=sWrY*|Re0$UyP_^@-LQWKZC7 zuyCN75;{VZ2)3vmX8eLxxJBIP-_a44m%QsM|D)43|FYdjz27l}+vl>rn9uf(mdhnr z4)h;pCg_<^dw|mDgA&_QzNkE~KYN=mUf#vd|yBcfz7I6x@-X0;ILYobAEwbi!)H;c^Q07c%H(?FGA&UfKx@iYH9?!%!5jP9dS?*oPPAv$zyZlHtpsb{iQJrz@1w< z3jE~%FJ>~h3B39ssTCBfO2&gJkq%Ra7s;M$P}QNJ2o68u;_R8!Bqx9;aO%}U$9)Qw7a$wZyhav6$6~d zoJajJ1TY2m^HF;4=;6uY`q})q?uzT6SWI|zktgaK6ddTPHjncWJAqS%4t)vm_XzD? zG*rLZ>|(@P&`*cmiDMGKCfulKnWZ#N3|(&ho{L}Qplf^VuGb-HqZeTI#wMrx6$I>R zUBr2h#FbzXDzb|eOCAmJ7P1==>sOS&O@KcZ zXF#yb{?@P^p_YUGLLkk=6^n2`LT}*a3&HssGTDTzsA;?_qnIZG9&73=Jesu+0Wz(b zL*l-GOM8lW`WE%()%3mGmfL2J)HSV_%PQV#!z$>Nn&u{53yE~#POy*Dpbpma!>8NE zRsGwwy8)bnIXrQjAEKOD0nk>hcgqFkxT_`pVppmeRr6o2*76Gz`aToi^RN1a*O}Uo zBJgWZfas-e|E-6psGR+&o!e2oxOo}EXIBfz^O+RZWaSwmkNt-1I zi-$Wqj(HlnQ_9O$P`DOeEbMJpDPtPs0e0PVgzou*G$`zsj^(ilxU$!p&B*p~v(?*{q^GKMl^icQJv7z8 z=|RK5b6vr}H0f|#G2F2s_7PZ>>y*u99qI1*pv2c|ksHSN`?%%(kSTH~W>44e@fO|Yl?Tp%9M*)%2ZEJENei;v*K&etb<)4C9dkblY)Y5X z%cC6cHs632dNW)3E5_+6YF9Te1Ds)wJ#3i*v)1pToBz&>nRZp`dJsaNRRZ0!FMp_X zdqlJNO;^3)TV+_}DOWZX1YTkg`yf@ck0J+K{og^O2_(eh@K;y3Okn`9EgMORM@0IX zxOep+GxGB$58($TTx+6`?Gohx#-5>yRZxHE{w;d=wO&E6Hdk3dr&93jPhzCLSq z9kn3k+F3ZO9nLZ*O-bjbDiXQsHS+mFBWX|F?KFCv=CfSc?w;I&)F`t0H$cr*oi^eL zZ4~*GD#s)5VwW1k>TRfN3&GF5nKp<+yL?6HB$iEo9NzX>xR>!U)8QgI+Vy#9GBFZI zY?Wd#WMIaBSTOX{i3aWR7I*mbO5xo~f%_0zBNaO{JD68AGo{dF$bDB5emsr7{l1c6 zNxYKcG3B*II@h=Wa#9nya8-zy8gR*506oF-kCf4gjxIm^d}y%`TZGD~NZQjpg3Gus zMJ$5E>pwLSOyT|-W6ooYuj~f zbMT16RJ7u0H1J;ANt)yj*SsTEXtoy@nnWpe!9th(JpbnBa3U$U&N@D77Ly zqG{HY2Z=4ib7#>sf_^yPX_djfziNSRolhzuP+KcE-FUQUKZbSv4*Ml#oH&tv({~r; zQq{a4&4qL{pvdbT(wVL(I4o@m&dRjM(>o!earKRcp z*;wNHGVkqYxkDk{Q}$owx_uHnPuXMK$vso;dBoar-FN$fT~4~CMM;R?`dyq*rlfwSnPi#GwlwvNcz8Yvc5*dHWYrG>QXi^0sS+H~tmC1|yIK*D&IfCk4Ga)(WE zn5bST^&vX#H{};F?mzjN-4uygw%0!U5N~)oR=8Ce`;s@M4BF~kShCBA zw}ksqMp0~0&^I2^SGXvBwCIq;gs#Qhp=S*W^H`2J?zT!yGe`EqwQxXkUk=*nk4dWW zwIS3bHQU0Nhu3CFm1rY|qOLA9vC9P22n(eg-9oTgr(=c+o`>_P^9Yc!(J}wJm~Z`m)w>1NQ4Ky4`F! zIxl;kAWH>y^>wE_c@0i6dvHEgvc*dIuk!|z4MY*O9R4&6Z4n6btKHfst>j(L#-uzK ze=53?c38m?(n8um{)N%DnIl&ptEUy+MgnDU0-9>G^W8>ss(5;%`?($vUZei~Xi0{x zzNheh#aqgECdwzzvO~1WJaCW5V|jLP|B1_RClIy4KK+qve*# zI1%7{lXMv7U~W=P8%r<}(u4z&s%?cY`{Xl!U#7S3#n$busSO6g8rxLLbn{mZ&nFP+6<>hG^)NYuZ{)6`TK`#-4@%a)s!1`W(<8@r{Zd?cnM zv|cD5^xIysK;$35eL87X4m(^oM6-rz{S+fUejPjg#r4dBfb*8x*)c5ujBtyg>A!M7 z*Yh$#w>^s`8F&XzR{J91AGv1vS_k&p*w9}3gD&@)>hSewkAYeag(gMXdkP4yUEljc z&C*3$#en-3>nOsky^ubU+<_aQo|=E8#<(0yKwW7pfO9qh4t6~$6hR_KLWlLMN5$7` zJ+)^yiV%v3Co}3BSu}yU7UD&4H$&lW$brCR@P~Hpf27nxmi25DmeJ~Hj+mmqy2h$8 z%jh4J>}?-11$Dia{C!LqfAifX`!UNhj1=riVgTi(H~G6l2^BC?_K#hKD@bK7uGwf1G@G_s?dhKgV$)n`CF2S6a0GzN6 z_`Hp&8TydK?SMFqf^!j|5Y~*j^qjNdCyKIkQN;1_#5XXGaplhMY|z?KWRRj9M$|#bf7a_zf_?n%RD+^wB4V#`z842!Q`Pr$#z{ED8cj_O8;toR@mwKuRTN&Hkd=gOnhVX6+wW*!goJ84qfW zSvco~pAq<@aNfJO{Ps(Fm|wKMvv91boShjJAfW*au>qDJiR=IlK-&j8s_iXBqCaY< zj{4HeQ@?I(8i9X5FYWCgh+OyhsA{o%F4_0ymB9I*rVJqfQ5-uzkX5ok-$B&k9@JH5 z5tGj1(JwRTiBo}IFjz<~7&)_;=9{P{9doVZ`_bww9F>l|U?)P%iy9`em^RYGUOTRV zgKw|2oPIKte4Pth$|Rfu<92P!W_e%BTGSg8Gv5DhREm|@c!ME>0&tU#R{ypu1@m(~ z`yNaiPh}{YMl+@T*~U2fm#tfHjtH?ut6X~5uils6s9sEctR^9uWNEjUl_5>+H)N5K z$=|;ZB$qlo44{8=-8fV}h%)cM%kD%f5rDGqB+(^_id0`Z@BP&760h=o_hY!;Ql$7C z$x(!}LPaCy6t~ksP=GnQF;Sl#;dsMbFd zTmOx=37X!3|63une#8D2Pa`6ctGbWrG!ghZ^@CGxanwN0EG-|lc{our=JdIPV4QsR zNUfJhG56}KEn7XuDD_`#(P7F<@%5h6J|7l#9bwm7)QIlvA9&@p|MddsXViy}^AEbp zx@AecZ(&gbG!pXfDuv%4lctvv@{T4GND~EqYYfKbAM(wO_gyjYlM0UW5K8TK6n`DQ zxq11nuHEP{*z?Dln+3k30vaFw$2{6VDvNV#2imEF*4V}*REq~!ky*^2@<_|6A_J#gfekf&B6L5ANvrCq|^%7Z!ODutkw0Hqv&cFEq~ zSezAgO})u^jdERvi9L~ujHO>%K9UB0pd%{CdoLkUDRSG6YDpMa zIJ(dD^RK*bxX_TU?fWGV%BHv&+vUZ<)T50#VEdD#!s+}kP(rMlY)=LKZ;qK`k%Ih(%sSxA{{QB!qVN{EhXLE%hDhvEg%g`cS?7MEG6At58wJ-&kH!` zkNHgAGjospntnx-BD*S|5T{+`hbzr?6MEYA4>Wt0xxNWi|AAZqop&JtFXO^F`y~7C z|Ftz&iYoPov@DoO=vZ9`%F$bFAjt!TCn6SRb({0x;$9syl_n;eE%VTPVf11e`+fg9 zew*Evd-Z^S-N9$xtx6ZcUIXQQuJ%7u(rega^vd1ZI2S)_J43R3oGcorG&YlIge3n-Yn>i8j&R7?JumZb6Xf3$S<>UP`OlS^Li3DO}Qa(}n@M z&!n@H#5-!@XsOeQXwW>9Bqz&a+;Lo|@dt8ors_sbIW9`d`g_+IGl@9iwqE$j!tWi0 zq&Kse^jrGL@J#7u`eTnXMOOi-eEfqC6Lu*n+IcCy_i3w+!E0P4n(|ah5e1?g zO~I?UOe)%NScrU9&+iH<)SN@wwcO-3S~WN12&u-God;yEM~yWA()doguhQYFeFh3 z{&h@fh4OWt0MJG)OnU7=r5T*eZcaIM>LHJx*LS|Hf(%A3CB~MFgkHX$G0!gk`su?H zOyOuU5bXEzWbyJievB?~i8UAHEKV{%eIXRc$k(2p=TjU|LAF$(|XF zJAk!GYKqCdDw0hFB?nbZ zK((+1pd!tDgWT6xPL<~=M5*s=Ug@G1Xd^3i=V5BOJuz^}Jz$iw678Cf{VOxzcJ-ux zEw0u$Sdew)S>9;~de(Uf7s^h|lyMX5bD&#YY08+%6KE+&5)%E>1pC8}&S z(f%gyEaqPRgu+6Z3uXpdnZ~3O>uzn$OUJ!2^WP*+sd&Va`hjpHgtLQm;)Vy&L{BfW zf80|EPczF+)`=Og@cNat(6!0-O<%c$hZjb|y1m3VLLvJy!GS5X@MzhRIW3;k5T4?uS9G69v5?ywXyhif@9tKQhsKM87`HH(c zQB~xs`j~WSCCaI7d6#W?xwU$&QsJ<^kk8-o()PYYqiDk6oA_4mN4DH@($6zkWIqUw%48{wuSeeWQ8K^& zReUB_mA+Qdr~42=cw*R&Cbfi&oZ-tb?tZ>qY5IvUYeK*$LT9;Z^f06G+dMK7#RzY- zCxMy-wc6%>$@&P!FG`k_8}KS2B>Q^|MMl5Re6tO{dlofi(7@FPcccHOBn#BDM7v8m~J3E}g!`PvbTJPAvopba%zXqdT-3+f!6f)kM5A3KpG6FL|R}*oLVtWky-$WruV~ z(R0b#Sd+unTchqAg4aFhU_mW?7);eW&*)q6SU|RG?K-PIr?W*Q=BM<~JeSB?Yqgd# z&H9sihMk2FXXXN7$W$Rg;PH@X369Rsr}$`v$omBK#OUtOlAC*{6Ob7QBeP=TJzebMnMfkW~v0%X3D)_%nOW`O{CUx zxV#GbFV~?!06XeElU<<`<^%UH8(bG6O~Qp4k;pL{`6tM1Ye)7VKWybsN*%qm&ygwg zsh9?Xgw`@!XxtI{)jpLZ@i5_aqW6QTEl|rIl|BN>Z5?$?Dp_Ct{Yf0)$7Qh2zOb~D zm+h~gZ=QSi#2teNy*7|IMudPL3rMMCNkWomox3~X9ey4uiAkUh3DZ#KXBnJJ=S-zu zifel6heh;heb3_G-g*mD{AGqa9gt^4|GkPFt1r=ytVAXioYd}Gw%8r|UVwHeM2me> zkXBo|7r&zeLi@DS$4p+#a;S1-nKQp2bh>VDIS0>fiQRyB` zq#3u_9#*axT8*=^LISCUt>O5y`Rj^qe@XK=?^EiwJ|hvYyb(0@--y0;J~O`Iqg!7v z9ne`mRa~x|YL`rH+}l*6Trh>GX~#00pH(U43+6hzj+m$WFtq^_o6$TZ*hN5JK7&J_fd=9tXDR(cCe77K2X=TC#gHrW$m z&5Wt7l%8PTLFjNS#V;AR{+Rpq(sof)m|z8G3AjNf_^%n6zL<0R&LivF2%j9Ux)TY2 zc}^7VnnS7B47NjrMmwFl&JqOsG96S}Mn?Wkx@Aw{?12uciRfqH5KN5>N0;KNz!>k1 zXum#^vt1{wHdX3G_hq0KG@knW+%)R!)u2sFE9&ICs$a7;Q$w{aqpVHvCLAh}ZVb_B zTol8iYPMW2bh{ud`Qc3v!GS8~-xf9bMTI)7jZ&zE<3&ORA0{E)&Q zzh2At!B!eS2o9DU89qqlJonGe#Nb~{BRv6~((#y5gsPY@V>G$J1?PxwCGe*3Xm#}X zsZ5M|FWe!N<{k36qy@5EidK|C%C>eHtHqALe#Boz&QT`2N)*VSt27b7b`GLQ)otQm zaUX3el8h{*GKGVv-~-BXu)eE@3!befQ-dU`0pDAJ(ZEp6TE3+ih9D*J>2#t!dn5e7m`@sq^a+bjaCu z++v%KWlRF-7Ew=%My`I=+tK-w!)ThXo5r-V_B9fIXGb(+Q#vB@uJ~QXb2@iiT=RpW z&Jak_#qo%=F|$_NJZHY(ksg?30(7 zrtTRJYW1Lhn?h6BD|EhG4bSaQc^_eic`JcXxq9Z9Vuv$O8La7&R+&Fg&3i7O@2MmO z67(X;g^!1ugp-2|ev-U6duxTlBlzWQtyT_tHeOb=c!Tj*CpH)1bG;O&*nM_Tl*k5y8Qs1{j z*Lx?r|4xt`H>j#q3#O4MQ}r!)+$)G=LlPR3XT`oeJ#*Gynk6ivuf&EGI9U_X-hf$; z9mRuueaf@(9-16C75Ki)8`$y~izO>{&hsfW++B-*p@fW7of@~>b$1QpXtD;0_-IQ} zFh*92hX_{Bme!8lhpH)s;Vd?PWhdt7Jq#C)@kM$UPqQ|MBfWHZz-h3zJRGm~W7?_d z3_Yr>lIP+1rZD?)mN8zUoj97?FCx~D`DAFOc6YuJl6B-v%DQ@_n868kO!x=g z4~02cf`I485%OM?eiSH8yF$BY_K44VjhR4=1b~R)B`vcSeFL)v|M$17qYy}(RmR!t z!taC@Jjl9JA&q_Zr%~8b?m|{_@~q#()y>Y*_v%giMu?u(oz25z+w|eY%v+69uRuYe z3rTN}ZlJEl(BRKH0!y^|5)|~MkpcYWVOjFp;J7tQ&TPgi%*weNJ>ZR%#PfLhQ~?qB=>Kt*L_VqmfaNU&LC!k z<`v278NK!)aflzI)VDG1v$`hL-38}a+pe#*M5Xgk=5}Tlokx1j58FcgTFNE!4C;f! z+cV^4GoE&BZQg3j$-0Nj;wM#2ywgXF$#d{8{hOsYtI|43*6%-dsUV?fmOl3(I zK`icl)fqyj%-%N8BSbf}TpV{jV?PtD4Zr0CX#Z-0;(3;!=Ihku>z3LIJ(@zauVXhL zytoXMakS6Vujln`lpi~XnRPAM2Nz!1^^!|uMzdCwrUtPB^W(5%pT&Nf2~Y!}i1s6= zGLnn9dZR4!_`Xghna`Fa@#w;m!tO^lZsUR$ih_lfj!Vr%l1q56D#HN(flK6J-J^K) zy*%OUcY=+8|H6cGhA)ve^oq0$MK(SWwr5PSYP*z z@5uCMou?}d6Ws>Miz{c;YDM+$mwyL7m75m1eaGz|EzT0$RybHMY>6Gp zu^$(Nbb2{)lp6CQr}#ylWw{rL&!xH>ERVql^3IrwM{0e=aVTYzpI{10ztl*ra;?7Q%*|I}k1D_}+h zcUmG~DK%O9`tdG>C1^Mr`;|150ufW9DA!G{R%z<d=NQ*YWHE{hO zeiH0yI%=0lr?FlhPBscZ%y!T#FRy{cFLF99XXPe2kCkktqufVA zDWZD`N0is~1=%`s>Kymv3URTf7b)Wr3JO-ok|EiR^r2zDCtEa?Sd~cGwI7Nl*Y47T z!zYyv(z?@Ih%}fkL)(Ic6Ucf~;bjO;on0s}7(YffmLw4eCkY&CXh3!Qi_?dnI@oWr z)4ldFff=uz^Kl}3na;{xaAqu7y=3_`bV8kfa`O?m#~JVFc1h1IV!KAbBZmLD1THFv}9 z!*NwCh-s4+?umHn)?-RTXeDDD z4(#}>nweitytz3QlP%n2HCkv+s3Sk;IMybCexR|s@3yLnwm+7YrV6`(1-m|r{nh{e z{ti~}5itod>4gdSZnG{n6 z66sLjoTdiV-s`lP>J7PyHw|;|$ImJd(P}I_is`IvJ(Y{_y`Hs+`=|4rn$M-1O6KpB z>uoEXde0XPpN8Jq;uupOH6M(4U9zcaeY)z)!Rz3eItax~O`TG)9NDZGw*SQ9lR+pR zLOShDtz&x)?0@Abg}|e=!}jdDEDoUJ^d_Od&g8{V%uv$Zp&%0oXKR*m+nRXpQRTG$ zK$+hvu#LInNyJdlP8$7*J;--pKrva$IRpj#pMc>y=PNg`FIVrtFJ&5#`{Zfg z|DaPbqtKg$@3$lERLv7&fNY8^`lD@1r9lmfQ(g_xG~Z@)GSO~-Ilvb6$!s1fdhy8# zUKZkA2u3pnRXeMtJv(hmwtU@@qX)6kMQ)zLa*{bfl|_sPJU@sVM<{&8&hoO(@cSyM zcPbBKnnUxERSq7sN0Pv4mnlDS7$tQD*gJk}F-@?Z=Ttw6L|)fiXVl&sujk!rR37`M zB3~qKWkv80h>#+^$t`^j`IB`ox`a%!I$0%qFb$;Vg(}@_erV98EV$ILDroRN#GSmZ&6|CE-;vFe^g;Oaq1H#e*Dx+z zaA_pOzVdvPalOLl#$nlFAcZ+v5Sq_McCl!vVlt5JzlJVLa^`+eU$&1$GH1&PbV#~A zX8^hPat?)U@o7FkxK4IR`5G2|ji8FaNJ3&%sDnd}*xA0I9B=zpcvb;VkaEJvdVb~^ zZ|Fh@8(B&1x=6kLq4hEdl3c#f&LF%|ywYohG;-SvPHdB3NW8nabE6%*J1y(8GaqyF?y*lq zuf|O_q-DF7HlhFz+pM1uS!vPSx~MvT{Q0uE8`EHEF%?~yS%7SB^(f_aT1@$Q)Qk53nMto{feyWCJ_~~|xSlv)6L!Bd-V0$!?cuq$ ztXyt)FweZ!zLNq8_c^pg;@eeB`HD)Z`?o5mp=Nz{N$cXpn9ocrclD=>4$G&L`S!mc zT5H87MeQlmE@@bgQkxgfd7T z-fP7UQvQYe{b=66`ToClz#ABg_c2O>tFo9)D8sVa{+HCXEyq(R^faM=uuxGsI3$D& z+dpTQirO{cXonQ`q%fzHr`lOqktPI-bhnk8-3;RTNXFiLt;>IEbqOtmSbGxBUg4Gd zOC03oR{NIgW?b!2?|j@JAr-z66FO3DT{@N%hkx3H2mAGXEs(FPovbBKs?%VaBnx3C zL)dGyO_iTJr{g6!W|504tD9`r*}sRW5e6QQ&d)nM6w=rEWzYt}7NoTP(dsrkFIwW&fDH(6?bIagpWim-uOdq>FZm9Ei(~md0b_0xikA0rtt` z55$$HakePNq0Y^~DyuW6(9?zZkx@ID1dy*!!Yv0gCl;S$dtUECIqfr7A9>Mj677&x zmWRYa81W3&eq<2rCT)v=n0gK+9~Hxt;blp!&Xg02(IZ7oU@f_n@HF2p8AuAs_O4M% zA=}#fT1$3`igN7v`DFC@Xr0Rl)Yxt!H^CYsST#0#wj}1-Ae}hEg;Q9usXiI3--*aZ z_E^2@KjT4c8~t-xvtOHFe&_O*A2?M$EPu!2^62a3x$oFuc^PuXr&!S-*DD>{txJ9z zD>&(SlMjdP7rX*`3os@Lh67w`8n>=jU zyr2NsA<$1K$Nu28zu@@p1sN;3P|hO4JHW|6>+YKOv9{r^@9}Q?+Rcg!t752rLEY}g z??q7tm+;QgfKt8`^eSSq45L(3B75q8r{qhHsLV{?MI^Hf%ffB0GAv#&9OTn-Ivwts;%mi z+U>QU!_BS-$1^;|t%bx{uwN?jCE%~w;30pk^>}UZxkTRc2{m8%`6o$!{(VBl)|PBa zV9l@Jg6wrYqyLKO7Tr8u82D62iHL4dkgx(-6BWiqoxj@f-}w){h=fkKtmKOxQZyod z`T-`(#*h1H?iZ!QWNa)|(aWzFTbslw?}VYU0zudlRy=<>C#W{Cau{k7fBNB{4o!CU zwZtFU6)N`Dj}1TZ(~L1l63SvNs9=yKLPk%xn+_P!!M1rnf)NR=e*b8GLyllsW~9ZSLyjSm*m`@zAs(E(9#7gQs(4kq&O~JIll{P z*u%@rug7qrWIe3TpSj4ZVA!oD-l5`mV|?18M&ym(<&}X*xd>Sw^k< zg@Xr3KBS!5)gA4(U?}qvK;$9%=!E(+!H+|B$t6i4g<#H#lGLn1t+s8*z;BVK&=S^l zI02+hPp+ajw4(WN=Ys}}=05jQ*BYjk{f2^v5su7Lmy=W@gDx;JRG%_ZG;fIUl-lGM zlc)B}KdHSK^hf-V0zkdM;m0*hXC>M6JCYNQl__3XC3s`F<<-5m%FLYm-x-vhDXQc+C-<2~H=c9bUFlaX zm@(TvchL3q>3Qn$*fN9p5AX6e?PnODR00ojAY|V@2Z?WX!^G_CAXZjeMFDdS$`@H4 zbZGkebd;5~$LpF1(E@b$Ztea9%5coVks0t zVBjlS>C&AlBPByDu60sS%+Z}s3QPy};JDD6lTcfma7hl3&u-WRNpMAPT{7Tn7iZ0! zD3|;&bKE)&$#LaE){N}7DUUogM{BPL45nc=f~a|34~n)Xz%Ng8^||@-sSZNM?ElhgYRtz^pZ?i0PLp26)#9=c9fv zZC&KJ8^IY?Jw&>dK{B3>)1Tzla~SpIkY>wnR`D3@I3MYP)WS+Ixn1JcZlDfp+HY25 z^y!j(6Zhe}@Upc}KxO!b;~<^CN_v|stgb04`47+D z0WeQvTHlzDSl;UHV?aV$&^ERh@X~FYUV){9`|X1%uwN4{rQ&HG+V=ahIv6R`jdTx2 z1{nz>1bF0HzBkC*xcU~Uabz~BIowPAb?e`WXl}yaDv$4L%I+f4ZbX3R6p`znc{D@% zlTAhm%hY4lPQLjt#Ol_j=}H*gNPIt&+B=RE|LH10L4}EBb&V*J{jMYhfI~qGj+jCt zhGcXr0L5ig8KGn9mHy{R%MzDaT?uz5a(`Z zBV@0toK}Uc^Vta$fYZ2=mCp)j03!PV3amIyqv}?CHn#XBzu`hZCejUfc>BKnA%_h5 zJ!;t^oXvpK(q&w$C8G^6VZay)cL}U<9qB zIt{ll?f+piJTj1*r-lSDp`Rhm=&Hcnk5;nW@4G@Kku7At`bK<Cdj+p43#xiek}=3pJq+PN$o=%DX^(x7Ts$s=n_OcP+}NU z-MjZ@(N*s^F$?C1DE%nu;%=^x})j=j0ne62I8((QczvzvV|{ z7Zd8eYW*R+_ba;bumwz@P%$oDEE|`2Y*$jQ+Iz6=5r{Pe$Zz}OUwauIR2Bj;aWbk^ zLB@h}=>PM6PqR?EE52GrX6=wOEd4G}-gI~5lrTk^?uuXXDNZ%e&v=DH!SUxL0wOxN zwtEfXCG5j!xGRvips;eqI9H!Zw`uB}%tvXuhHRS+cwRK=v;l7~QT>+WV^V{djQ_O8 zzC5A%Mnun^sP|wTS4c31CmW=zEGx+kC)F!{z{ol&LgWdHp{@e%-QwaD!{1(%f&li{ zdb6IBiO1hh7JEvHDtquj!H0r|1(RnGrTZ=n z`QYQFIvpnGJ_x@Ozuf!rY~~wPJGitPOQx3yRyw?Z!!!^g3ZPUn5;FjcgGwrKIDsaS z76~G6vR1@~9tHL&ocYDGHCluVf@HM#!zwYXEl>`MtKOkRZx|H0AeTFz;?^`$)Y{(G zeT*InLP5vtlk)p0s6AAM!i+A!mb}{=sqx*z2d1!@Td0+QvKUjTs;dIgy%?dfNQQ$r z_eopDk;W%|#y*sbVJn3=dZZQb&h$J;M3}Y^gEi$C9eVW23mH7ag)V@mfX>#>)Af%2 zoyYFCx9}_rfIY{&x>TrIS8l*4dZI7h@ztgmkFACp0o2w30$_nD}wGAIIq z-%P=H1_49?6nvN@KsXvWY`95UbQ*{dbZdOxEr7&R%lCX(4vrGa$nF|WQ>_7H@(nBw zZP!tzGJz0D1pwb41y*@_x0gKS$WrQKN>AY+P>#uzY`*ywQXo3$NEL`B?4E5Ib_u;MZA?z-ULY>^1Goqzk zuJlT6a`R%nyi+1MC=Mh zfab46cA4z0t}Da`mPC#()o{?)3#;?MXqWJ686O8YH$Mn2Nu*(a%m*Rkm6u(oZf`yj0%)ngIfokR8glvz3z%VWibP%3?#~D=Rh67 zdym$$cj+LJM_&~kI}3q4G$hoO5@al&Vm%Fe2mfj4fNu1aS^5}$I41S0p^+_Ef2iR3 zGQD{Ii+WB~4&zqh2+F`O&X#l+np$~RUInO{Dqn*=)EEcx8fnMMwepf?`h!iUk0dvM zQ|OQ4J)U>2qVI~M@0l&i7-~P7@1SReun!Nw&~SXH!=I^?tjf6e80`1 zE7L|%*eWKHg=r8TLh)OG zlelKEmWSS&^T`NgUS_&TNmW!*c|Pu+mz1!KZa-4hH{^flv9#_P3CS`dU%R#g>~yb8 z-_A|nJGttTdjmQMgY{SmEdf$hq9jBBu9bAr7gGlW8O?pyMvaaK{WO?*m4V)2H*x9r z=T`?wai&9(3nn)PCw7pFw^uOeg#DJr!J->9Py_qid`_R3@ck1_|lYbVW7ZwH8KZsdGvB8d(>cboskk$1A=L zk`QUmq3^nzaJEn>yE0NI@B3JBh|WQtNydxp4RiucH2o$qPJzv<+Mg<*;y!-K3Z!-m zdNN8ye2Dqn)>_lk*p(jG#vVqfS#F+cIEhc(&nR^Z+|!@3gYpb}NIHHs8*}_+cQM)B z77i^>FquDgG(K!EcU2zZb_rPoJ{+X^?CFwx*T`dvG+187dy+g;{#RZ`H=il^fNtyU z(cE#b+IVdOp9wS*a&iSewvvBpU2j)h8yKV}3XKTg+*G%A6>I4V z5pWU^`SZBPy*Egl@VPzHGN+MWy!8t}%EJa@BcE(0&`Vh{f?jweL|Hh(C^W(#at@DD zXbVG+qAc@<{yCf8x-0q!2cVh<5C5Fu=2gdl8Ed(*oKnLj^pF`i*?{ZtU4<<_TvKkS z*}dU0QGui7ZfE8j8_}8gPRpGziIWyGPb6n`>Cw`FaU?ZP*N%p4Rn==hNr!P5ffcT~VgLxf#t6@_Jmn2Ggx<9pM3#K}lE$QV8e?cvDNr=gToo4Cza~mh~&Kkqf_l2%^WM(<7{(V zHYtbP0o5^~>m}uSP6K4NMSTHIV6}ac9Dg_M{H#8eOyvyRHS23T+d^$*PaQ78)|>ca zMkoa6y^`%HGU3)wtRUBqsDL2MdT9r$%fdzYHBg8l>!fAmAJarORXC*=loF^2G5A-QmO!uDGV`JmH?a)Jz`Z`>A2?) z0m#K;GjtthWUD%Nn7Y$7UMq2%@s2xhq0Ei&Jj72ir>!2-aY zh*HxU<-1cVOFEp+E4=fcH(1K*FQRZ;F4D2ew@F~!q3d~m%_bOhi$ZHNGZW7R;!b>q z(UW#XaeqiSKSyM^@msNO&-Cm?W>Yqc>QqF!hWE)2O{J+j+ruNQZ5k4nCEy{_=ti%q_BvFHAzVB3&MJOW z$es#K)&%E<8g}$;Ab=x7RR$b#5c3WH1+=YDpD;AQ}f2cK`| zASNe!%`ZRXM{iE5<~j_q$m!r~C}uY=Y*&vcbd1`+FU(Dp#Iw{ORhv7iUGrCDP2idh zJ0OVNqkcNo&!Y{F7;dv57@q362Gq#<;nMn! zeD+{yfr%R|2oGw)S@2X^*EAGuLk|+(*Xz__(&?>()YAI++-ViWrpo*UsjcIInCr=+ z(TFYFHe-2k5Tv`i{_Np#17s5hLbxRcnY3Bmer;?M#}FPqXhCfwce!u#f$?C}jD<3CPCGr236^?BiR~ zG(;|On=TkA{yl)T@#|!38gdi1Bl=A4nh?*JX7l#Yu%+dx_Ug4xTp`dC0(OB9hbOea z8K++6?M`7lfh=+0!0QFiC`p|V#2xG2gN1ac1=XWmBG@GWAY9PJ&AOrD1;T#F*ov=v zXRuRf{>NAQ?A)if`?H;Bcc`EEb68OPXa^qGp}g|3xs^}E$Ldi9To>uLM z5(v^4M;ThR|Hh96G)yfP?73LQ0k^rWXZO#2pX{pc6*d(4q^3>a6aHrLN`Lk&R29lk6{ReU1Y1xi{89RfiWwtc%m1o^MxK2IZ5G(5gWKbmscwm{?NVWdncxTz)7P>}E&XyTDn+m!W>SeFygufbO*(mYs7; ze`;OB^Esb^%QRue*Tftm`_*Nr$tV?G?cvZQj$M*P1PS#C^zo+5DNtf3`E4g5E|!%6 zqT1*eJA>J%`oCHh|AgBMsoyME!iayobxw?jDZ>jgX{a&-MfUZ0Hl}NIwQ*pAwA9R& zIiRy)Y2#}5>1GvmrUhV$AL|+?P_9KHCG_kbQ$u}88c3GFMSmW-)T>hdc z9vlZ^$LSWdM&C+COM}pUpjM`SOkqi20UmU_uT_6`M*Y1dlIUD}j|K|EHzqH?qC!Sz z$@IZ?>|Q+mmQ=?oyDPH`Gz7OZ_$u6^^_9hDmUDQp!wf~lau}qMUI{4(7{Hl)eEcJI zejKT-lEW7fhj+eJ7%{7|KZ=^BphCh2kP8}gN-bt3REDjU%R4MYw0bwdP3=$#Q8gS*@+RkH09Y{i*$|tTfArzM#+c+ z?e#PqXdi7V<=XYicNl%N@LEWl8PO;5mtrGD@Fs!BB#mqYNE3=X0}R?+1Ht z%?)OpC-^gdMPoxXJpkW1teG8-NG2($5Q9UtR1!VQ}iN#oYZvD#6YLJO+jzpUV!5!@V=U4Mr`XD5yZ8><4WbwFURle_34HDrAnaOHfR;IUDWkZ zNlMR}+8QItEjfXp@i!p%F$hFDdc7_TppoCKBR+_iSY*Qb;o;hhZH2Amroq>h1V8E5ROXzDC$eQ&7^Cf_E zaO>wKjE#Sd+1OL)Mr!!WJ^-l5z>xWm$a4WA9``z-z96?>0Z ztH&@WwS?O}5}#U-q}av>q@0wK-)<}!QlH~juTbj9`ib3DW6PxM69KW%+mcUL*}W3{ zRtg0mdRWDZ8x`Ufla3+U8I@lStAw;e1)h4?ILy8k zyF$mD>P3#Dkx0UP*!%$-gl~tv+{rDQQ^W|K ze}78)_5NdFtIqW6^{}h?j4bajTHzAKd558hN$7;;wU+*+rQ4yQ4$I`iyc5UdZsDsg z8%SNxE#wY74lCpKPA8{w-3iv7jb)b z`N!$@*`~QM$4$CI_SE#*=Bm%vpAUut{sy!UH4q(N@cyflzA?g9{@H17+1E(Y?jRWh zHAVSX%`7#{+eAEsXp*IwcQO&2FlD-*=g*)8riSW%qO}&~sQTpuCQ)bS_LHYg<+LbslmfiUZRbMqsyc}{R%19#g_BQ=%Rnp_S=91gZifLgf zN(eUW1LYp>D=;xw%?}*h^_UQ zgz$x#Yq_}4f^yO$EDC`F~zkV904^vw3_k*|dOaju0Mg0ac>! z$Aa`6COs9_<5kk%C9>`j(UYhihX!<6CY}l5V-WZq#cv zV!c{y2FkiQD4uXW&}x1v_7mT7?7xBX{1t>jh^NHLiDuD>L^}hEkPzCQr-g<`KZ|3W zogvKxPIC&N_NgSpibdj-#f@`i5JxlAl*WJKqes7`#WhI8jH!UwEqq~xnD z2Nl#ZZJ1ic8SZ*SS-|qA(?Wy@poxt~8Z(&Um0-0M2d^yyvi)?gy;giFckphKcoeYk z!8>52JmFfpVA43r2Gc`F>w4l2GUa>^lOgo`jVIMs)I=E!UH2ipQ#8~^VJHsYw{T$n15`)Y{aSsnRR2XzB%c zx3MWn3M=RDa*VXyLa~b8U1C^O5_8^4npshP`w?zGXbK+}0jbwj5z|1HR}F2Cwl8v4 zIjS~<7#ry4LZrAxP^yw_b`9gi_vhn$@|bm@;G>ENnp1yP;&FomBg-YGcOSa0Y-H-X zm`1Oyfsca6Dxas0qbIQD^3!%a>t2;?>^CLIN<#^IA@dmOnA2uhUn?DH=tZcleu}`l zM)tz{+Xv5~T+-K*OftN6acun+aqHOSld3<`IhK=H?d=n3{okHo)z~f8cs1nnt_aVx zoX4hB)j-j_6%P{Z<|0n2vQ!JPP$IQI!+#@!ttWbUrDG>4v~g+L(Fk59*RLvrq(3Zz znpSX*_Xq4aZv>(>JD|s$#;@`a%38RQjej zh1kcoOxGJ3y_ESeSerq@7E@DCQ1#zLW zO?YSdesnNivZ1nHS63CL*zD_?b^ZLeGl_5G;WhXXAs(NAimBMbiJ7m2*g{4v5;89v zRX>s{k_~9&hftH>o^2in({H*IEWGta?Fyk$LH9IB2Mya{!_y;P<)U*YBlKoBs*hnE zBJZL@;Wf`P9g7rZ9&;W`s6ntZ+rozhmV`=ST`dp)GoaSq3Ug!51_DrMl1ADJhIODa~Xm_`3|zJg;LXTVmfEzdoc>HbMJN zU(;cuaWRn&=l^h}@4OUj+MgbzN~msR;*#FUAVmtkqEVGTw4ZzL^a_QjqaCw};4m0h z_nPkpk~<`jvHZjp+hpb|(98ln1U5s{e#SqGoOKw&EvnSD8Qcbjkcgd9sxyb^24<)2 zj%M4xR;DJ=uPb+v)XbP7P<`enEqtHV^iCK3`@l!atOD8gcey%aaEydOJ8VT2mS9(mpC={ATuz|Eu3SW5w>8>iTM;OL{`NbP(R z`$g0HMFK5AxHU$O_tRs)d%2lX!Sq4CV0v_6y98UJc>z01>;t;9zVy3`?JQ6FOv}vQ zKe|9oMWLU6%svaWZ(S~qmvYV|~p@Hf8hRd-Pc;z`qiSPG{n39?*x=c1;`mS-^l^;7))Y64m$f* z5S}f5!352h7xgn=?$6YQy{okaAof53L{iAXFw1M~W>TXIO{<-ojUxx-(BH z3>slSl0OhBWUCs7s{tCenL}y}EjyCZ0f5iM1&_J05}@7%3@Vmg<%PJ~xawRg{?B1U z0d$WDEy%ssNq#?*nUGsHEP2N0?~p?5<3ru2r4z!{-^4jtt4b;l0JjWM>!-*D(f2KI z8%3h9Ocigrmp@^dWrkbmdlJ89_^rTp5|2udU8=62+)6-*3~ra+zfR}jxWKvr`?{AJ z*y8*;hw>5bX%HI4O~F{fAgkw93g>9cESy_Mb|R}8MOi)EVq|N=&s*oq)6>}v-+0Sj z+vL_he!*Kbw0SA95ajY?Gmo{s?|wXC6?j4_vFcsX(ZX&xj@Z5LmCw-YVtpSr*QU5P zVW~Y#c55+@_RLr=${wht#y>R-KL2?3ty58)&KJB7VHLYn&+3P>O-f*m6SK_VadgD; z49FSy+~tqOB!XwG;jGdxa=3qC;0XWc6T03F-+xIfe57+18eC~sIA{5Am+Ea_1}?zb zZini1ez|Lz^LIit|HKn^Jnbx?ZZ%bV@Qd%iBlsMeib_<(NNGj_82BZmGAxaJ3uG}B zUUSn}#}asi-j)X_eXt7cl^O)JIOg!DMg&IP)SZkFhFpWWZJVeCILwr#ecsNBf3h9M z|0qzbFH_t8)}I5zu@oHW&vhe$po3}NvyVki3t`SuU!gpy1}g=b)GSnYe&Sa){}PIB z;LcuoW=#W;u?gZ;Q4D7FY-3%DtQYnulcdD1k_CjyPrQ<1fi?(=YOzX}P?&BGF{-Rw zAf{a;oK%9d#qtI?C&C(zIL56@To+{a`Hsp&_ZOeftuT3NtG>t;eD|94g z(C3p7t62qV9So$2HovS<2sLo3#x*mc8$@*Jd!lE0K4(AcZTup$|7;CS4{U#sSkP~k zSBPt~uEZEKY$78c5L~Gz``d*$tG(H#G&X`?(O^PE)E!DXeF#mu?Z`@pWiYEbPs*!* zpJ&+80A**c2&O5&py~fFgfK!%>F{4-9WP)&a!n*YL}Y{$@V6JYsVT>2M&=S_ZkUly zlwUJ#8e>9+f;GjF16M1g_J7+tK^0icn#D{8D2B?#S^%2Sn%m+yR!DTBH+GEW^`3c2N z#wZ=H8431G+WQ<3sCHo5K2rTzdGKI_B>zHyDBw=Xz^04By1pQpIK?#62DwqngPZGs zW{$W~lBY`gMe>5>osMcB>Rc3cpprQGz2@+fyy=xn;YnH#&Uvw(j$hVI6BU+q4Kv&l>qKJ&S_aLCE_J6=I)I zW{V`%d2C~UwmWuisd`iL8<$Y0^s#t?WUg4;BmbID>YjD=LG?{ZoG$U~GbBRae(o!C z8i!&}yWpcuXqOn=*OMJ=7#~xR1K+;M8XT5uAAb26H7esw-)=HHWLOz6tBSKmtllb?5-wPvv*Pxz>Sv1>8h@=7J4nZvVUB4bh;EK}pGI1##)GmQY z()M7SZebu21O*)-7D8k>{az}e*mJIaISU|+uOY3K2#YCPNyQwmpjLr+4sFR*{Q4Wu z17AnXG4BSZ7bN36%AT z+b`HEc{6}JOEO1IOQ3;nC2?WAAhvbJM|N-y=<;1JnhNFq@2Sk&tf47#Ns3d3DC3c0 z$5@NpL(pcXCrVaBzpq21{W46jKKVi#ZFrmaKj8d-OQi0&bd8MN!1fdk8e8QVEDRL^;3T zrAJAeRB}j6C6(8z<{d);4LBK(2#8^XEkP(BcA{vXL>H;R==jhq$`)Hp)=8w;+o(4> z>o=#3@``ik7bBQkQ5O)FjdA>RK9D@4M~`=OY&UU&lswEPM&8*@fM;C$`XQUqy(K z%}5^}k~=uc^A!Ias~_|VSw|ph!&N{g-tVI-yrfT1K&a9%w)>{m;**@WNas$>RuD8V zn;}9>{@L%*+G=UDd{RR*d^2|3M2~zh4g_#y)sWhgCC6AFh~c+TM`z7)s zmj9y9pj3ZQl%h(Q173#l^CE_Pifn!Lx;whjNTpAU**5%BAL&_}{a!`S&-(rvlD?*f zV#3W6hWXbYTtPh}cSVTinjl@n6?LsWmeN6YDQIz#`o zoHQz`RDl~*4I=IrV3#Gso#g4G(3zvSdg|Dy8&gOValGBm&~9LC0F-3;>)3U+kEGBi zRBhx^!IuA725OjxIdtx`_lxCraxj* zyxjUsVq+hFp#cv7FLb**6rph|30_I_px@%hoiV)mD*I#$tq*Iq8$9XLDrGyn;+{(O zWZw~>JpTWbS@jnkXZXK5&Y0*f_HFvNgfm~)%(6AaG#S|ZWDw^~pi~YYu4;uMa!_ff6sZhu@ z4%`vM?Z4~^>f4nDX*#@i2n6tSWU+Qj=QC?M;uImEyk6R;fxqw1-4MHDKtm&P7z*kD zQU>$4vF23Lzpsy@KY(<^-W_}?^EmHe5`V!Y6Jb;7p56x9+0`?Bd6B}|#hY(I$K$jy z^Im+#60yMb|v?I~rc+fyUndeGL^_WZi9# z3w=htj^V)#&RYng_Tp_HT*63<1Ne(4jX<0t`g1xupv}I+35|OeyL;bJ;$2cv@3X&$ zcrHc(d&&nw1N4ux5|L}rHGW6`F?s_hYJuD47~>*tDSHcYDj)TcOYB7`wl(ZU8cx8< z!-pa_WL}!YX$u+g6eTA&ol5s6mhJ?_{Ci+{0lNQ?Q7k6^C-JmEKpLgyRtf$dcjo`e zzTi1WN^YO2Dp>LN3-B9MEzA!rT$-Yh4hv)T+&2k6AAU5^9s68ZuKIXQBNmR`qm9Ik z;Qlt2A&ZoS;&7i3-DB!3mw*$UP8?Gd#q~w^Zpk(JR)777qC5mlA=|>rs|q50Q<;r z5%|Id*YO`(2@4u1d@&+hM3^exuv;F1dqU72DNLF#Pe^SP2dNwOFkM@Qb9bgR5ssJQ zw(NpPP+c7Jd+Zi`X2dTtMKuB)bj3;LZ2ar7nKP2q8pPbF@wp?!^u`Ke7MJ|6ub5Kh zyPeE>m(Gj-=VxS{xW`(x1&u^(>Qy5A)tyxszY8;HzPelcg?CNMtCi>YJd}7fnOg^& z<8Xae+1CX5D3WKr*G*g!$zL{{%rz+@4wR>>64`X&SGq*orGZkw>Z4lO8nw?dunp3T zX0pg7I6}IWG2N(eWGL4kq;@KL4KwHHT}Mg!?Dl0}M%%&qbcYCR6&Ck(@2^oxlw(2- zQ8t;p;+EV<$z{89y^58!1>@ZPtsAJeG9_8xQZFd12IVr$3+_H9zoBCz5G`x@;qTUlbp3G#g3~qw5p%p8svNX#{jg|;20`c_ z0|+?I35F)+u<;#T*YG{xoXBTQ%Bu6{B8&PZJnCoSH zVP$Ksa9gX@#XE27!`!D&7evPE64{j6@;}}W2qIlfja-X%3wCi^Nc%psX^voj2u zGbwfOiL9u#-&z5Dh8q0i<$UZh4Kw4)Y`N`58nCgrt(CO|d!uO}pDthqtWuI5P}6n& zG2`*Mh+S#Y=LGiNKqpTtQs~>?(YO6M+^KU? zD*h0Rd2D=kj!w`>(u?XEU5%@W`u1{;eDV!UXl}L}BQ`j*5Sb3n>1deIQ}&GCo^xjX z+N;As|Nq?TPb7%GlK-1P34mRx#$$N<0iT3}fdB~h$yY(@%cA~;1_N0Q8FMFK03qG* z-?6q9^LSZw9iZL<>(>6Cc*zW(%d(R3tus`T3OE1XjV64eh6GP#IA}s{R2$ zWNTLL9B-tt1pO_fC>thY&BUFdltulU?5yI?p`wg-g`xQrL0b*e5VvWdgT0AG)bTn$ zRnFqO*jyLzhKhz+Wc}75r*=@`#*B_jQZ2^8i3hwBicGMPXbu@>@~pw>mSy(icWfj0sMf`ka(565yf7Hpu{xP@X)re381qTD zvtI8#>sP_-n6OatzO;CpV|&8;&5~L(Yj=g~i1Iv7>T4Q<$~FKN92b4uCZ` z(7%tSPk2bONvwU}d_BEt8_lJt@B%Ihhbwh)uf#yKOb{bmVBP50+&t2HphaFL$iSK* zIGu)TB`t%|0I@I)Q0&H#6@{HkRA_dcqvOu?RF2YEsq&`IdC{Gqe0AN0I| z=u8w3o!@}Aw8CkN^XpxxGY1aHOs=Lvgdw7)#|EthM~rVSzYMOk`cm8GjB;gRKVeL2 zkermk3jI*+uK($QZ%N9iP7CqZR zs9!WDWZP{1`4xjE z7VdAwl$!tw)<@We+izm8zMAwR<4L*7^vAn-xyydJ5V~z7ifB0$_fB&=0_BYpyXdaF z^thp6x0Ge}uURWEZJtBjZw-I0%{OJ)UIe$jKN&7-mzI|1a}g^4vW=wFsYw4XL1qUM zlj3k>(Vu!J_`c^wbKm>1@vNq#$R>}=5BJjf(Pbyu$*wZ03w>o{HL`Zi{VYPsXNnD4 zcM+q}e#6*_z1DVH>K~u=`E~=zj>gDXq-GD1yo}Z{GrfCx)Gpgh*$cSn(mg!pN8j!9 zZ8=J0SoPjrRm+}a5#Vn{#w~K{=uP(b$-lG$$QR%Z1v+NH>+KE%E+x1O@x2i>;CIWkGGjiq-iO+HwxN-8$c`<>c*{VK410j3Yq zX;`$_1)iH=G?t{x{qAuEi(1ISp!K(*)OsPXj!ho+7^1x-q5iV9ym)uYceOdJK#DxW zsL3dYarceFC|@eU_M6hFZ++Y+z#?61o;|?E+LqIge$F9+A7-y4nLr+nE9YAeTvIvU zEM$d(K(X{TsC;IljS#`aiE+%@DuySKh06E@w|L?}AMIRPO6WKmO;Q|Oh{fD`_bV(h zS-m0R>eZ7T}bj8ux6Y>A#)wc<6Ib+&wZz75hQt;xXxTdNg=rO{({oh zO~5t4MgK7vo75w(U0rbEM9|M)zH@z&Q(JmaKFy-&UGwnM#r8UVO1->ImdgmG*zuOi)?hE@&woM{Fi5(rfB!~JDZtL=8uKfb_`XgmBLC>f|Ql15zdG2ogmNP=r`wsbR zsLW;i#CrkPc!ATO>#i#h=@|o}>`&W_na`EuA!ZPe)<|PdX>uVgh-8|h2fm$Y#9(tWKPBH+d-v6FAN}*feQW^k%og09fZq) z3km~0JQQM9zoXO!$uf)eM>_Nakx?Xy`Bc;He!#hcMVj@KDpOBrm{Z{fhS*xq<@F#` zBzb}ETwhkgSc#sx5OS4)Xe51WE4qbJ`cszrFvY&Bp}-bCY2c_7Tx)IjdwV_hYo(Xq zP@s2fimTXE)a|FwRg!P+C}Ge2jX*(~>*b)x5h9XU>-0#O~A8;8X=2k?M2+-y?K$sz;>TB1#?EL>&B) zzNtL)W`O$7OqmCHo|IO0Tp*X*+{y zMAsqB@66tgtwC8d+``q8cU!MZc0VTAQy9nVV(IpphhHnpdS1_jC~9SJw;$+cS5A4R7qha#_HFn{!;|p_;;04q%-4s*$GC`ySB$MVkWn=y3<||51n=N<!Nq;MJYe_uj&JT#K!f9p~v@7y(>&{snvO6-slu4U;YMNHG!%!q_jY z#<|8CXj+F3?z624zUUbjQ0AHn37ivp<#r412>x)L`bd~ZO5FrIxLEuHJ%E~K{b@FC zq3~HTZoH{gu~}ua`ZBNB>13w4)-pR=*C%PR%VHlz=|yP=$oKA&o+LlKMk9fk3RPeEb=rXX@B}n`F#(_u zL?E012cO;@@|OMrklC<*zVIp127K?%j$<~uQ(VR!aXya^b?Zq_*I_?7jBHZHygfT> zxwf^+dtDuN6Ub4k7F(h|x}sG-6q#-bo#&g%_7$NjhwSKX9FMr>I2npjwwertLE%+Z z($~pBg-VCDgbJC&Hh~(Qchh+W?^GW)lN3p-%GYeZVv~iK@@lgmey5Fje_hrVl%yjG z;u4y3EJl8LXI-1aZ8xS972XzHpf&pIIYZ0{1`|5E2Y|QG7po#KIcYRy7O9m_IPyup z#XA3Hro(`PSBZsQn#dKaE#6t5V0chn(npb12y3HgPSURyui6V~+mEnHS?HRmezX@k z$M#4fTWq3-vY=}?w$YFJICpMNOa~h_l~__m8p(`hN7?GtUgsw&&@65i4+k{qM^)0{ zSUebp>H0znuih65^H{rLJG6Xxf0*|oM&U-1E#xQ6ia2Na(YLc7#a^{6B+Z;-qR7(L z6^i=v(5?bMy71gzWQJ6ZaVNOO3H+ze8N%svl%#UEw?%ff$8o*|BR7}4ekXav=wUs^ z_yfiG7i5C|YE{t0P~reFR1__RgIbpadvUhJw#g3DYi0%hy?dp?Z`GdJsL6^#^A(}= z;?>-V3-`tr;}6KE@FIDN?db9Sw&;}yB&ZBuDEqv|h&8*2iO`ms%8%-H4H(o@g>zB;B{>m!3X5-;aAd!@i!lRoQm2e5q_SRL z71N_l?wYp!eBDXK!@+@WZFL(m67a{clbgJ&F1dr)80Kh7&Tz3!j!|dq9wOzKbU_Ku z#y&Rx0GDj(vmMkCT~&HDS2LdCI3L&dYMrW?P(lt~e($ej^%|J) zX0N0(b?eyrOka-P$|A&JI_X=XD_C#7#9Cx%&@byydv-yMdLR=0NDck34#odOY=8hf zYN9HTA3A+2xK&%_rfGx+u6B>go2&a8zvq-^9}Ap?g9S_GcbP2`<%%j6WdTY;qA24V z@j}|DtYx85Fj)c_?m^#`ab^vYQ%XzV#N&^J9&A(Jh&|#eAO$mHA^l)Iq=EV^HKY`} zGr~kVcN#~D|j&aoutROY;Lkq)SeUkSvoi2y=mmxVX?nDKzrs-*DZtvnLW-&IQmT~MU}u~ zef#a*VctpoS97TvOb58UhfY^WgRZ-6iI-d5>cf`@Ns|axPU&Wz43=yvSjBVv4DFmO z*xp&`{qf-b05LuC*N#_G?ASPnf4hits5L=Z5jqJ;rN`#VEKI{D+#sH_GBk z;(?x5pxZz-Sf$%Hs~PwVtFJP>ONy`TVzPqdJQko>m%YC-o@0GsJg&Ao=#}-=Ac)ib zFIxqZW6Ccwzc}W_KO{cuRyo+6Tf~{2tvxfWSvI-+p5fT-DiN61O;iOJR-=1S#{pVQ z-S!a^Rw|;fV46(e){ug>o8tamsoQdrGfdm{ZxA5R6oT zFuE6$GV*@F@3jldVx{*Af%x$yFO;xyLr;IvZ~Qha@R2R(FKFVN{22+7{Bby zDnEO=^jUC(jGQX99``kms|{7@9Hwo`4+j41@xB}#_rG_ppKV=x=D%#!ir3L;SLl+C z1bM@orZGG=!wc+Wp^jd`o=R0b@So73rs+>ZNpoL1;QkIbUFQ#|Kk0 z#4EVS7~UV*aQknTDwtTfKR*+aM;X47W(AmqV6tkpFP!NUn$FIu$yvvy2}&NG`5b4l z^v_UMy)up)C+_)ECz`O{5r-9YnndV^PurVt|9M+W<<3NZ`k4M_9xI*=LicST2l0q)jHVBtvX^IJV&uf z&AsF-m(Eg`tk6yj2fW*GV2>9HQ+72#(f2u^QuB@Wsi#c22)H0Uv;4JBVmbbyeZeln zG0f+_@7!h&YAqTZkYUTdUEBTjIf-(#`jqa?Vt+4MA;F<6cVcCuAlvtDW1Ec_vtE{W zc3iOW*muw0vwLk4M|uq7`bW(^P#ALYb9S?kvM+=#d3c1+=d!a$Jpd~)3%(YD>aV9$SvCE_q&$Ae_N+N7Z9Ja zy^w}d4=Jk1U#9=aQ!ALIQJOE}r@X#4UOoGf-lCYswCkPA+!@dk`$(>HlKZ1vr%B=b z%<-qrw{{p>l6V|G-dr7EF5mKEdz;7C-gtu2FyHQILxN%ZAQ??l->v|mqX(rttOxWR0bGz6=Z{@w+n z;4hXU(jq2EdQ|EvQHd_8h@LTocnWuw?5bch$PNeTmayZ_yi=dl$Lto(N_tehH<$V$ zbBl)_9Kor=StUga!#hYEt*p69EsMFI(C8OU8NV8Fa7bcDGq@wU|9;FcXy_k=0^ggP z1hcu3HS z_La(9UQomD=+p|&_V)&d$hOm?3G%$S9Yr#ShyM0QN&T+i)rS{La0G6GOHs$uTN0mg zrsSApqeO1jYQ;YqM=8}a;JdjhGCRI+j5eAnPlEbB!M&ADNxr<|3u2KK!R%@2eTPb; z3L9@hgFl5_?EFAJGJc`y?%5{W8QE`$ImW=T`NyAYqc05(K>uVE3940sTEa`@_V4sr1JJCBz9HJnTv4|m8wwKiu^i`51WO5v0wE6z zYvE~3A&@l^e{!);;siaamyOhKJRoTBO(5R>`#&z2f94Ppgn1ZD!5q&-L52kntxAIf z_zO~`{Oe&B6R$=F=IdlU6A0N~y}zwbou#p7v&8JI`jxLDvZAsm`}Vi%c+tluw-NSul-kIbMHH3?b;d+EpfD-8J~@d3`?3hq&YB2+6Qcbv9Y5?DI)b8N7T6pV z%+D!BFDt}Up^!Do_w{PiGK7!ZSnTGZ)^M05G?lBh&K=JwuT%Bg4X9z7T3vV>mQ+8h))+}ro$XXNLqeDC)`{cQqC3S zfo;zYv2gP{<}3+H*Z6uln%2GSZda}usgQlJ@o?A7{#j|P*PhiJgMM`U!i){C*df+D zzVxUr1rdMx6NtDJ&6etv;0OLz>8)}pEcFzNkKh^cxl(tfkLbt>gy{6*UsDM45j<#c zr7&(E)G<#D*Jb%O(CZfMCY2+r?F0N&O?~U%(RO3tyIir04Uj(b>wmFt$1zZ29MJ|H z149fw=DCRhL-Xp>pwW(--(eTF>rpDX-P1_<-RlrLrr;yge!lv5wnbTmfSlb8sDF6V z%%Rx!i@5YX55b;!aARfS2Dg1+I&C_)Vt9}!FydYb`&g%x8=?_TZ<B#E!*w`iYGvt@AlNsBebEu+UoCCPCed)&T76~*;y=XTcXeiN* zte|t~uQW*URm+gCeskx4>i=k5aH5-MFjAi*z4D98`VVsVX`7U1mJOAnkJ`hWvAX?| zLpRmANO|*{{|hC+3s|6eQ93pZG7d!l*N`NNAUfoU&F`?gfhAq`o8Tygj1z?#u|(1y zB1~)_EsPI*&nk@}8G-gOp!lzN&h>>3v%U?C8t|ST%K=COAcAv>XZ4BNC2p(_SBIV? z(r^3YZbfo#yyjNG#0c`AU>S15k}nvaEHXc)qv|!vlxsKt@uE&@HSN6TF2e>~B&Xwr6&qsrlyuI4#Qqb{$*$lZJl zSNJ<33L!sz__X+3cpu|hB3Vj~%}trWA%0-RF<#1|myAZD%Jan?hMA{tm&kL#t-WhW zr}>q1j$kkvm#r`51>8bu>n25|To4t?ayT14OOV6zuu<~WV;|9mR-Z%;z6m@lCgYH2 z-`Kl&N2MEOA8aW02s?+OH|MV%GzXOMNp&Tia|`&s+~d8(X)rtyhwAvg=Rz;$96#n7 z{0ma>;m@q#!XV>blfBBJtBBwCi@|pb^j41lLnB^Nw7yBx?2^{~*A|8s@BzL2cg%em zW*E2d6cD)r20=vs5Zr}9z6&G-B*4H!(uG;2{{7$~QLpyY@p3}?35YdZxPwg0O3coZ zQt`mSkaiiwZ8>5kt(5h9()Ud`z{4NSg9DjH(UhoC$DH}%GQL84=(7P7<0z|m!gs;9 zXd?zrT)P7Ktd-Q(&91?tBsAnn4|+sZm~zT+F6>xwA{={%f$}bIC6-QykXlN|dXhd; z{j*m=VLI70W*JrFcq{q33$wnKlBVsDX`^qM?PIZVp&Ynnc`^V9k8J3YN| z6NzmOd-osPSa^GxfKEG~_Ufi`+?*CYpTSk8;L5MH35HP%DC@j^B-^|LH@z#>ZbwAA ze^QL@DPZXvw@&Ret88NpbOJuzm;Mgm(vDqn)1?o`taLb$*=ur4c2#A7s#R=qi>oTX z5^$*+^Redezx-a8eyp%F8{$cS1s@M{v=4zRP;aXRb#`gd<3N-W;kg_sUJ=HG7tr^d+i23C4Vv!^dzhr29wRPtLI z0FKe5cYmtfwE~hx8=w3}aBC$54KYX;wyY(?*-jt?5NhFOJhp|>r?EdvT1?&V zEI2*u=Vv=BuLbmpn0#3w-wtA8lIag3f{Z(oyh&)*#@)L=2Ex$*k6Sm$92*30*o7n` zkx{?C!U-lPh1JGRrf^5Ek7Z0GJ*SUr#?K^uJqp~;d4Ivm(N-zmpZ!r zBErBL%NJVk%?ZPD|0fK57tprMv+>y9aHb6!1C7Pg&w{IDsb*2kk}i+S)La#(BWsOS za6b3{FWL+*Ambm0eg+_Nm*xeL2^SUsq)}5lgu@%?Y!7Ez7iW(VVj-@d-3g00O zdZ54Mx`uG*VnLATZ@77grR#?AQ8(E94SxiQk3W>nX!wV-rnHu;W%F9O3hV!Hjf6&= zX?q3O!g@U9>C5(XcM@+++W4HGo(a36!-1o`{#k#g)S;X$&89vSgogczrfj0B=fct2 z5#$74GP|)Iz^GKddT*uPR!Pfck<2i-i(T3#mQ|Si4&Fc^0EZPs^AQ26Fi20kghR$C?ZGR!S*`PcgJ9q%9C`xg`rv;W5AkR#@}hK?(U zg2QmR`2O(MFin)Hl^xkGL&fr&Yr+tOYn!_VMUWzdsW3)?0bBIa5jbTgp=SY5?)@O( z_nddsC%LQHufh~4) z2dxiRo0MFOl1?O*ZS0r4;=B|lk?HU6O@`^S#b&Tc%9G%nLk!1(LqQbHr(&;Me=7^& zBECuuf&Yr*r(T`9M?9bAB}V!o*T#C=I$}7TpX;1czq}cTmLUD;z-c?M131C_JB>8SvQ3#x4~Z&0U|E`wfxU}}2RX`F!*_U3!a9)$QoM1vI_BgE3zz`IsE%+L&e(@lHdpUt{^Alt#@_D-IU{t z&@buuOqb{WQFUO9C1aXogK#3b~PGQk9f}QU!n#CiBqlhb{~+MClRxMhZ>FDS{7wkL)1CIP|XBY1?a|s_a4y z$p#s$ZGSOQqTyR#DP36b>%8CB(m)3!&S#j%T!BX4qisoy{W!#Pmvra&ZV_5J-#6In zzU`;+1*PeiN%f#&sObrxKKBxdtYMtt?z2L49AGZ`d6`ZQN9mD7XewK9b?oWW6-T!A zs&WPm;je5-+S4-p#(~eTe!>)oCI|1QtnAkpoS+*CIo_m;7hF}(4I3^3S=O_9^l_ub zYt@&B6Niyvq;m*glVW_5WLs8RkVAOw<@ad*Ka$0Re;Vq+?}*+14%Y$z&B{*{P{=F0 znV+8u0?AzHotK6Pd>aUR#wKURrIC3+M4yGdF3=7740l3>9KxJ~XNepEF}i(rts8#& z;>buC>Afw&T2pAEh{Kw+*~RXiN^PbKyZhdY^f}cj+6BR%LBL|Dd;)dOg^Jr5CW@@3 zjD(?%g{zFLy!9${(-w^WdY?*YOJp(rT2(z_Y?fBxivzER4;383Fft$=C>+RuW%Q*z z95?>`JD8FieeJ^X_Qr8ffWMED+X7@&naaCn8+}5l0%n-;F(46h{Q+s+Rf%}X;@oDR zcfaGMZ!O@iuu65luTW?cys*YE(sfnS(=RHCrDqWJ0!8gL=5mdXY_S%dhzL;L>1NcOMfRN9OQf`gqt4@X5J1ZaY6=|lJ-lu(q7YR$;-&|r4p zwC(oRcZ$CA#%kC?b9bMQnjqP?~ zZ9OdXikq}QJ%|JGp)2Wu3OqswF+D(VKr$cVIR0XR3|>|_QjN~Oe-c-$ z%7~TvS892r2+0qk3c`HFtI6QTaS(lS+Gs?Z*p8yy{cloyjp?%0nf>5{O;`8qs~Wly zcYV+1`bxN_`*g!n=zx%xt7{g!gH211KPm?&rbb0=TM(`S&t6)~>HX@@s5?*YYvulZ z+GL4WA8O`h=C=(RY+*GI4l|50LqheeZU)sl8)qITjMC8_BZFqeLD#k~!w{Mfx;rA$HF5UApVU)ia=WWh&n-@=fO&pyW!xV61;G%saE{A>54A#c^6EQQls)0+p*mdX zpi>|fKx6Ej@SS8Y4>ezwB)6hIw|>@^uv{^Rc<6aOijBI|^N@-avE%k|^+L0>hpCs3 zlyX_$B7!gaEzh!1l;}9aWCT-{Ezp-7Cu6v?s@QI@_(jmss2cAVKfxcbn#n0ok(Xnb zXFyJCnJ3|te6@zsec=>~*SK5Dw4jjwL0s0)a5oz^M-dpb_1v=(`&=z?@D!UwMrea+ z18ld)X6t#XVLpOOvv1v4fpTkhrt{_U1cRJoZ^)o}&|~OUh^-*wW1#alyh>?b3M4*z zRFy3I4=j4M&L!KY$-pBv0k7ezH__{K;3LRWw-!c=;9$)L%Sl;9cX~uTLjOd#CgR7w zbBg~(Av6#g?Kko+%O{9ptY4Pq>z(bJg>Z*No3-Moqczh_+l%T`&Yen9*I{5~?0@?8 zPVmco`>ALp+~prZ&lNff&{*=YFgMdB3(*$FjSU1Ym5Y%8BbIKiQ#U@Wzsf1f))8md zwxEcE8$4^{t<*4&U?l{Ievt~(uXv~`-ozHV42)K)f&xy?D3ATb9n_ip?|IQ_QG#1V zp+IVuDoeC5bj80VWVZfkCcIL>j}WDi5MAb!j;h&k?JWDiw5KJ1G!p(IM@5Ax2@$^V zrfx;|Up}(#wF1LFij%sHQ>1cA3yRNS>7RPOOXb!w-}O?WRQ}#3LW@{LbZ~gPm9PUh zJ9?liVQ{Ucv*WJzBeyk%&ZEdFZHPEq(pL-;*L)^~A9AtwAq&~y=~lB2=)6P^Ysf^5 z6SpbDR2uP8H4Ho8a&X#z8BP1j?1H^euA%#I_wtf1oM7*#kG4j_ zDY^m=2tEcH2U;UNDv~#@E#*fofw{j(#(uh=h+EgSJN-8cz?o{%!uyUak8EVYTa97GNlWqHttBhhy@i=yaEDohz@3-4}=EpJM zVw(}zJ~sNT&~T-|k6iX=Ki3Pj$K#&(*+t7LU2C6*z?2W1Cz3BL;g8n=+_Y|_7d31D z!~-aP=@RP33h)PrB0pHtABS=S0f^y1C^a{}GmSy1Vwz*(IBJIT(w-QxJy>|>H(|wZ z1qvAF7AZYOY|`ibHV_tAR4;MAWZV&?bFip@x!&_KtkF>%n4rOt(zQS6!P03eh*@4A zs{9u0aj2d8lHg)7#vyKHh1D2PCwndi9>cTkMhevKnbodWvdg>D3PbeVH6bAHZUdP% z+;tXU`rC`z_gV|Ne1Q1o`&ECNqMP@7x1*zoj59}AM@~XkPf9&5Xp-sqQNJtLX;wB> zhH9=II^TCbu%6(^12a<7$hEmW!uV?V(*IX z^4>63C9MrY4qPzIf3%L?n(@Mkoy&5VGU$);$6 zgZ){e0i@YTN?F##_aUD7TkEx4S5-{{c5dR|9oGqenB~kja7AN|;Tbtocn8EB3at!0 zdc~5{1~tm6Iz1p>jZ!3*KhL45jNyUZxR*K{Hnm)z`>*F7WRq7p{8ZK?TrKTm0eMrQ zdY-A5xoq%4=7*fi{Wm+B4%GjY@0YxQH7=(A6>>x*-_1W`kQbkcUm-dz6bTn9LX(z76@zlmA|yv1ZDh92$_asIA~$FBSJAfkH!av#A5D!+;g zOeD^=Ewvxrr2Z7#mbB#{lRUN~=3nM9B<(xXq8yrD@u;u*3BD!IBI$7Abjk%?QMLCp@M+pM;CBPWa2g!nChZZIhd*B6o(TgI^JZdNO<)V^-5`OY z=#<X^@l-rKP(ihAwFd={)#6@B4n=b*^)rYyStcXWzfQ*IIiozmUzH?A!Vhm-1P2 z@x@f+fqlDeOrB={wVNtzg<;J#eqD$?8}8AJ_3JFPIFo?C!C)59heSuEZQoAwH4f}! zpa3F%u%KE+yIK`8=@^5g#WO(15$JIefMX|*H}yZ6Q4;28yykuZm?oj()O#{_-JD;c z;%NlZh|^om1qfE*E;r#kXJu+^6}|a@5>yb-v)9I)FU ztcVIW0g5eRzoaJisSb7XyU@2QC;n*LUfFFY3NQB!opk$}H;$g;5!C2Ty<(~OeZTvt zwMFD@9@A#}f#A_pA`t1RQU?B3O3@6eIoeaDSZNTgB4?BN1KnQC9VED50Qd~h09*iq zLn|sy_&kd;;|X*ihz^Rk-gq#U>XjGxewvp>49oww0s0?L3Mhvr#~Ujo$5wit^Xl4X zQ@=rqfFKYrA#F9Gvp*M4>wDxDg0UYU2t?_)2~pCGOMfpmX6{yL_j5oF#Xdwx&Sla- z#!<6&fzfot@F5>RlmAn2r|?=Qc)=@c{Pkn6J5~Igzt&wd-{;(+e`?YbaE5CHpqkj?BJqqs}VbMqe>ruM#B95=0jCeTV!2|J2K=a^p8lH=FupU)L6tJ0GvbcOBEi_x=FpYgDV??&o!V=r)ccI5UO<$9UuHa+{Pb3%v8k4eY1kMb5pAL$8qxd{WsM_7i$N6N$;hao}yCDA=HD8hD_K=A>|H*s1wuD@;zmr-DBIdSM7qIkVeJz*5b9%v8{!RBW#fRiBk3vV ze*y`!>9J{scP8mYMFPaajlBbdeNOV}HQ?!D{Z4t%X*CX?@k^Ed&*;o;=q2)cCrTBw zn%aiglhf?u7p@r|AI18FZIaGEoqChOzfXR-TNlbG_H@FD9VcPXyFAO}J9enuO>}Jd zT^~BuKs~!;<9>q0=MF`=y|@;&>vF-F>)9Y)=tpa>kGXU5eNb$MikfzRLgTw1Wi8)o z{&T?C#5cjn_lL8txe-U#!O;=TxNO-UsB-`l6mfPC8T4a?}e7xpE(*6Xr_3h`>)}_^< z|LU2_AmSuOBo4-?jgKt2;xi8$hTZw7N3L$XiTX9-86LM^*jlKg)Vi9%v~|v%T^|{U zh%s#yU`KXy@5#3;JCD_c(kq2s=UsF+h@9N(^)u#@$8Q%$=vP#I7$?OG_!s5ks<-)^ z4GN9j3FLymxte`FQs*R$RGV!_gJ`5>=i{tDbdO>+|NOGT@7zwxdIAnnu7Xx|P}g-7 zJx2Z{rqTP1u<$q#G03xs=JFW}dU_tN9q;$v=iKMJSUO||X<7yZfbo~y@Nnl8(dRC6wj1HG zif$14=L{4V?O%j4O9Ry^xtU?%LLfgtVQX^eHKHrf$cG+FoL|tDxRF>;z*%ftsPV(l zHY?GLG*d_~rQ^sbo}M&=e_?s4nZgsCg953Hzlh!T4Vy&%c0SH`^zMhBQP}m6aqxq< z`%4~pfvzllb*$Pi2ce+JilmQ4D@kwb&rlR5KY}%poFolFam9~8-J#?g7-KBiVsOVE zTbaKX_s=CiRfDX5%m!d<;txq@=`g8oy)!JF%er`GzXo%3!Q&yNp{g;cuW2=C)DM-% zv`Eq16M{&+H=}Y^467gfIC%6b1RVTf!fz&oSpT>9qjj^)I|=DRZrf1qMC67&7WUs0 zUFh)o+NCkkZ96SE(4bL+B15TWC|344CjJ*U!53(wpj}$Y6mTv-^XsS9fgH zB2~y;POOD`mPMY@G?kuO+C#99N;+$Zbgnp460I0R-%#eKMh>0p`_#Ilh1iyz*TYPw zi1R+EDi(-Xl;u6PMpMu~4ncEL^W-x%p?a?8Nv_}gi!CSi3GIu-%tuI)jde{uF`Me; zzpk;m!!HaKxthln(G#DP84FLR8U_!1SlQR8#O14?H+qod2V-q*J`MWWM7$3My@zN% z^(zd&8HInzhWs(Q=UV9Y^^ajsIGD?hee$gHX_-?$;Gh3qxq;OP_dH^x1P zR;@+p1{lnL5WMY2gd#q^fZ=3SaA%l=cG_zQ^aBzBEY##t)?X4|D4E6+N`i5fGXbfj zw9`hyzj+)N?96N62&@D<(0GkC-RHb(+vcVg((Kz^cro{oKwM7i*$vATwfdM z=Jy}PbCDyO~~t z)LolABV2HdZy**-aQgk-V(QCo@mo5*3`Ql-;6dj|4yf;V#TCWjY4s@ai=g}ujZ-5cc_RClH8qQ436UH7bI{F#BPO03sOou8>g87-_ElD4R&QM!JuT@QW|` zJKM{+!6}wLNHUs6{wwsHwFs_Y#14ndI*#>#1QcaU7W)GvG*~O3I)|I1ef$F@=F<<3 zx$&S66`)Y+j9x`Y_2;a0A$CuzAV_;rbuxfySz-1XM1qfn@^E#buTe_!10&E)Rll{BjGMv4^sSRttTNTjdfoH_Nw z?c$>aS!EO=s%kf4XK!C}Hl16+cZI-Cp$s=Xvn|q<5}~WF>u4V!H$6Y8s92{>he_LS zGm%MU)8?)-4H|R{2Y+}FJWV_Qi5xMaRZ7OE%KJBH^5chLGLb(3Jh%PO#0q(sGua68anR;xQ6i6& zZSuES6lvtD3t6{poQtiGU*hc^%?l^wh`B+YE$JOM&s$Q|qzu4>%);HVEk8!YI!EVH zYqIIjJM+Hv?LgW?&wS?K4Sv6n?IR?i@r)OJesffLy$e(t;A8BLp5>ott8K4{LG8Gp zhiBCA=!@e`fDYAD?PzP#KUFOM8>4l`5V*q2t+#b1*G2vI>x|o=;%#HfI_uSl{_e9$ zX}z+m%;z0O5xbQAC$cgZ1tjKu9PH;pXzqQZWd))I{R>IP26FmVO2)+rbmyHYs+zDp zpZUIfe{}xWCh{RrzpZtv6oME?9Nn8NGZWWIAwWfx0T0B0newqWJ#Z4*~G zVVoX%b9kUFswj5Te|jELX0aDF2N=Jpbc%N#my1dGU+;uUR9uGSDu?&qROVE(bxhe$ zJeN!Y+qbZe@u@iY$QFT?<#sK^Nj-FnZ80Z@Ap`3KrCnheTwm{mS0-Ge*|i|JtME62 z&yjTKLC_}G@sJy60uUYd?mWt{WZ_7paEJ{*%T&q_hyn=8K(x!5~HLT4W;}Wc3jLLRniJ16Vf{TBk0^SvvIKr$6G69+wE}J#_l1vBHn?p z++}Br!SJyLyTQg_rm5cC&^>Mb>V)gK!eyycVRnHi&!n)fkT4EC9&kFA+Esn__-MWG zx?7)UUm_g3+G?70>Nv}LCzGXXKmRR>>5BB?$8S`73_&nx9WCMAg=Gq;L6w0m$vcnZ zD#STs-wjh$oT5O4=Yw3Eqdq)S?$Ze@cs3zso^y@iXoG*TiEmhn>~FG!`0T1M(^{F_%rH?0zRE+ z=Mp8AD|?+w@W;T0*21*U+vg%vrPXnU2p{G6Fo4iLLD%6_pFZRb(?s0^jc?kv z*&)ImS~im^>qu?EHLfXa6jcxp3!{qB(Bi`Z&C-)!$SaUy2OXUXzqQ+Xz#}r!dqBfr zZ+~dn_%^9BIwaw|w5wKC)EvQeSjVv{`H~dnliPvxRRA}z5WH8 zFY-b|JdGH(JyyhK>{8Fw7^ka!+(kr2Wrzh^xf=2`$hh~Y zn%~WywGiu0nZj?Z-p+zPmqN(OW?;bvw?2H&^?QXx3~mgceGeu>ylX|9!d|p^SqS-C z3GWGGKE)H-mflNV_`-Fdg@osNpqM13D$7UPcSFQ=qAGoZ6Cn|Boz|Xs@~i`hsQjnl z3PZDOOv|@$@rQ{~4e_+{Kbtb2XA2nRo8`3@?tMQCQCp9vR0jsH{EI4?1i0429yyg~ zPeYuMFc6=De1-@hA>92XlFErLa#Ku%hx<7g5)ZHdKp_1s+6nLth6nTHGG0vQ9pcXN zgO3P~Ko7$+i4f<5lFe3g^1VYw13VgBGhOQl6_8WR zbj0qTmAk^C>J)js5lzCD20m1~R!t8fvCLk&0w!ZfXMe2qTW#VBiVr*DEY{z>#Q3$7zjb_irDNo@8Mr${@l-h81=FPdqf=K2 z-iuBtT{`h~q5Zd!`^IjQ=5p^>E5naI)KT5e-I_5!z>X4(ris6edUlS!ZmLtlV0O#N zw%GYhJW0*wCqn`8gq)|_&*j9FW!=_hr?s9XWc0XIRNPA_KHfzq`Kh+kVI_Tw$q9x8 zx|XTgCg|WB(^>roMtn*;hz%DtVHM>E_-}kP0f~LMH7~^QK!g!l_sUfh5tb90%;%H2 zc3{$>LU3|2nE<{DE_s9(?z;mX0T!g2EWa5wU`QqaASWaugB<;kae8l<4gf}6paPGM zazjQK@tzZ8T_U|wTr~{@N4+gj5rf&=ja*nWckYwA#Wy}9L6!4{3IPxORJbT>r^+R% zDsXCYlbU*{p@e$8FO7+;V57o-ZW-JnYD9DelW*|N=ko={l_?YpLp}?=#kh-cmp#!rs-4SjqWj~RS)uPrNVeL} z&gbB2FZY>#vbKO1?ZTLj{t;_Zqa>%wcE1oFlk|nAsC1N($s~>N*1!0sQNy?=yK3Il zkm^m8GT}i^IHTt$tc}aD*wk#kA4GGohB56lYI$erxcQf3-4>*@t7Vx8W6c4t$$=mGk4v(fa=)Y9oJ<&PF1% zt-lzH01X?!^oAA*7Z}ah-xc7${~c;<&_U0CmQeu2Nb6M+JS-2c+!2Rcfn0%^fGPk7 zhQ4c;2p*iLw0Zk>+<^u0+zot%_vz#*MFJ)TSgWOcP?clp6V<6|P$bYfMsvH-%gY2z>Zo_Y^o&BKr_xt_|X+ubaa9xml^CwLVm%VR`He z@HgZ;ie^aqAh~p6Vu~>~tI2J)YOy^3an5@)n?Lzu(lw!&>ZKSo@|hB~8;Q#?{ef`_ zSHA8`Tkh?VT06L|m;xD|oNK_n?BJF3iZ#8dbX^(&ygWdR86xxFMrq8+0@dFFawQ8G<-v+N#%|4jA5x}7xMcb5@l?CGRD%F=!x`tqdxRVqb>emskSOeM;C zqb>*hX7_+4o^HE?9X!5^bhL)EzOKXsy86({H|8HGy+fB6g$-S%&M$slW!Uv!>0LC2 zT$7?HPdQ_48Ec!w|yqUgSaCbOWLfz+%MRcx5e+w?Y^W# z+Ja!&p{Prc9=E<;H-N(v8KceTy^x0W!=F!qn;k$l;pCYskiyTnkY)cUo~Z8FfK8?A zT?0F2@rT0!yu+rk``=niE@xh5zx^K@4}S($pqkU$#eJ~}_b=L=Jr`ol6dd7q1T2Qtz(a<7r#%)`ti9>Y}{XW<%#cwb9yj2P@g1j|7!F zFY(C5M3ak;^cqgS-t`~4S(zD<_1_}C=y|qLF04ZJ&s_1uX*Ior^T;s$9S}R>Edpdp zadXOA2|Id}1y@5dyd7>l*KcCZ*sb%*XVIX@Yl?*;6v*W7v2hii!>AlCKopBNf08cL z1~b7AmSq5C&i8X|4;$~EXE(CD=(Q`4Mj=|(8!&?7ItAcMVgt;%&C1zXw8M%JSI$^e zEdh&V!lzWp_^#5VG7GmhFwYO3=gnik@a!~PQ61Hoab)GZ!=VA= zqIq;*%-49%gkq&|StmUGV6~*fY;hjY!3n~i)`FCV7`U00W&A8dK#pNwgrG>J> z2uYvyNgOp!F+=}13k?-(iG|xk8WmAz3Jx(l#u3I%6D4&7sHkwFgs|!W_X08k5;L^xq)n8m<@I*z?T=~Q!fd8Fn?5%#zKZj@|jdonC}DHs>VpZ zh;SENr*Fl3-X1pSRO(82s9o@C^yBTp#1k0Ip3eJLOrHpA^lGlZ=g=3Q%(?&M*$L+x zIg6zAq%KI~Y=3fa6DIXbk49oi8L1N{%J|r9SwJiIg#7-Ph0hsn*dMeLML7hB@ZUsF0wC;Ok!7#!`Z*9?~Xi_sTeu(3pob^A$)heVP9vvE9aDk z{7ja-CzXQ!wvz=>NMMNs4tBgjyeA;-eYYM^C8EZ^4&ZfwRJBQ6K{zm6=*y1t!mE$X z?q$KVLRX*JXVJDd+WWU<#$-+kX832&~W0XP>^C3d`|VJE>(CW(aTFuqW7*ww1Yp{n<~ z_Z7vgV7o@-xGd8{!01;gZ~6qYB&758Kkz&PD0EP5D-2$V8=y`HrZui?dpFRRwkA2> z&e&>*E*L0YnyT5_B$a(C8p0K1hDz8looyRKK9STL$H7-9=HX{A+ya!iL`> zn^&q-aB3s%YfZAdMC3C_Yk$)5cW!vG$5Do7O9x@RDS;~)Oj0~?db;&>DJLH}bit%Ga#o7iu)R8^7w6k)Y*war<(EP`3AMy**PPnxykU>T|{{of&Z3lm_&LK(sAgM3?Qvn z-;>0zrg9ozj560v_}7Rp%h^jhxvXpWwBXEs4b^X@piQ?17v%J%_V>QJVRROy$7F1A zd_;5pb-HiS9#IF4ZrE`i>t=bBcn18fkaN`uer=|bXQ0XOAzxJn17AR zo{UC680Y!GP$J{ib7`&bb$r*EgU(;TTijiRTCDV+EdSJhL4@%#hH%fM_({FVro0@o z6DN53A6^_ss;4JaQt$0d<&30pNgGUF;1b{>*71vNTRM(kLLeIP3+Co*pmG6hXs;m&J1cCFcKVQr6cLq$^+*)90(D%i`6CuY;J6mYk|b_v9r{WF4f zKqsnjcrpKBdF*z-xtfcpJz`K!cxI=n6EFNf8URb- zWy|0de};aC%zavhchz6gG~X;Od~D{pA7sB6B(GiLr>IwTU;7Jpu8tc(aOuL@uq4s` z0?z3$q*4T&dab3t4F%>^Fz7(GCoCe%_TWBNi!vM+N)lBDc8ACTba&N2=;C3X(Hi8< z`YWW0Yk`7lri!N%P)TJixY+Z0f$Dy_bI6FYWJ!Lulc}fE&7O4j7G}WHh1A6=r1T=j zIa1EHVkF|3IU_uJQl}0DVHXV5D+YrK^DZkGbubqqk&tXw3sqOL=8z70 z0v@u824R`?({kvzxehQ-3l@*##1davG>UciJdGjsGi8(7*L5L*GYXX2*P%?vsw2Xb zzIBxR`<}J^5sI0Ps8wyRc3tV&Mc-Ny$+*N*G`kJ6MUL5eC!8YHfxAVVjw3oOaxG@7 zbZvgrm^bK1<2QgXO{v1sVarOB*cx`|@|heI)L)ggS&b(FT*+Vn5tK%+;m~JIjFYaA z(PI7b6j4*Pw2)mz>n4b>;>m9u&z_jQCXavlJ&g4IO&caALLsL*2UUvZds<2q&km~aRHd)LujP{To}Il6=e9zEr;j}^ zqFEKNlW%8EnT#ERoR5kv)DW}1_iK`L7vbnRV?x+n+lUL_3(@e|hMy97JT z=ovDqFQZpN56Z3gb5iZJ_BU&M*Wj1oRWcCycfns6>{S~hW_Mg#@@4g6ncEw4Gg<8i zIV)--(zh>b>V+++Y4Ijf~;wKdPF$4uV+^zPLHVI zKg*kadvLwYF2|QvX}cLf0a(EJ9$cxRRTE+8iIu$ikc4m?lP+Q=GHIlX+{N00;681f zX$|d}1p(zXAqjaV-&64Fjk8A};xUF*fygGtH#$tZVc|(QV%$B_mdtgrv4M5}n9bHg+%C{cbE401)3n@I$9{;=iXT{1V3U^O0cVxOcICAk~YRWEmcX~nz2Tlc-wfg4wzmEcGU`0&fWu7NgS-9LzsIp!aPu6ZzU zkN?g*WhK*m{wJE^$ofo|oQ&Y)0p6L4O=3UApgC7HLA*eBLfPN%6gz*|)!dDJ>IFA+ zq15Edx9hJHHr)bA76NB&$8vKra@N`x};fMSS6h zS5DM&JH&DdFL`TAjd{CC{Em3%iCbL->2q6t4rnz&v%BO(se|OE#yDPS_+^S6n13|- zP*z#cbuZ;RWR&V5eBMOi_xUfMpT%279iZQ(b5M8KoMh^rn@q@{RMpwAU&fm}f32Z>?2KFNO@##zgv!X?8Lz)~$#r+zNMXE6+t-?D0HfHZj z*L$eNOL7kdTNO~pDEo)P{zm*Pn%c_KKS%wEtB#6CiQr=p9AL(ghk#(5cTvt#gM{Al z)a$%Ff}O)3RTLW)T@S>PhtNh!-)9ehG!`jhQM-57W_tb(*Nw${pIyiJVYh^8R+sZ_ z@oCX=96@lG5%AI>mioPi*C_A9*NCY5@UhIkmy?=@T~p3>P3myj%Ii({LmSTBKPA~( znF<+cln*7~xAzoSo;M8RC;TJ4v}xNl|rga5vXrjpfxpCZw6fzJAf ztoDYs_q9(f7pi29NZZjZxnFqYqz*?CvUNHU(`JCof5>~2)&GC;KD`(Tz#mSrVi+-M z9OZWS-g9B|3n_=N0~7K~C?_X(lLCb0a1X3*ZuEf8y}+?OC(?izJ$MP1t^j3j8Is9} zbf8AO*X`+m1fs_jCxQofZ`gyrNgquCmNE{@xj(R*baQ0=fZj5xaZAbMF0V|lxX zoD}4yB{Va|;K(fI=B)!)iEJGp!+pp*E7O3|Kr-LYAyuI%z{GKv#~>3G2${h@dgpkw zoTViwa%)~0oX+Rg)1-@^hA%uO#xSFRnWRq!q$7Tvi`NXKp+gP1uR2xq(!Th%w5=3{ z`jTfY-}+|%7CKZTvio623FF;WZzRJ%7@=u2pX3`>35;9wk|dESOH`vAL_(DvEIbQA zNGr_QQI>7FKi0XymnJDdP;54xwJnTTk3b1WyAjtY5le0N`QBRWX2o)rj(uPFy1bC&VEk`t^!rTG~{rBkD<4r%D?lWfQoQ`uu zB$QJCsYwAm2FylnGoR=4IsM0HT5R03S{#I26WFlAvlc zLFE1A4X1BV6AG2=Q%AQMH#as4nv}IGtQMIE5loC&3Mn8py2iBf!{9lb>|89o8tvZDU!m2egIhEAVf)s3i^B0PsVxsqWb`Tme$-D zGxlnBQT6nXAPPYKY@h{2Tj;PGfvEi}*0&oEw|Ve#RT0X&xy6zhBrdU{+tVRQ*+AJA z3)+(l6heg2J=(S`T$H&Ur8BK(RLFUOEvQ2ThfETZ-XIZXln2;ovD5<7H(H*4gcr?k z2BWd|P)RR}JoHQ8zV+*D$ux&E74_?KRBo#Y^Hf)kEbIHqo+2F#Ms=9PL)oEwr`Gye$Sc@4z%$^ki~Y+Rxdnc0(kW`g6{D=Pvp(KrEK}3M z=~%}&0$lex#Uo<>als{;zrC%;WfnC?X1_9b8nAW-<(a&qyO48 zIJsJKlYV>~oymB}c@7qga2`=&aXWt7#rI$O+gk5wuv0E;m9h_ddM~g8ke1c57F+&E zw-pk?(CpV7cc_VhS&TvynnWa`8y3)I5|7R_0Bm$(P;^wG5tuFr93#LQisdZg=m2`u z%wjqO@_|vA4W2VG_h1NMCzWD?aw%x&tIubUojWpRm(U9D`#nvC)Q=Z-f1}89PKW7^ zfSPxAEg4u9(tTWNs6*7wfY4VGIcD~iraToaJ#o|0Tc>yeNrf;ADMl4O+1<1gT~Z%v zqg683PpYRh{7w${_yo7BRdE_DY%M5KtomVzrOa&aOzX?l=9wuEUD3&kYOfSn@`s5wi`^mwv7oO} z1y=<|UQT?4Ex=NxLjGyXAc!lqFhoGvxU~9mr7=WkR%_b|gYoAT$!hB9M$~lfPxaG= z<<_O)05&{2Hn^uLuhX-ZW#`aIQRV7cc`ch;>1_W|$Df1FXNAw;?*b}t9D;q4UG)db zN-e#Ui(gcn;q(jjmZWIN=|@#Y)jUw(BD0IV7Ktq)n)x;Z2G~{l`;WiCHE*1nNF#pf1JE^)Ji|f^5N>l zLi{QK89cHgw9h7&KDRSrs-)Q~uSdxKzZ_J-n&ogT{*_NZtujbsydVQQI;K3HYz8Q* zfOrtp5<^V{_x;e6H;e)bf=W_eKWV;t6IJ2MSY&KLZv1qcTR?b&h#<-vI)XMtmpl&F zUlDC}(M5YgeFwoi>yZQNGp-I{lS~eDYG5chPW?l7JS|*O9ux>t;hH0=1#J>u1m5Yf zi;}D_%pvq!Wm)b4kMc4W{V_p=vDnkj;=KdrXlq1)$ZxuW(5=WF+Ovqp!k|LA(mTb5plKm}bkg-( zr1NCnrD#gI$cChl41OI*$mDaLY$hWMbiSAy!3J48e=&DLvdf*ID^c?tReU02D@r}o z=YfU!@&uiezfkYftCA9Z<)W>k4%A5vTK~kDAO9r3)(9OO`PS%gv~i)(7DwStIWVx3KH71Vsbx zjj@aE5*K?NKYlXjiCH@hr!78cQ1|_s8FpOY}A538H#;w!goiSMw z-Qo-gto^BUOU{h^69Kd1GD*2Qm(OnyDH#)DHX)-4V-Fq>b~?ZH+pi=*fxe;AEA;Z& z+0Q@hCES086bTa!hY=UXegVYVzlxx$E|_2JyuIk*EUk8?*uAibyk@oeDoHvquVFN$ zKqn_}QtO)RDp)$3>VPXKIe+};74-ajo~p-^(y0Tlc|L`J__Jo_IJxX#)a-U)r}{F2eAmP= zrhOpv?711nRjr$bwTr(vJoICejM&nT)7j`oTj~DAKVV9-e~_#tHe93X|3lK7vIFu~ zY#=rO9S{{cMCm8o9boPQv^!|GLDEl6K)2*Hz|lq*x7z+KPpa`7qd#^tl7@j5hR3N! zab{v66|+jI@vX_)93_C4C2gDDf+oLEVW^$!!qz{hCb?7`yZYI?=9TDu6Uyf{UW zIViPib~Tw3V8J_}pIn~^e&23@&-uqL^R_%@37id+Z^fU~=0kBkFZp7$;Hs=$WoKAf zDGrbNIPiBr;lbg1pb%JhUp8^kw6sj2!pCMA15I0*!B(bU)5D&&y@y;^247V)w6X9y9(65%btrGFj_UI)R;Xu_4ODr5|HZtaN>E7bvuWyrXsYZ;Y0Qa zgWi7Fjc1~LC+w5b);UZnu076Qa@;FCY+OvF$x!?o zShjM=lC_Hu%qi?5huu0mUIUe&f2Bw>tPSqRW=_7qac)NFC;$A)pqg;S470!xtz8?A z(5Z5tbcP_3jF7j1zU>E#3Hz{(1LwYz0O_FXy_` zfdU|nZxSuNn?dPDUibzicogRIeb;#lm|}ms+%)(u zf1OA~#k8P>DA1ImXnV8C_);4F`m#lYHKLvS)G!kv2{g`KJZqjhpv(1XMtvLKytGq? z=_ApkU7^(6px4Yj1^q*cYxSA(PtOpsY()bNs!^)&Dgj11mC{-t2(M9U8(k(n(v!KX z1xT$;OI6&S6-ncS|KRg0h_)4qe8TpI(CdYw0&%T-d?aIIdiv~VO>OGk{kLBC8-|Bc z4FxP&IpDZdrIk32Bo*a^A{8n;nwze88Y=6kBW{ccv945ayL|mh-8yisA4gOF$lwIM zEv+Gkb8wqkL){{n-9EisLTX6~=bx z-Z}g2d1cRP5A?W-_S;vjC5Qr>TD9GmrQ9FZi;Z$m#3zIT#n{%&JMH5=vFlOWQ+5ye zZhu(M?9XKP_T%NHUerIfT!L$FDXZyC4^sZ$e5p*ytD4l535wAj=(yL zNNO<7U*b(QjyuHBpCV3|KoA_@64}YKUvN#^GTONv$oo3jK)>US%P!@7A@t%c5z4MZ zN{T}3n*yG;vLMxWL9d9Yw-j2Tz763BMiaXlLH9n-C)g1Oz|5+nTBUP#SoR;}x8>y& z_i0=7c_s0bAVCoCyBliWq_G7u@xV`=9Jma2)lwxqI*}`AiF1OJ(kIp?s(Z3z)DvT} zeWTre)I1`1(qySNDUl|ve;oT09VRtx zC1xL|iKLmFC1$}q1gG)p>QlX4TgZPF?=-OFBYQV^3*=*L5JY}vKV&_mwx>5A{w}*0 zax;#z(^n9&qF$Mz;RBWoKfzhMdm#@oA`PB?vY?PflpS0Hhi22l!O6*YteACTnSW@` z+3J?Nywj9DhZ0htA@)Um1d72NNUbkL=q;HhuM4_WHs@D;9D0Q;z(Im# z$e^~j=4?-*!cKBt5M>pms+G0l=bMhG7T}<)u<2(-!UcRI<#V0BEqicFgS~yFJkeyX zo!hgg&uJB?OzDb#!jyyGglQs`3PJrq`0 z^JazeGapL(skkmHh-6)Yj^wgPaz7^_^voLiKl9`_mbMkAm_%U~_v^blt*Ddn$v(!V z>o%mh|8;Yo@+UD{_ZJG4KqtO`ACW|Q0@88ufA+eg;y>KJsrYxVJ8agM!q{Ap9&I!Yi~J1N^Q z!tqYONustT-MWF;7cbXgxpFb$*k#iohx?+k=M!FXtb6&y+mKtF=&VNlF3V;vtG?Sa zNQ?qIeVp2Wy9@8(A-;ymZ5R_;E#D`mMuGHUX_N@{XvjN`|@cL4s0Rn!_F zCzH%Ss{l*{paHlIPgoNY6!91hI>y9Smq~*L5EUcfHf1&2XKXzjJ)$r9*rgq{Zi{6P ze56;TJW>Kt{Tz5z_+yx8g6($+2jaj-4d~Y)saf)>z;fV?b-FmXSONK)KxU~&j*Q2n zX1dFxT9!!W=;}VB&uO9#I^E{ow+ch3Af34+R9e5RE=^E3OwJBdersv7!s-=Xw?JcG|M z|D0lx&*(&pPY)vzlU&#&d)D@wuI-h`2qLM4`&2<1pI67V7GgiyYbwnH>KR#8)c`$Bjct^!}`PGcp07M#R^LS zUPFx+<|p-E5==B9+4t`$F{3^)7n58d7Uz7LuCTf}J6lvA;0swC2HWctqNa1e$)j4` zqmdEiO_p8zsVx~)O?*39C$bd4nH|)f0F-RbI)ObdIY+UfghH?jHr|^R2~?M^Q%#ry z+avhHnMU%mq6fle5i8C?G_t$Ka!Ef^X{^ubXWyX5AdeE>s}~OAwK1?1tu0jg=>Lh( zI~7fc4i6Z>+>E8IUx!2vm)GlZ;t5E=v=hc z%^C0pfZt#ETC)Kb2o6bX9VMUp)CJ^6Ldj3h7Ak|dvtv1I)Ey?{8-k4)j5v${L{wrI zKioSj8H1#dY2iaKw-zJ=bQs?k07E2o+w*$ zq5O*UFps@-L-c^u7F@pjyfFbyzJ90lz-TL!7N0%rrOcLjJ6lRyDb!+vnH6lsm5U5& zn4KR6un3#s6LwT0IFangEX9y?~CYKi28a|TuRVI=nm)FsAwyVB; zUA$%4e@|Hw+IUGhWqGVqJE2?0gTBkqT+_gp#~~4F)=-mzxeMD1$EfJ@7(Eo%%*)Mc ze|X*>uCJ%zRwnMn@bo54)2jYEJ289q_dP3!%|qWg zv90Nn@5#4Y*%d~_4iiT7*?AVQqg0>R^zbS}*N5AFpM6AVk5-UnxT1NZ&4~Z;Ivww@X@b{rd;*WOwJ;H^-Il3#RHGu#)5DExL z1S|#!0+cbp??3V2!(;=(Vo({iJ}td*14*0ss}M6pd!0r=7#Avmu~Hl8 zj15ejM~LEZJTUzXOG2|v3L!S0*IK^?6{O0wDwU71mecqr93-$!t)TjKdsfpf=veV$ zfWNl>3eXwJ2bMHoEew+-DuH&-HLQ)8fnV9T2Kb|C&2njhcW(kE<5MJ)ek+{T()Q-q zJ-x`Ct7&X8&Tebo<2%ZkTA>n4Y*zM}J3C=?K%^9fVxC=^S=*=3(1QPr*6>We0{ICq z4`QC6t70GGL$w6V2s-202$#^oErZCI_<%`1M&00s`JKk}=x!o^kQvsOZSNKlOV_;^ z$mNQu0-`*XHosb@!{PXf0o+O=9hgr`+dQSa=G6dMSVJmkp4iYk1;N&gVARPz>(QrL zw6$yfPB-X7?7nYhCZnH;TXJ15ty!AE7u?SWzd0d(hpmvntZv@F`fnQKBR`Xo0k7$! z@@w3{)(S46O+}^O!~f7d4sAjM{hb9fIno*bgYu67S!l-+1G``WN}`m4TL2be1}fpQFK)I>lAWD!a>ZiT=}oidv* zAPOJ{ptu03N})7#b~BdOhrAVE(3$;H*6oDX<5=E{2vo*@YQ#~Cp(V)m5>2o zG7p#dVgy)ADde3dwZt?X)D5|Z?&AT-(Y@m=uk)4<{1^{AenV5~m$I>?`Rl(=BPp4d zB_6~GlUKC_2o9D9T&@#n?tqgi)!JoO+;kSH<@H3z1OH4~Irp9R4qvioH22l-Hvdd6 zA2g*FQ6ed`H7EwFtt?5{p%>Ac4L)_~WZ4vEq%RT`cgAc7{AGPhw1|V`F-n@GbpIuo zUN!a0bsl=F$>Qf2)_BpDxQ`mxR{DkYSmT{3mw&}I>pwUsn^vTf2QUi{{fOoCO%)RW zYPVy!z}Nuu3u~xeP8Ev`)n`SGQTky&*Gtl7ZZKx*R<$|Yi8{W~w6YWNW zd4g4%Sc7UIT}Io6c6p4guh<9v%J2GX!;0*v5=x!{$fb;YCrhA#pdlP`Lx%)Yt!9q@ zeCY(ZpoR1)r}we3McWoVzA`dUL5%6rQs@bS=MW zuA^kKzkOJl=J{yZz>Hf)azV%Vfod7F5k%Bb>h%wv@GoVQ9~CZ)mS6JUOPE}PkcPVa z>d)tUtFeXEg0bO<*H`)TWXKxRq)!L<$-I28v?Pr8$PviJNd2>~f_MOtZzFIN=C)BL z?HfgMuclv1L3eIUGyD{+42R+Fg?51t4EqE1 z?@}%Z(mZL>CO@87F}0lJlf{;+vJx+`&mY{~0~|Uw+vDPy@C7Vc=(M zBjqby>F)!kAmBF{3gPFFkFqLZGB{qj@EaIh55r2KuMLUNgP&5Zh9#oWXQ#lENcVxk zq6#6#6b0y+0K`NK#SYrcGp1w&M@xlIS5dDrpxyY)4(;NMYX0BgvEciGw7$UMa5n%> z2!acS#Aih)(S=;bA3VAVN~)`Gih#Ry^=aIX0mFv$l^qv3 z7el%=Y>lgU3>8s-HUwM~)PUgpdPYhzIyt%GI$1yd`5R`qHzF5J>2iy3+SdcP)My>U7bug804#{4DGG z`~+}%#0_Nt!OeueQ8Zir=_!s3hg4+7iX)I3_#?-O70^Ecz2#L4iAi-Cgxx|Z-u(l+ z2j~aMXDX2z)a$K8F=&h(B7w+-xc0Km&5BqYsp5lP9wfEHwEc!)2Bu2vz5S)XZFy7CY;rH7@`5GA1`B24d}#5y8VG*o0HxoiRUu8oEVvV zq=)APDsSq?f3wctU)p#5FGY0u7}5XH5=74eL%h6q+0}o?R>WF6VXsNWdmcA<;*m+< zu!BH|?_sj-~$b26({ z-g{VMRpx`Nx^iL)Khjrqimd* z^`YnI*T%@voiUK;3xJvm|J(vjv_oS|h2-gjF8Nr=)HziM#Zq0-+8dg`z`W_s@iEu{ z^!GmwW?#~Qy4kXQIN{1Xk zK#O-RLxoaukq%f=5Y+g>tlr}{Bx+czmJLZpP;7p(*ZIM%^G3X(L9KjhzvX+ge{Ug| zTiHzY*3r|=$SD8HFg7Z+oQ)dvrwi8okQrldi{?>m96Gem2qjd4@+;wLtDPlr)^Y8T za(>}wMA4MEtvTkhLOJ*mo5yb^=GOE{FI7MOhXIQhSBN9P6j{;_ofuNQxMLFx> z8{b(bqf!xT1+}c%EGlRI=w!)9Y=W@z=u4S$*93^AWsOq?_N*h zy% zBPrA0PXne0!q*I0v(AmkfiS^$Ie7XEr`y+NV&B_E15G0DQpSLcsq~f!#irk_*X`ds z*iuI3(FKU)hpwM(YPgIXPcy!(Q(+a+>J3j%i@(gjwIjpZ2J$j>Xi;Xmk+6 zK$lUgza~P1^r4dXO-Bny)4^W0IMJ6dQHKmIutBe2YC!x7jsSJ!=gsf=(fZ93g}$;; z16-URl6{sDxQg>G)sY$uJYK~&!Y$;GdfUmYqkz~Y-6=f-uvFQ(`(e2zR1k4%Qjn+i zr8F|-hQTQFiynOocN}J22Jq;dbxNg{s*tTR@%PcPct%C@e2>{6vmBNs@_xfq;rF<$ zhXkctG()T9mh?il@>A8+U%Ej_RWm_6m_^T#og2|En!|#%YO7npzLRERcI*9r;L`K%$Y-e;L76#3`G`KRRCa2hIz%~_4LBMK=ga<4oZ|78HR}o2 z{JQi&puXWmeIs%&bOAXio^qFR)Q<6bFC*=%L~rG1siYamZCIWNEV9I%C#&N7 zd0k3p)RRuxv1OUQpRAFM{Rbdbh&12mw5vz||{w)I|D0y{y=*`)O9_jQ@hn#ozua zl2kU}!(jg2EX;lfg2@4Bg}<^CJDL#NVNF7Cj9^>b$z2e!RzNEB3K=KzyhhcY{>H^W zxl!^pXl*iS_{)f?a{NyBX$sh5U^zz7;WJM7TAc?N8XCN z2a544z(GSQI&^VP#~~U0dz%UtO$H%{Gnta<(e7GeJgLCg_2QUX@9=th)-NlT)KVm(=Jz ze(YzVe`#vRaHOD9AZq(<{fIn}^_%zPG(uDn`nmb6^eKb#`g#y)Ka7kDLz@0L8n0I0 zoLEit6I=%M@r%P+J0@~5LQt!3cBPS;GuqLsX2_y7B>?+v5;1Iga1X%mu=1WQ+fQ7PU>{N1-uX54L@GK0B2b1M!GJ0<)?{OXyjJtoB(HGiy z?Pt^{Unp3py-&sbU<3Q=F?tv)eA;;xmRs|xQx|*}O0ZDgT}vf>|J`l&fJ!p3ufmBe z?K&D|(+Cw?Dz0$@g;wLQmdGPL&eH23D|$IFeiFgNC6WAP+o5Z}_uMN!v4s(JMBn+{ zTeL5Pm7hxK%4(G&I?M#MEs1Jll#dj*CN=bGfK6 zJG!)_UF&Gr#970l)NFe6aF68MD1U+sm894bQ`JTslUV;mACeLv(hjF=2HQ{TY9mvR zi%804{zDy!c8H77t5W#P4nf?V6@(fp@vtBbK1n6F`Ra9kJ@-p==YjN4%k=0IflEXv zUlJMV)D$+u?aLcRugIAG1A!$)$Pgh!aaHLqopI>r%Ime*F&GIMD$}l=$}y zSAT-0I4uW?;_;>*1U)Mz!^`sEnH-1NL2`a8JzCEe2RCe<@ZIO6S|_s~N>3{g*&08Y zBa|6_l=A(XzA(&Dwb$9nhdq&GF#ol8rDg@#n4`lw{dmRaoW)OtH2X_}Nl5AB_>jQA zlX?x`_Mb63n2#s;n4EqyY^DT}GQb`?lPT+$Pi%nMGJEgNN3J2GDdi_hrYU}I(p^c~ zKy4W44DYPl;p!|McA(C~1i`=$6Oa;tytRV0k||h}y?_xurY=J>lNac6_WXEo{Txl% zDQq*+q~P$Sh94kVf3}GGpvKmtE#ElX%6V!+*oaZ!Dw80cPp`p!pZ^=R;h z25JCaFBec*4VHJ-+mNePcaD*XX=p2Z9nbZWE=iOjf1Xcm3-O@*G*B4v6`G)R%b`g5 zW#s!!`k7N8hX1tt^oj{~OgB@wDc1(oCC!+O@FTcsIyqR!unzrC((FL8fE=YN-t3-W zuOVA`;5iM%J44jPu_d;f9i1n0sFyX@Ms0JZ-d zti|499>cXP`Vp=~z+$1kKR|I<7+v{u{5Jrsf%&#y*bA9-a>6>R`*t{w}755Qbh9})ijaGs0WIYj&U3| zletX(ktH2DEW(SP6_Ov$|8bKyZKozZiVNpP`xD`&+BeLXH!Alea4M*uZanKZy^x*^ zRuDf81M%$%I+yS%g}WYtsP0Vy`|5gg=Z;VO5&^+JRypV-D_SE$r*~p&AG{{R7kL|I z32Jl9lhyLgX+~69`mO|^N#ll=FYERZDr7!AudGEk<`uzlr~5J9>ztc6&^SuW*2HPm z#_zk{&_PD`lfBI2lV72PtBtxMj#tTut84yjt@gwAWJUZ#QvyzHPv@Q3Ug!M*d2N0P z_^i1W)&ctjU0aK!y~STe|)Z(3Q;QAH<}tlSr$X+;hJK`o@DiG3o!NDU#_|izHj& z)u{BpVu9E9c_43SYYvbtFx`;v*x2KgNme|)AKEHO?N7$9Uw&*%f(!s?!w>ZnGs>R^~p6E)e%2?YZ6@+lVq^`?GNi4F=B~_ixSuX}QpuTzj#ufr5 zwh8*k0B`cLb1Z7WJy@aYX`YZ*o(8T66FMJ+@0AbUd$qKO+O>R^#Exk}lztP0MD=q# z{3Q@iY}zvhdrYpVgsl)nWxP|LX~LxPrp&W)eidjI>AIuHc-5;yLi@y`uCEY}+3dx- z11@*VSm(a)%I(l|7`iRJ`b@dO3zbbEwfgFmV`nG>PIn6a`m3m-4N`ICEqyjZ>pEx7 z=d=gV8z@i;a>m6!Yuem!fc;5y5r;@=Wd9_m(spr%-a4j|utoy==TBYLDS(t7=ge!g zKaTEt^_-gf%|ug8w3o*Rr`MTS1;TozrEGoY4T!w&lAF6^F}+3C122vFf}VH1ULJL* zEui9`b0qEWnO78hG?hniQ zw_*x>L5B$fx=16%&m`UIbq0Lq%jsdX)~?F(3pLcDmb+RjACgsiKJH^Ngu_1V&q|8Y znIrh_an$^hJ1eS)JswjVNS_EM^!)j8km~chaGIR88ji{%V32zMQu>UrFYUf!%0Q4KzNSett(`4@EZa{+a{-KCDtu}?DJ}wW2~!N)UD8|F=scBQ>t5lj%hP# zFvf*_VW1wB(Fil5Mq#3s1ogk%)w}BolTCdSpr_rIUV6CeUh!{ez3vpYKP~tp?0?$I ztL1uNf3tddytI15Q))hwla+1EJyf{rRv!4HyifjJp_4V5qEs58R&urb?sdy^LP=EyMx*O4!q4|z zB3#xPiS0J>3E3JpQuIH0iw~I{9$IkMiYZ+Ug1s9O^9!5{{N;vQrhk3r#1DG=nY?Mv zIDVf0oj3?I!-X`sMq*IWudev|hJ}Un&zNhv9Wu*90-5#B1(bv7HZxYTPC01=w{fl6 zwtX?}&X*V(85B{6@EMOxsaL+dvsW3MB8Ec1I7Un9SC!|OQvvhh9J2|sCwir~$C1;0^0cpIIjuLiXqH0ut-LWY7B-+ObkB9tK#ld zkruN5Q-^hKu`Q8(l=faiL5u@3n(R}seT^;GZVeWD$Ek`f|1(c%uawct|N|gAA&Fy>L z#1$1xQS04`#95P1=tcbB_xpVIRdU6-X2*z)ENMoMM$Kk@BLZq z6<_D$8GS{;(;ro6_<{RJ{b#5WqMS^spy9bkhW@@x%CXuv!n)<+zVJQl)o!+otJgPown0GL zUbyhQ;B|XawkM!DBivWokD(ghW0z@DY6+ArR2g347nDo@)l)Zuc@~`&EV>KD{nSb} z)Kb~LcSJ~Fabpw8$2WdK!-M4HlbS}$2nI(23C9n{55{;KMt^0E_YRqu2%qH*GU9|)A~jNW4pw9BRRsC~Pa$YZ$2>(=OF$UWwD=-&R2Bsg}h#3HFJ zZ-Eq5R*9}IJE#Nq=72=&%bCY4I^hA~)Hd?sw%OUT#0Dt`5!l zK7_4g=%I{u-v?1My(6FkZ;n)KxaQR5`ZgH{{UI~#bL^6izcOI(%vD)DX3GjZzN`vS zw=u78UnH2!w&SjrUDg|+&Z2{)27SGnoubb3I5md&jq|Ox+;cu8f8(aJ2pCFY{~ov_ zOW@QqOyFG8oa%L2*WGq;xNM^2f7RNgY5%MHgz4dURt4hz;FssQ&ymM}uIpWJc{~4Z z-KAoco#LH?A;ht%Jh*4F{yu)=m%z=ODu~6VA;8Mm>g}`Vr=7Pe+|5B2OFx0xT%COx zmldit4i{=xD^N!v$JN*K(cmRi_dNap=Ph*v!s{}ci~{7^H@+g_e{+k?5YlhxaFz@Z z1Sjmtn&Iw#aL6PLlmue?8XV?+E!5~O)fQEY9^V^sQw(E}G@(!_UAyrJQVJmOsUIV* z7R>mZ^u=`~c0mD(y&zQRMVxA zi+!m`dvl(%f`7D{gw?2!6awgw4Tx(SiTF+ge-EEDPWy&T{hex9%lW~*dA-=!A@x!> zcGHb_U7e`;s;YSu|4SUQM(hbY)7hUm@Y)B*mb1u=TkmX;77TC&@mFMMb=%Gc3`7PP6PW2HIo)*G5} z$Jc+Zd6O73xYFSzw}9ygARMbYtgh5m&JkR3iXS%d9VhE@E#wGY9(OolNz~Gp*+(;UX&rX_yKstSuxEm|(lZ%U0Aqs3u0c zDkpZlvRpy_>*{;g+hpUgRyZK|y-L1!8M5XeIu_U0G~*bY-m;wFTP;MV*|iob6(W0k z+U7PYnz*w1d|dlu&l$4#v5gw8XvVYN`Kub!*06_P%?5#vh_fBiLAuI;2h5WSD958| zKg^SP{jc?#I?0pJ2u8}ZQfpi7T0<)@gn7L)%QhOA$i=p))~_;Y9RmZHp&uNEQ;(Lb zgVkKk@%zheN(GOOw(-+XQ*Ra&pWj{S=(MqP8u(}j?vpc@1 zD~tFZ)VOfiZLmP2L1yZ0CgGrR9`|WiHP2Hca`IU-W4$5L!oIaIc|WV2E)-)*U$TDZ z=mHgYkx|r<9|MVp7kFs&vcJEd!IX7iX0!1~`u?JDbNGy2@JA8J_QvZ(k=sDZVFD$O zldtA&C+5%HqZ)h8C5`vDw}wiA(#yz5aIeV?CUh|zu!ngu5X?OKd!uR&Sh)CxCVKE~ zM!6vZH!nyEiwH@VdTd^9yZd^!H}>0@>^`dPdTD^rx@VT*2;kx#5)i+(YLO9`f`P<7 z)5+vpSzrZ!FEPO$T6YnR7wj3<$*RlGtqmQeDlWh+({PE;F2dL7mjd)*L>&IV*xmNb)8Es#0j)v}AE;s+%~$^YS|BhFhd257M2! zwMgfb&8|}~x!F&^9VRgkJwDgJTe*-PMnfCh5gv@fpg#R|mHc`m0ZZb&K~ytiA}wQO z>|&C0G{HN~u2uii>y~iuqK1X;KK1TLE_2GC`1F>8QC#9HI+0!D(l3+UA6bqL;Bln! z5?Pk`zG%hLD7uXX{#2?iDnpGXw$#*vss**AaAr5;@GmwLt$6p@>l)V`y3`!Q)6lt^ zCH1j=BGo3C=xA#<{Z3sigVS}<_Yx>n95iI3l=%CwSj~=*-SCGMN+@L@Kz86W9!xAk zx#b1ig5gs?FJI6-i%M7f;xo8{Uy?7~GuMQ~B1# zi^D*t{sE{K5H`x`st~6VAc=(j8qZw3P&hs3v>%jQsQ(jP0!dINoMeJovSAepWBgs+ z5wGGWkQkVGu8BKHS#tPJQg$BXHWBh$Z7}e5+ac@FA_g2(*;zUMh+8%|dC_q(zDKk( z>?h!PtFBh7bk@6?!iL0TYnnB(in4G;+u^SwRU&O&urza^wma=Sw(DF)alj}wYL(R+ zIC=Z|`^ic@QkyvIJ2`YNWX?#Q0}RqPSMqfM&%T}`a<(N3+#B7+ewR!7lXv&?f*At| zFvECe?=_;XqPXUkCgPTB+`ArkDV>U3!+d773hN~TP13?2NZqVBLfFlJe5Ac1AsC9e zL?SmrG|pmggB&j^P|Z*$q8!Qk%tLI(vm+<8#E?WB=}&a-2=|(zh{QLXzhPs64XX|w zX|K+|jG2^6RBe%*m&nkcrXlWsXR9~ikZZY%6V}>YliP1ew#PZ6t3}r-ct}Eoy;YRe7iBfvgNo--6#+RCabrUN5lCGrZOlw@5J0^l<-)Rx&Ygg&_&R zX@N^^;LO4yU<0Pe@#c8-BH<*|$YO8}-}+q!ZY7>dj9MsKiYZ7OJHRMFL{5AX0H z{_LVm{HNt*S`o9u;tfE0DNO>Y@dYKptKdo2R;;oo3{sL*AWh>dBZ>Ns;O8N4LjzjE zHz7a8W+%{e-d@4JZ$qC`HA{V_apW9V7B;oD?>)P z_u@zlTI37ys`CE&t4MT9sw6*#;0KY`(r#~;R_(Oq3bDAq#zk<bHGK)fg}Gd^49 z2}^_{=@aQ;dz6v~`D~@p&7j6F;tR1cThtPi+iq$~cFe_lECzCpc~x@o`V||?aZbus z?s^?^D=Jbz0QOd}%zrAw*RE3tD2D&>u0=7lSUmIQkRMZGTdRocVfgLk&j(b$h%T8E zI>|gx7FJg8h4gjq)L9);%!efeB)NZ^VL7UEa;J+hnEeJHuDD*4mxIK4X2YA6`CWlS}ews zvZqPROkaUGXjq;ssq4e<^%(lV}w97&NEHpQ#jf|;Dt>s|ApSZfYE`F zYnip0&JOIj?*aL0-EU=UABMaLJ}KWsodjIoOG^TwXCLlKp3#Mg0%d8&d&dm2)LsRQ z-WZ?DE48$(nyRuNGO^OgSROpk^<&|tFWB6?y5m$=CRh?N@4KDSXnKABP$OS`%_#`u z)pl}NThfl^&Y<`n%9$M>GK9t^{bqo}t_J`*x3G>30R$N7{!d#Jz>iy2?{7!{=oy_;6xFS;6nGzXJS7h|7`}vLmGr*CtP z0g_V6QT|P)&D742mG>rjj?4wrJ}#C>dN_^Z^)S5*wZy zwGxIF>*8B8g8_H#u93PI%V3cZoQcJ*>3>nR?ic>9kL{p_-ng|wqDfw`p=t(`*G;~u z?LcQ(oqSJHQU6S;K_i{%i5W$V&j6x!+!n09MlARfE_UeZS*Y3Z2(Pfged9a9mt#}Q zP;K@MEm6s6LUW(o=aNU^j<&2;snzV(8RIEj&&FV_piW_}8f|0H7M5x+f)8AI9Q9w5pH$LZ86rC+pP>ASuRHSN^L1XOz#-(KKGt8Z!3p3@MD$iiprOLyn=5; zV{^T_-X42ma$#FqD5R{`mvg2QCk$X3yhlz65u8K`I+bxjCj6&F21GCNyAoVfJ5(Y6 z?a1)ny`3fvF8U~S%C*()`L73|{1W~hVj)5|NE}dBx%qMHP~8Y^lZG5IQ!PnRkB0TD z#GRdE`97NZ5K3Q;MH}-^WZN z6%!K*7=W0te7<*z>E+UJ)R}jzfC4m%zN@!3BR~Q*bNj0590|?b) zv8`R?yb2X|0*ev6r6^oDXB5P2g6Sp_1J6b8CF(PHH&5YyP6{~F+bC!)R1k^X?t+bQvC98jn5rC6N}qB z-L6VYDrkS?*R=8Nd`y2fcs;KApwtt3^Lt!A|-i z{GubeF-oo1ieg2f^Q(@oU1+L_)seLl7ip|LM*g?>03zqp{k;*9k&&)|pc|ncL+_8; z5R$y|_V@qnw7*?50OrMCuo(Llnfn{WIa~8w1Wp?jEO0*i^N?3I{eN>J=qQ{vRun@UFD+VRb;GW`Bi)vb&|Ln6+aR! zSW%u7AvAjLM7!`53+2_k>)|UU8C96ivsmONiQ~a36p^w}-TXmEmaV}o;0L$Wt79DJ zg^t1dZAbb>EVTmAYCx=&Pt-fd1>f;KtkrrqBw|OC2AQE!iova^9a(39y*$? z7}{=CDxQ21Im)B)x2LT(P8IfkGt;h)Pa3Z6z9XS$`^- zq|u0>2sBNwd(3x96*$fNjfAn>e(~M6ad!KiVH0mh8;dvj1!Y@rxPJkVl#pmoOFO99 zJcG_^lG_J)oQaRv5l!Zpfa@Bg8h^2>4Unumk4%3$OkKR0G_wk$~Um+s>e@ z8yf%d0+1Sqech0{N#c|Xl#*xCDLXr(6EP}z)Dfn8E2PpTUnqIzuJx!nD;b>^bw&?M zbE%|RjE~@O#-bY^h*2JQ&n@70)^us}y?m%(abO1|KoUGvnPLnj5fTwK`?XRtzC$R? z`kx1{ZHEyokiH1Z|4MYjVjM-C9n#tlt4n3c7AU!2j={c<7%sg6BJYRiHbi^P@v+N- zIAXqZe6~TfSWkOB(2FB$ovc@K6k9h*7*=Wi?_6)Nj-we;6PUv|Ids=x5-6+K!GEUz=&6p7BK{dG7Ws)Qg^ppj>hiLGv02dAd7Vw+md*2&n+7iH- zN9NjT=hkOiy}h?eKRVAa^BXM`$T77Qw&Y_e68aB>!B>d2QsD8-Kc_(@Of$7PYgd z=HsL9wp8%M2u17%B6G|5U6nWbdkbOVvw?00{m%hA;XeIo!6v*6sZyy}nq*Y7nf!&% zPALsp{)Tl0Tmpwlxp#3+Mx6kFx_}O3@0TZ6BJ{rOW;{Wd_o`a>qX4 zEJE%o=0j3*aI-cTM?(zgK;+IE|Wi2SvjlCahC4ZDr<8_eAWXx{wut?&$!IW$M9VZOL z$Xukva8NL~Ah>^mw+AX0w6!Ho{c79x&#Cn{8c4Js(EdHcbYlQvz(HUMAa?XX2fN2) zn}FQX5d$u@%9j&ZvTB5&vDA%5FPVPangY2eqqk2`=d&Pp1AYvhf91_!FlwkASI$Yf zJZYKAi_+p;Abj{ED=@w{NKO~6{$a0G*W_Dh!XHLVJW!BHz_w=;-{WUg?#K0!EUY6UjjJ4ikt@a^+v)l;k+#}UXC&R_1iJK%G7 z$P)5xI#pSkkRCC(D;ekl9y=`VsWiZTm*enZP2)~KfVVKfZub*z50w761A@k^?I zeGE+OegEiM(42|m^IguUp>wsP)we~#rfgdjW}_v>`~v74p#X;$1cxhU0=xgeOB@R> zl>_151$ovlZSaJ1Ywc6}fCYRt7YPHcV1a*p#vdd4 zBH`5;}rA+PT=2L~ci1CbBTX|sq%QPdJ*qiYqeo9I0Y--rtwyP- z@qDP>P(_3g^Gp05z$rsIqph6Y{NWjfL0+qF%JgaOm@6TNegQGftWgup&0)k8EqyQC zALIV4C#w4F+Uy@Wbg)pRIc({1non&kwd!G%2`K$)EB2&ZG-pZ#gnw!+iyfyr)BbV% zr3Yq2Gx4i@^^d!F^>4i2h(_9VJKl5zyBKppuzz785dT?QC2BxlX~0|2N~&_}$nSm> zncMWf#a1>!3b7sw4|Ky??g(mH_rEc9$Us;Ja}pZt4}Ns2rIi9%-a}dWtQXfI?^mpt zkHnx%?0x+R#U~4f1$BkNed}W0O{Z)}&gRp7gTv@-HOc5gf78!3=ruGahw8*izli$97X`3(G{g zw5DlQ1mmdWY#okEPw2CYkr|d;U+ExhsXL>$l!~gr3N=M6(*OBz>DWqEW`i0wn^7(0 zecC)~>21=Ng8NdRe;GRwuLd6Vbdx3+CVaZtL_TWR(sevQDMeiX4%@tKWv?_9YktKy z2v{1qCfV#T;wdX9HDo(|t(1%(`K?a4Hn2py-%DQGs13M^oI3?(|c;@$gT~WBR8SFy9T`9vb8y8|8^EItXbD9l_e3DGL!lmhFFOuwAc1YQ_Ag5Gw+~foe(j!2vOF+Vv5w zVl9za?~#C57%^}q@MZ%fzV12n0!V1&dtlc=#L@P=P%J6&00U{XS#@hT@~QJ-S0><+ zy0B}&J%O2w$$JSAvm)s~m{^bfah+J0kcKf*`!-nxZ+a`5E%@BN5@KY3d{qIk@QI^u zXMABN?j^m3KW=17P;36VL|#%V4cd2I=uJj;@65J@Y!H%K0{bXaU}~McADQ;KESbx? z16WFph|stt#CZTrvUWcRP`JJ<$#5Zidhb3D6CvVkCguGDw zCxaE^Q}r9*A8T)3xgk*`0m7OwI})$ndMMxP?M>Q(^Mgk}A=)FWBOc|(4B|%lha#Q> z+#S?T;D>$qFQ4osadl&u$4T+*#*tY&n=IPcWD<)cTyMHKOUljY*cpSRib<( zzjUx+4K9wE2A_$nJ|2jz67*ya-r6``hd`47Bgc}y-4^O=fmjkxbgnMn^f&+#y;*j7tTRig;6$X!fzNAa7b0!&a4rc=t z5s?$Da;Qeu66+(|L&ayA6QO(I6!_H5^)bYdgYf`ZT=6);rw%AafcSzA15erycyvqE zJ%}IMX*Vgd*rq-`J#DBTt_Ks?2;nqB&T)^yLPRfA+MlIqKc~pq}E`scFk}xVp4z@!i^LRWqZJ zPGFjAr1AE_QMSWa995Atag9kq<4K^x87S86?>Kc@!;i%D>$Ek~BxYLlsVZa5r-?D} zpggFvI+>m+3;Wb0N=TpR4N+n-Zhc((O2asaN`^GOZm?02VDB780HS;xleMk1qcEvD zI#zUCIS-}8TnJ4*&u;T#ZL};-0IXUO z)vY=a&v+^y6-LQwvN!w(@~c^FCb!EuqlRZO&!29!3Y$6Z*?z7rfUigWnP>-KKOW_U7Jev%yW7<# z_qcHxIr2LF_DGV%TZ9V<@+ih|K|jAiNZ0=$6@UQ8Mu6 z(mmedFE8QFsN3_YMWYFr5iH@bY4L?N2=Mjp3%B_<#1)rQxUCqe z9jWR@0LJCu>{qdbhbyW*#j!WWx3Xv1tAo8aIzzG?rl~otu!L6$f9_w(iu7I2W-Q%4 zF^ibk)^y1!=^w(6@iG|aU-kA_RKg?b&8C+om(NY!04q}SP|7emefJ)^b+B%Hf1=K2 zP>2TKdN9|q;`*PPH|Ye@%iCDh_s9cDOSx=-%3Q_q51jS@BM5O zS;cP=Np2Zy_klBgPQmEKB-;$QSi>(3eRit&cYyPNRkY@}t#PE@rHyh|vqr>N_nYtw z_xY&;@k8X>5z!w7vVQDd@#+jlrXITXbq&lTVUgcRSZ8U?yvzfmz;8R+$g6L9IXh#{ z7t`lO6=jV6w`=PAc`c1IU35RwmKzk?-Zp$%NlD=Up+Ra9pQgwM4f|IQ5Lg$;$P#yhILC5jH{7~{k{vXbqQhs}s*#Af~UV$mORQ*2MMz~ALN zN6k?#j5c@@xVAlhxNRtxphVd0yz;Dl4O;XV0rWIenLSI@McXPPwB=GV;de)a8i7t^ux=eWs=qMIo;1oFL+N{CcC?yW(E&h#(>*g?*MkC%j^tPjztMbc$Z@s@6 z`AGyQkhvdCcktbv6LSW})59qx1R8tZ`@ zfjV}sIPdz(sett$uCZ95j3I}2srs6-^-hsOqc&Kqw!D2yxXsQuXIOX(^mLT>l_E^8 zrbZns**j=x{l~8CSxP7>_*>UMuQfKP+rC`w|1C}#`mZ=;?Cr^PNFauR@W<0ag|5Yy zj5)VM8ZBbvHaG|aHV#}YDsnk{Q1-%gYX(bRtaqU0UprXQ!VX4$u2;>Qbb9L}5gF?@ z0#s0K)g{{n#By*OSbM6J z!FktnkgCzKy(k!z>Fv9#=_`|@N{?NsHl3=h zXFnd|0u%G@-RiiK<4(i7u=^1Gkv^ON-+xo-6uEn_YV2WUU; z^C0}~5Oy*63vH8#84;79#Jc$TMROR{(YVsR#oi@cA-}RhP71SZQ4vKDzO>*)DJPo^ zf>ytdvmrr^+2sKBG8FO4UKG&?slvVE&Y!v*_O^4Ly0Xfdres4`+gZcZN+n(2MIzH^ z8{RwkXa`O^Je*Y$Jc4IxQ$n^`h|nt4=#{5XeF@%2xU44SeHRJ7?w#D^O36THOAc0Y zk`8GQc}St0VcTrug+|N+rG`!db)U{kW!1vm9*(y57wL!@5f`D&VNl%UjiG^oLCNyv z__qTmKIff<eN6B6P!Gm<|C;xS}?m?85+RIOeolgy;uH&6efrW4bfg#jz5_UH7igP_Blx)AZ=WE>sg& zT%txys-#5j`mJ;EcO5*tV?4Hxk*(W`{AMj)>=q4Icm=<;M3s1@pQk+H%guQIA7-e{bu^;2F(A&U>k*5iMR|+945Z1n+6xetl6Jx zO6(yN+2;}spolQpC2b`&Xa?JPguDl%e1Ea}Dhf?p)c>6X;aS9DAMj9XRxTpm;Q>Dx zYvEs#fbf(?wh23evYf)|lN%iW=+_v|%2+>B3y(>`LlgX0j2Z>0i#oW!mGu7A5z4^g zlLZN4_Hapt%)b%N);yumTEFv%Eg5HFd0J{+QTm!uHt8((lM%};PHdR6`(j#Y~gl2BRv z@g!?*EgJr4!Fh;i3z7uXV9qL-%X)L(_BX${CuckJ4rXGe7D%I^S?JNL>nkeRE?ddA z&FYi%VLDCw-r+{4BLSc{eeJ)Wt(Vsm>}E!GSEr`?eZQPlVDkpuU%ur3C};0S9mK;W zi*eZ4;_11yn#hjv(#d%nCO?;D4a2QRb41)=IE{=+=r6!iv?EF-d0TX%Ofa?TROE_f z<@3F;%()!S8~^V(3{i6fp@l(T09inszfG793-tKA&5vl8Gi|}>+mPM2FtrTb|iyEl)Eu-G#%lLQir#-?ZSJ3OT=SWSND#0d35_SS*RuIz^i ztmmyXHzYPE5*=aD+Lcs~oTqrkkl5*9ofJ9@lDcRvK1%jO@ecN&R%p+>Uii72UiuJK z#h(lySO{w9r=f3$GvKz>s7AadO4&xE9PivTwEr2kXzoo7DzmpWmTBvXalR1v< zVqGnKHi-KSkErEOGf0oO+?W^=z2RMFP%Zw$Br}^D;lw9{Q+Ff??fZ!I6qmQ|%P-1k zUl6i=`sT$H;>v$!0|3ASHc)6g9`NrEzaoH}Cp3Jnx15*!%NrCIIFy*<9$bb)!J>M% zG<=GRg+x%Mwz$}`b9o8t9+gNm0ZC>V`~{7fg)%Lg()UTF^qR;@n z9{H0Yhy?$9>*f#=ff7nlDjLpifaupjv|tli(evLCR=5}W+z*{2c5%thP3Br)*!$~@ivB$ zRJmAL+~aFN4!uT}^MpdO@G!e5AJ*Ah-%d)Rqt(`q}U4*Uv)`itLTs| zJ1ZPUh+>Lo4y+*>_eCH1OHo&p8u3Y?=Uf4}i||JB;;bL3N{pRcfgJ*WPQ)+@g;BJB zxR@lN?L;|V$HcUiR5{U7c04~HR9*lH6fARnRj_7iw@PQF3cW>9NjKgWbT!&760t$M7kS1EpWl^ygBOQ_>bTM8anzPOdwjAA@kpVGX@AfCXNALc1mcj@;jN# zzMAE^%p9m7PRC`!&TCM?5=W1`Z!L?M?S3Wv@F#79F zuq)a1$Y=Y^zWZLFEs$XOxZTIT-RO)WW>*3{<{hg#?@1O5YDp7hsFeu3&0xE@#0FjTkum=gP>5S@NEO|Bfg) z*BhI_d=TS~15x9A8OXRh;4?LWKf93r$n;;{6(Z@w4*E6V0!tW1?|HSXc=>dpdp^dbdydSs z2o>%Kpr1=*8Cbj|!@AL8w9t!Jlnf^y4;C8Mp(bIN;t29EnL`gKO3WmYAZ)rmVR(NN zTRKZS9xH8-EPVahhFK!*ecuUtRHz8|PH0<-yBKXh+FgEqUhnCQ?1cGL%(%xaIE9DS zU?!a4>#`VRM;1Htem+g#N00*mnitH}`1Rs7vSJ2A#JVq1mdSOUuPql^u;3h~c4XbO zn5pf)5@?oDQT%3E*8U7l&^=MVer$8|{B-u(5^3wM>__nRm6F5GLEFdXuSB*M0qRu~ z((3+)x$}Ql0KJWv{-RXHeY!7Q)+wVxHw}X!LYN0t08^{UASvYEECOrN6o$Gk{pXu^ z)-#qT$5IfP;Fua|*xlIGJO+k__#OK}@BWx>;$`?cSl!4$B5Ij>I#)+=^a#24%fY47 zg6_y{UM}z!jURo^w_RAu(LCuBMNEGVj$ahWpY2f)wxNJ+6hWEKQ7x%dnX*?tFub*QwJkzN|la5XnR-$1-m*()AqzR9V=qwbP zYOrQ)Xkb>fvlu$9OQUm~qATXy2O~Jf>&GaDSD#U0S^kciOW*u4PwFaEas~cFcRNr+ z>tez7P{&=QFsnRgY%~|u`>p|`7);UfI+RRzP|y*J395vJL_U34n?TtdROAw)yhUV! z9ufV5p-pMa@>Q5p`7PV&P$lD##r8!VdqH#F>X!yJ_VX82P3{-O2hqCz~C=r{sCky!{c3 z2cux&(1YTLp;u1VzsybyPE}KObd5&62qn_q6Hnk=8KY?jPccKQt&p5~-#rJ6)-aW2x& z$k6)*p5WIn`Gfq3;0{PZ`w;>Jq?#f_5k>qfM-PqcwleEha~}Src()QRCxj2=0hNst zd#ZPe#a#X_)j1Du#*u;yjmiMJ%+Tsu?&D?CES8h)59no_YHZWWlGUI?MKdTw8x*ZK zrH-Leegan~9B!Ym;_gfND~pDO(Hb&8032==?XUCwPlLb$b-^=o#iNFhVX_~>#xyyO zFyRAXLG@&%<;h=V#Ugz4N*PQtSfo1#*4i>yf|`6FNLJt8oy)d&!o4@s+Z)T`%467Z zNHveIpD!wlWM_+EcK|MRXFh2XG?e&Pk$sU{MDzVYBRjSlmH1+1FY9}&tB$xJgI=uP z)?H~>*wAWM>9P%&IP^T;5YaoEw0RZhe1rrQL<4A!T3vQrC zGM3*wG0`0d4<)!oAfY>%G=w~J@uq`JRj;6r?4d7exPA(F&ic)Y(oNIZ!BLGmb7@mw z+@l*~Pway-y@VFpY?q8%EOKn&6#4gpB@A5g@InV3kO+R(f0iZCLZFVl3A#6}4UW>s zcn2(GWe?8Gayo|tpq|mBdZXLCK3j}!sVCF3GmQrp;j997Ah*tV97`7VvKf+ZxFR|^ zp61=LpWNnAvsBSkI(yg5A81w(JpAn3zmyer8kJ%l>jRJ$}=7p9sBgL6MOpNKrxlZv2963l%Vc@KWJ zN3c92m(@2@NQ|^13TIH&!t)dbqkuCr=enTq;``{jibT~&x^kWFPVT9_pK~wD_8R_! zkf$@Q2u#ecUoqOa`I6R!t2l7oF~cGa(<0~&rF+MC7Q78yPDcz)Tt*=Rx>O{1;iYep zKcH(ud4z{hi}lYSd%)Z|5pvYSJvr=sZ2-yg$;(ghObAsQp80FLgCZwkmJs%bmle48wpRe%Qpju7Rx z6>KvGS_A4{2bR_$F%KbO2ANNiwCj=Y@8qbssD|k^v!zvW4ae!b%tb=P`HkLn4kJiH ze5!rpm;BawgwQNV1=}1Zhv*#0HxP2+|9ypQVflLe^?uhylNe>!vzk!E4`4XWT5VRm7l8a64H zLjWBtPQt5L;N!E3XJ$n+D|cNc^YVZ-&3ioPV1qOVX!I!$Zb3x_ee98uI#S&Nrzcvd z1JYV9S>^o^9*bfO*2GY^{Uh~s2nc?QAqnIM;t!(*6<5WJE~Bdf1%R?#@MWX0W~4$1 zoLtptc4j)KDV_VvYt$EXQ*%Jr(!Eaa;{|c#BkVC@JbJc5y*E1g))PMOP`)K_;)i6& zZnTH(uL{jjvY976+Jqd$$P@XFfrMJKKNXy+ub>faa~U_qb%H-I(|ca4d7Ja+TTfUyR#kpZxkEg#?NeD1%6`>n>We@cQb;Oz!R<`X z`CFr`a?`xQuV~xt>wGi;$R><`t_k5k*W{8Bfb}oGlTPZu)jPPANuWFSo=lYQ$d)Oz zz$0k9`RG*u)cO)X1Bs4(Ad_j)Zw;FWo3zY=GGN;zQT`~1Zm(hRCV6n3SQlnd5{%9N zNAS=Ukf$@6QYNDNn8Z1lrrz^#jqp-fHaeft zDeUo3&PUW{c*84$X>h z&kHR9i;2ez3QLaS==C`4^n}G@IUI-UJ@*atFoZ5r#x{Y_MYpZzw9eCdx-Ea82}U=Q z=PP}d&A)t=<&^OL>%GVTZu-gouM49fq??~iWMvol*>_>!4O5tTsmvpLe+d5w#JYmj z+10*!x*Z9D-2voA%HWR-PwgtoF;7+qhUi~#9s&?qzA{$o<&f@X*1C_BywP3#WX}FB zdaT7pfuOQ3oTT0R4)&`_AS*DXIEXxIxf3t(TZ4(lVSDN>(+-Aj%FePO*;^nVM+a)g zKzo>k-(@}V7W~yHwqb$SM-0giW5$zvUwGIcV*vRo~At3?#vU^MtMD01Lg0!*h z$4&B3RilP+Q;C8f-#U5|@lFnGG$7+S*~9FW-|!p#n>Ne=4Nr+OnplYDZWu-6-e>XG z*s-FY=@<6F(Ks5wFyO#;)fYhxtmI!mY0&!V`>{}zMKwisZz!r`D+@(4ab%uxVc3JI zAD?X>cph|GF3^@mdCT_tJJ8qeh6MOcC?SI?18i$_BQFzMo9*a_r;~`kuI#Uy2oRd- z5otm_5x#|<141(q@o!1!j%~`NclHk&I97ZS*T`V8uCZNdS<@JAS^7AoXO`^#oOqKo z13tK}T5QpQ_nN8awK;3dYP3D`e!9K4uKzIl-VNWd1M#1B!xRf*3I1QqFb*T2P0US# z77MK#q=JA>Wsn+z`1> zxIasEYhX^dp+bpvJX-fET+*M1*6eG$vWT$@P)5OjI7TSRxwqds8?ASfog@vCiIq!g zs;&;_lJ*g8MuQy@562j;DzC^G>c3ar@FCscW7&%6(IkJ>EqBW-4&qq8!b+L^ei_i5 z@@1*$By)Q7fPtG#o1nuyfz2@wO9Dqx{syvC$Y^RDIEV&ISUbgi-E#_SLO%OQlkvDj zwb|$TD~)fMYGF9Y%U%tX21zJ{f!5%;^>aP9NQyg2E^C_1DR8hbShW1y17=Hhle*Tc zgqbvz68`uBnub{E-+RLS0`N_l;K96MEakWmIgV z9Z8{T|L!4_03R}fvy~7ChA6|`Fu`E` zn2{g)o8kg}d)Ix+PE<*j$Thygz6SUYo_UqKH@jIcrnhv-Puk*ciDjH?I=EIn!agN^ z<(~|ma&x*Xs#fo?z%uA>oF4Db%j?J@=LKHs+Zypg0R%PQgnHA6L4rE#qNvzm#gq|a z+`=j}k?UmUzISaZ+!W4nl6ny8Gi=}%A^y2oblgZ6bdXA5JevPyx6m|)Yo(hmD!Lxx zoBlOiYT>f15G@(plb4`E7iCHQK0Ali=S*RxQVLpV5Hp)hF^HObIrZ^lvIy(IT!}Gt?DvM(}?FXa`<);=@BStWp`?1w&q5rUPFO@{cRJ*x@gLW%=d7q{%iD>xb4tb znVOxSEq{Dz&RJeMQcR|_(&f*Cl|de|K78SNpeZow9&MxH=U_u5$!Zwm*e>}lZr})N zO92Jl*i=*Cl%Iir`|h$LZt!}BU+v_jd@1;7`RZ5-(G=6~kaUG9fFikm%35r5m90|0 z-DyU03!r`tbz^3m_OrSv8S!kL0SBwnFgDPnS8{}95Xu9D>Y6y5;yf*G-u2q>-c}?G%3?6llo!k~+6kh_3e$U(-H0$Q^LzzEO#2U@8NEwBLhSo%0m?37Cnjnc6#Rd6o%Ipi{72saE!2D~bpu zDUm_$3?mo<7kvOEF}Kmc$fkEH^@g<}QjFFAk{QF7i#zQH5<@C~J?I~LNVr;5`ER@Z zqk-%ldY}}!Wm4E8VH{U{{t}wq!tf7ab7UL|*aS-$hzPLg^?>SxS;z&53giM=0tw~Y z-C^y0k!lM}C#|mUD7kMADO2Tk`f&51K9-><^^0Onwft-q=u~6n-{A(?>m`VyqH8K71R)#a+2-a9X9(0aw95EhlXrj%Lxc4MOZyD= zV&k}2bx>c%J?%%9wy&v7V!ZDQ96Qf3J@K2|PAc3!uW*E7-hGoBN2W~A#GLsjI_2LZ zs)1N93u=Z#{`~!+n+gC0;Ld~X$0375q+KLi=Cw{C0z!>?zWGRod3=x3BE{?FKZ>Rl z%|5)R>Xk`YC_^dub6YQkb08XQn0SKMM6M5b2i%|?*!X$x)m!@VqVoj0!&P3M@*cG5 zg{`adkuO)MkI_`m8=O7wqCMkQzB=erwbd?9dITAJT*+iKjcU8hufU(RQy29UU!g{j zrxd*f$0k$NYGN&_qvoFdJlZ_-5EmZwl-=v&4y(B+VZ=GcO&Fu&whK^e=&Caa&?#v? zM=D}k`7MK7CCMTy6sR0v5c^0nkVB+uL1~>dJ@vU(+9HUK4Qm_6Rh&=wTDba$cov7P zlL*X?b+~siALbvk1g5>2w~aW(cyfAXbJC0FLq}-;V@W|XTBMh@$ysVA5u6vvm3Ba( zJ`GGSAxb`5l8TS`P}XdB4jwHU{c{xhvie(}yyK*Ij^pVaIg9k0f*ML7F?6ie>2ISb zBIDLhZ6WvAE3?zqMhVP-2ZsU2vo91aJTfwli(hSS0ik5kOWQ*vO)wbS_dJ*n4orVL zs(8o=3G zGY(oOsHI&^fz|8dia3wo8=0)&{yDqsjTMZUIB}fcaV|yZMeMKd$n^Si{o*!2S%)tU z`r&V8&#idGji&OL=3UCS5N3f5Pf@>CGbCXUw0%Q`NU@=^xa4%TT-iytFrLHVrEb*) zixG@iZAU8`ENruGf9$WpreKK!o8c(l_F4hO_aSS}c&uGk>rPeXY9JnC8_wU$hi{gGlf+0%y=m$s4v3P?@nj6_502Z>d7yC&-ABu+ zIB9NLQ|b;yN~3Pns$_k%zbGt7@4_%fQ3ca3Z<*&&uOsq%MUOQIyIPE&#@Tm9r!)_{_s~keJ{Eyg(Me7z08W-=`^(`L3tuyK+v^G(p$jxN_h1^f)Nhhi*w30 zX-ynQW~&fm`f*NK)xqy$|BT}*K2S&;*NpHhmjI!x231ax-%EiG)Li%y$4Dnvt@;_Y zCQ-Pg$5Ls1)o?muk0)^6Ga`}`79Mg&T10WUYQ+r{9!{~J195}suUq*f58SjH$0Ni8 z(c3`H_QR4Ry1m^IZUHY|+=3F8@_AK*)Li5{vXTJg@tEI$77|`0_kD2gWh4?EA)ksi z73Gf&T(XQ>|@Vo+Ga%1D`)&{Z}{+0Sr+70Ss6UMSK31 zvd!PZD2h7g_nDIvkJz&!-dsqCdgx&$ zs?+cX&q0EMn%tt@IHplaYX7vBqJ`2v;tmB>B~_CF4AYO~{e^;+s^n*o=$<-jhh1~V?AO^B-{>Ryio>n=NIJCl{bA?#oB$h- zFH@J+x(fCRW0zmESuBouktADg7HobG`1Jr$4D=W@VO%__u~F|9|d*gdh!c|Pa31=*Re#I+B~5BFq0tT z0InO-2%S9SJRW85Z5^G+K4c5jv%aX>8UO@!rROcC`aa!^-@3j335_z4!Z{ zbI>7$wiahpQ0{n%Cd4=l`_T*jA~>%}#`>j}x^N6r2Js;Pc-i`1F^gs+kr9AX0O;*d z$*z3SaV0M42eJ=$;2^B3`NgE4ld$(ES`}Vo_`|9+;d_=4sz`Kj{Shs+Eh~8iP_Oe{ z7IbFpGChTn*S`cUyL=n9n?gZYsPz{kJEYE>DjSRd*wdDO4ZNMbEp%G;tS77qFS@QJX^(}vnqou32+e&>U#JY*?&V!6w5k|&8)ci}yB zn%bq7KYv^-71*6Niu)u*{CQ;2qMUUQNYq^~b+Wu`S@C|ymC*+g{*Ou2bvo_?sj(7v zAl}O`yQHV*agq1Lsb!zF@ie$7iY1@pT$S*JCY(HXdZRvwMe%)$!3cPR_o^YzsuCN$ z(eIg@mHcO`PEGvDp|EY&ehlgh%-~$=$@;;P^wZ`s97d)1<1Ru`HZA43ah<)dYS4w~ zSNWUC-MYz9GA*IaYV`l(2iyCPA1q#5P1;Ezz0)mnBHgu#L91~o;xV>ybd0GQ3PJzg zwbASK#qDi%ps}sEE1LfegMhP{Uiu3u7vwSFN&x&8{F~SKkD<7p754snFnQ2&YgPPx z10e70u#zE%%$7E&pNveXKy$<}nN8Qo)+NW}VyxjU;rRj&cy1?y7T*g}(fCOcBO3ZW zI?1N@1ewJ)AWFDBI}CB>LzJr&hxG|j&%4m(E#HmMM7yAN9fgjJ6)oyys%HS3F?Eu!ko_3C+VDUdqCU%~c!DB|b;CCG!jQQ|B7G<=9kPUgo>lT-=g zYu+A6_-SM14nx%<4LC~}u!W6z`1=!cT;(R164-WNpmpd%+l71Y%k5ilMfbSn!bf0& zGWY+uCU5mkbUw}x&+excUDZeX86?PK;G3eMcY_gUB=lECxkH^vC+6Hk^`@S(niDPM z(Zq?2z0bti>lmFL-x;T6pa(1;HPkd>m{7;2lSheG@>lkl?q6=< z3sV@;JH4o6k7+*C&&rjNP52wh{h`G-V}T#r8-b)a4iY~2V@kaA1bA&wQpKXNS4O^` zZO}_r@hBTsPJO%5aDfz4OtR{U^DK@vn`ac=s}J^RUu zX7ocbJCI`(DoE^G96A0ecCxql3V3gx<+bz{JOUoo9P_NrI!B4PhBY4kJm?&~y7SVLKf!Agy;CAXc1pYLQ-{lBI)mrkxVW2rpMP) zwu*nc9AanL%BVMFn3_A}G|aibqDFQ%qg%^x62l!mz~9xe8E)>hq;k!#>|Ec~%qgn& zqWjKdq<3h2kqrhoT330%2*}(pF)@i1%{jQL4 zH~iR_U1VU#MmuiKSF;`WtXi~ThkQ{|8)5B-fi5|mYg7Dk!f^0??UqWn!q3VYN1&ja z?#zlRChkZ7M+2W6ie&BERh@I8f1O?;Aj_1cIf7iqf9bCGupnPPsB;k0oK4WPBuN9z z^1ckc@aNCp5c-4C5#JNR@A0juJ-^ur7pN3s=bZyp`0c9jF)su70 z6hZ5qYLx^i3=|`DZYfA6&ARi2ryo@qig0;sq%E2dhRQcZB%6j)|EU~9C6=Qdz7I#R z+Vy0$NZk-~p~jkKwR|T&LPLfsZ|<#6T&w3W)pDbLeyeGhZLhve&j3_J6gMilH`f)~ z9+cgV^8rV91&b~d0FRv%KMYj(Mzf8}y)9?(30>DcX1k|OA2T-Ik_FEel7bdBkC#>N zx{b-k^$GPECB}tSR3cw+$3h>(ajHxJA>#9t&ILncxegrUD^kftSPWXN_NC76FH`8E z@I(Qe*Kk^Fc83JP@PaYjK)#+dUkNYc@|o1#jByUy4FliYxctFIroZ!UQcTtn63oAOz%Cwj0J|wv=#$ul-#tR}kT1 ziqMbBm@=Q>_eT@dcmLPN=laXqkY?7PAkF~lM$;yzgKOJ!w$GKu3F#xKA$ z+OhRy{c|JI4TZx@Y9EH*k4dh%KtIx7Ony@_zg=QWOG}?R1%HBDE8Srnoihd?Ns@*1 zYmAXqBG1~$L2fnCI+C_jqZe_`jJv6BBGoiaI_uh#Cm;0pC!8-o_iAZ@1SN^B!^nqd z--*cZcSFT;ia~Mel8e%B|KZNuVN(NF(ZUo5X7o%K#o|SlS`kG(r!9$=jJ}f>gB}!Y zo*fDfzS2rS%kk#ia<9IhzF_;*IRfsgd@q4|r78WQzG!WDs`=Msd{L-H08N z6h=s|B501wwvKSd>mu3}FkBYaMQ18199ES^WsSv3>mo%!zA_?Ih1XI>i|I-tM#UmLNY%(-3=YtStnKN zWaqQ;TDd`;1fR|eP^5EYQVhN39JA}`0zTfjv(J^IoveUuR=L;})SkOuWo-;B2IsnB zXDX9tIVPhk4zx!T+YkS+axccgL-VkGL?c?pl6j)ECC$qg5`8AZvw)A>Uh`s~{sYf(LNz{G&fUk>@7>eCz)PL=*JPT*hEdTvS?Ax z{cQ0^pN@OSz&G8|>j%4U+c9@7bPhL!Heazg#AJqP<=IL)T&fA47{%8#z8b}!Gt9;c z+y^^+fV9q#)Q)HSV{(IdrGGbi2Xt)@MpjYv$!{ z8^kb5+f9p)V$nqp!NPMuTw_Es=wD+_uAqc22oKiSlUlEgsl5q~6>OGo54z-jb{zR>M*KPjGY=is%F+wi=!)zz~UuHX6R-^6qONEfJ zn=EH#!CzTA2Ps5bVsjj=l=@fv3n|5r{9RL+yj5XT<$&r-wMGfl02zsTtYr1ug5h~f zsY;YQc=Q5!pinRg0Mw7^Bt>Z4uk+9c^zB%A&tir?gP9ojNt`oXnGr%DOF`{t?A0h< zkapiQa=ZTYLsA=p_7R!S_R+YQD31kx4KcYUIs$c#jNei1W_p3VD9F+=KL`pt8oUDu zE?iP?mN5(wS-35KL073{3fGF3h;)GQ3A;>`xqHCwj^`P`w|(MsRRek4#<9VJjz0T{ z*DKsnPgoK)fjL6cnZ=J^mX}4%4gDuFoPJBvAJKFlQ%LQ@@BTTzew}4V@LulY_6jueqjfv^W?sbgGP%i-O$GC}+pPa?TBjm?G*mEnB+X@pr=Q!eS*&mI4OF zrD$LU8-bcFBSDaZ81Rr|`MiDnwD$k)n#5nblgHmJtv{+Eu>6-MIf$G^hz!F0V`anfC!N?li>o%~HpNClQ2ypG zg2XvY(z1)f2WBrqz&Do^Dp2pGrHjSWo z45=QgFS~s|gM?nuK(cIUX}K5~+D)!4?#(qcjtO)Q9g{M*I3Q>o`f&@5{IwU^>hSBi zj&efOI9PCAT9PIJC$$;uPhwK|n#{mFcQ5ec@$yj{GP&H6#o6z4wuvDdE7p{Kj0w|l z{=dG8Jj|pab@6ncBFAe z`mjE&d)=3QxES3PIndn2p!}It@dTsy53g06o<0oJG9;rIex+(L<|V>YMnE;1W&1c$ zoc3xtPcJ>bYYA)nRT6?XHKviHVxw3VPlfmx1Ik~a^jg|kVCupUUGrWm4kA=34m|s* zSwzGD@*G6ywO-Ue38G`kja}kNTt;N#@55#F%3QkkCx7mc2sWT*(H2zY&VCY(K)MCt zz9?!uIr0-Tlh9rkJnLm5U@`u!@oz$-iYJu?ff(ivOKB}%JU%&t?Ajp%1@Z$$x(P2l z4sO`_%seVy(%4*gk=Vtys&bt`&3?A=IDzJMFQ>9IUL1qZ!e`aKx%LRJPK{poiE>56 zGQwWF2y_f2ya~5>#R6O0+khoT9F_nCz}m`rGma6 z<=hpI8Z`G&Q`N98_luvE?FI**{o(z&Vi7YvT~q&2RdxO!wUU|*>oxbKV-mT@lvK*` z+QsJ63NF`2Nlndh|9=@Jo{5uYpZ0WiX89l3k3TLQyc>KN#J8LM#UlE{lK!#sE&cp` zW^=7qOT)nP{bTBaY3czdY6z35t*oM=)<<6TD^fEL+cTN&UGpaz69+is)_Ul8vUl?H z5Zzq={P=Rei>;ZYa-P{7qK2}eY9u}z@RtND1T?h7AbcR{`0XLo zg6N}Z7#y-1G2LZ4c zs*&qqtcqE$1jhOV654O@7m-h}T^VVtEO7<}hW{O9rVA53->&lh64I#g7DCa8(0>^5 z+03h>k^9DM!MU8g{2oKKH0^#Yx_&HUNC>K@Z1UtK=#CK67 z@F>aS9D0*(a8YSI?d^f7gnq;n;jKa4!;e8MaB zdAIBKhbSDnDdMxnt*X1S*!&72FusR5Qq8IgECI;A%lh|IY-8|x!(Vxy4t+dbeTV{o zutA<$#QPZDjYK#xUjp7dBtwKKSQA_56m>b+bj$IZY&85=(SbQ`vPJ3h=#(8rcwp5g zj9@Hrj9^r8SBDgCe=WxgP2S7)HFim}BjtuHLZVPGXQ~byUm#nwmxGgGn^e2Ma3dfNI+`1qt}q@5`=-Y9 z5F}T!8z^+WhK7gP|9(AEB?gT!7hLc$S*J}2aqQFO0y%@l;a%gw+$Yc3^uASj5m#e- zTc_|ZD(=~}Rb(ioP&(zeJV$xq^BL;=Un?b)Xd;PQMBB^tcE1#z{X%&9sg9p6rzEui z(~k%lDjb>z4`d#ma2&E>DX1X&FquFe!v>K()z*bxLv-JYxbEr}P0!Pb8X_{~cn+Wa zun{v)>yIF5l<6=Og#7OnsYJhmmT5R)Hq!a$$|&OnzB8EFvX*sB>$EHWpnkQX3ll&@oeo%7 z^c17DyIsWt*t0)p?_~UxQ}w1O#<(v|Py!wr?k)g; zFpdU~IZA+RbkeSa7z;{6j7f?8V3zD$i>-EnbHG-86A(e=nT=hYcoCUCS9wHpseC5lTMMax}tYjKUfbo8=%+FICI&(~m*tBnrdiHcVNc(ea`Z;dd z>!nv~jp4I~3lqiMo2VknUaW9fB`v&8k~u6)^P6V;(wV2^vl58rGPjQLXiJQ~O?t8< zs*n-{ukf(dBpS?n5zeH zox}bKx1?OKde8-g4#EBBRJJj!+~BV|{{Ow9gA`Y{2hmv;SkEeT-0L=wyeV(_`Kn#O zUtW2wG$BLg@r~7(8>482W<;5^ivF?I_Y}Tb!1rrqP63xx6rqy=o~JX#)~x#S_K=tn zOb9&&-l{)iexeZ8*hB*O0J70P!GKl3Veny`VdN4pA)llKpn)`Hx)@}%M|ePpX>np! z-=gS7>OSuvH*rHsRQw`IGT5llhX!`UStLD|3plWU8ap$qc`!SxOYlu!ymMe5N(O{z zgWgknGG~bE=P{h^28|Idxk4C0cVI@2gy%-%1LK?^5G@iTo?_M2qN|GOfpkNHwJ15Y zy)N4Ez42Cl8O|JXu%9W)zpb(3GZ+#Qx=`>*tu3pdDjun^2dfBNj4#Bf{Ja~Tik`Dt zsOAVWDHFG|73j*-?y4qTR%+=xI(1loD4gDgq84w0I$o z=MMc<12Tf=WG#^odD>2xf9v|Yo=y#V0$-*%b+C~MfDypcc}!#IjDc*6+`x{fHO2_Z_u+cR;)lWJ za(KMnQjAWDPQhdW;@d$H!L)e5tXDhqW~g~jxfxSM9`9D|Q~=6&3KaV%PRB25J^UEU zmR*;Q`U{OTV)` zP&x<{^#*q6j6Yt3Q&e}IW4kXIVOTOAFbV}&Un2hkTjg;usr<^4oqn=-zEMhLvj#{G z@lj-R8WisJ(V}%AP7^jN8Ez)hjD6y zpiT9`Jil0tQHF_%L`B$}`{GXhGhON%=|UV4Ma4Wp@+aZ|a}-w-kOL9h;%15=5(dn) z2@5yO|C~g_mtHK&se()&DxrUcv@f>M9yTC|P?aCFW|Wf92%8vbvKYvYAOTP&x%J06 z+-#_B3cGupGTCUUnwG{AIm1%Gp2E|G;lUC}ImvCFO&m2{+|VfNtF0TO;2`rOUvshZ z+H3mhHO1vWR)03b+CwF5k;|QXTm>fFoK!_@qauXnkCuKjO5Ut-23!InW~{`sil~mxU7b@ z`l=3UMT}**#XF}*vQNs;qz3n=GCJmRY*s!Q5lv$ubCQdhgZkS!a*7(^O@GTnBM@UW zGD(hmk!+;ntADV!aa(y{Ld*pN<;R@vc6wWQIB8{99dADYKf6+0WM0sUCXZ_#X@R8zcFo3)@Hiry{|KxZ< zNG@_x4yJloajkPRR!JnO`2|(v*|u4l=|8Wg3upt_dp*&DRIL5WBY>BTTO2y(H}o&L zXEOTu-tDzAUu1#JFtc@&&LyelpPdt* z>$nca&8Spz;I}(9M$#DKn6i>gCB&e=XbaH}0sM8IVsGh>4^%s8n{D#tcFnGO7+wug z?gIA7MQ&2@PC#xTOZZ5AI=g6`2-N)To3PJ_pl_?7FN(EBTm}nfyTeJO%ocW9McR*& zr7^K2XVSSfQ*RKG{o0n3;svg=X>P0AlH{hygncw0WXdYlcnBnTv|+4PHdu*@d0LW_ zGj2MwkWMlRRSBuYHz8|(Yc+(20ERtb(p@Woz0@0w)nvWmt&K>jH)&5}(RZ;}mjp4? zKq|B(bee5Xmgr|c(s};+t>AmS|jX(cHCrhyaI*LxF z5uoFK#65~Q#?t*2Cl+$%G}u0iuHny-&ll*c#TQe$^FkuPPl(w-(P2k{GQC`hIg%_k zx0EBeMdLuy1mopIv=CX+_d+6RCo8$ijlM_@+jqT(%_81-3Z^Sv2pcB#6)`md*pNA~ zDBIMF1h*trBl$rhFqMfox7slo;}ejL{a9eLyN4;8G=}Ch`Aw?07<8d3h`^d9lZG__ zM1_Y3*l|`VV!3bo$F$+;*7fE*CDq5?_2B>{WR%SMX zLzoVY{c+*1jOv0?I}KDMBkaL4Nt6Kp53Ji zyUz1V`cP6)R**HrFkVQ|i&SOIZgYZ4YOPjdAB(?rDd*JB(A8-zZc<57Y1U21!W)AF z0p*ctC<#Z_dN`RSy3UfBN&2WiVgc!W+TSM{V;QPhC#KybK3Uwxo64I4O+jiRC!hEN z^NHcjhk-+ZoP7kJ`X0VUO=p;k^S-M}QgY)1YOldL$3C4dcL-YrZX0fk*3NqG~%E9B0X-eWbi06+Qab zCPa}WV^Xs-D!TV*xAS^R-;!prIeykwI7%SwqPC4VCfOykSBP!mWxr4>)_x(-oslH>---M8{@;R48v-y82>mzuNprTo_ zJ3Oy{K1DabQgP0U?m;f}ywHTIS;~X+{nomh?W!gD^q=4tKyCb!<2grBacuIYvOW8Kq zHq_Q72a%voLAnp>b;x}5N2mRtb`A>oNueb`C zUw_TBFuD#gKLB@F^Z1dG!94k14dz*vC1w0?FG3iOYW^RpRk7P&#K=02w7i(`;yCr> zSG2R=i;uYm{ncbQpNr2AxWH1mrC#Xhv|8AmqpquIV?Yr5)Y|5+Aln4(A>?f>G9&6Fz zL#W5tA9ByXGv!N6<D6uC<*B&x zOA>f9uTj3tq|@Y=w8Y^9q^d+gtbfsK&FSDL>o4OfXo8WtQl*iU-L>wJi6J)dp^c%f zA$b-*vT)z8&K@ap62gb44D~ z#=pqokt&UxLS0yfxA;ihXwDT$x0gkLJ#>=BY%X-Skd_d~ zNw-XwhFcyJag@qm{Z}|XSB#zp?JBwiCJ;IfGilXn%=6cez}QNh?`G;f-&Hq{8iepd zi%|(QSd*dj`vCeak%T7CQMWVTu+bTH_fZftn7i+Z+HRHirnEKo{3&WT7{MGrDhu9D zY%k^|#r<|!0G+uoch_1y3@1MYH!*stI-3F}cCn6FG{JS{t#mwqwqPo}*ys0;bF$+$ z%qL;xYBZdhyZzC&lNhAh^?Fl1-ln)>G(1!Bu%fj9VKqBf8J#HXyAn z0o$A9!}Yhdp6(^T=ihkX#jJ+q9^Yne%V44qm}H4V5=85l_XB$oYYM-KjYhVj$s9u0 z8oNjs@z38=WTS8m>A)*|yjeZV;P9`@5#dG-zFuy!Rfe*A_cC`czN2m80b3sb&7{BN zF^p%yr>wE+{v|%!3YeV;?-I|Q3%PXXw64F^j3wv{NIS2$3aRt&_UNx|x ztq1fx_Wrc7^KRgJ-j8aD&lzhUal|jK$|Mn|)ZarJvU|9EdHCg){_b=jCPd8TwTsf3w2yYN0Mjv`7mGK5Tf=PTwp?1Ya^iQ5Zf~-SVv~xx`9-%@h+>E`d=k zalMNN(|`n?O1X3AH5yyRjCQa?nlCATRN5Q0y^dZ=pJuY&pOVK*qEp0^gBXXQ*A^=k z<_xq3k7k|1<3$GNlo%3C5m-huBKt4oR-NqFF8HqxXcu(@l|AnkMw?326v&Y@-jom4 zm1KQ;L#|`PMF(h~)A`NRAM?t8EPE7k z+|sHT>6@m<>G|J1nyei>P9-LQD29%lygYJaM|M?aeevm(>!yMD{Yl=_ZK*v_Yk z*!IJ0NBu!2@OAxO$oA-mjB+F?xSooIK2-)LX@=kawT)Nk?d1XLlKxaqG=M??)9&i(Q6%_J#JBlH|rLG=0iZsk(mdD%= zAScqk!c1ZE$o?F--zY^P`1KzxX+3Z`DU zw=*>1FnAH>cKojR(9YD7wW4PCdwqquCNdgZM04|C&GvVIeA>dYs4t_pUWUeaPv;=c zNV$?{-Bb?m!0(w{yy{a4y&p3njr2|)nVl9v_Yxzs3wrgNzbBH0n_P!Y83K=!lhZ1j z@OD1-)p86hhIQFQrA;^DtvslZf7_ajOeGqyEAqH|amapJexW+OoBDq7d4Z~J!0-9B zA8)5sjmdKDSio>>btplQdfIU3A}+-_@1=~J$Gc7eWy$sAWdQ>%Ue+$1cd428Z`O&g zSf=!lt0AY0?f^L+>wbbX!C7Y|r`fAo1v3hBO5(4=IL(%x%oOqms-;6-xEYqLu zGk;X8k(K6fJqdLZ@jXQ@HgD&IH#ZwLJ|vVxG(%>)US&t0gE^xP4@7xwB3YS!OCC!d zhf;fdz6OS;B2Db28C{Hq^i~{^5R}>HBE}{C9nf=tHY(8)B+)F<<5ahr`F^ZO2ffrm zK8yN6k4-tonh-1y|1mEKaE>QJXD}8cE|3zNv%S)N`jb1QSqYC3g(%HiQ!%1YQ@~tJ z{B13eXR~(T@zG8DdA@-zL`jc^!7OKp4DQ+kLW6i$_g5Nvjt3%4L2ZU=r-wu&KRFdp z@4TG43pcLUGwRC_+r>TB`JYmMSeNyciwu#iVHEl1#2BSD1|duBKtU8Fqleh3j2Eai zOlnkeg>qigwYV>VC%Qn!21yQ{6}yiuudFO1)qdtbESQ)UGY|zDT~jQ27W{@7g? zH7+u&fuFgBzBv5hDxTUiTg?|gH1Jl?xvql8hj_f z8qw~%C!fez8mJ#;MoZ$T{&um|Txz+TwU4J+bidC;U^bC6j*o^Hr!!5_D)Ue}37Jmia;&T zxj)L!Zl>=Tz0lXUdaS@%?xb^HZV)PEFz99i>Y4v#DW1+3)@L^^!3M)I*ta~h_nZ#T zUu1>bj(2W0v)A+@I?=48>a4gGp(tq^GIK(g$Gjs|1$GPly9sRw`|<_ZA^1=Qeqb6; zCLWa}S~I{Q9(Sw|k%Xa38{b0rm{y`38SIt|D!qs?-foxQdkF^gDTiM5T3O^z?2Ct2 zE|9!imG0C15_?9c0W>v+@(Qxgm7we}4U^9d0%HBnp@=iYZR)pCedUeLWL}Szh*V(x z;*sB1dxa08#kJ^jGmCGbBnantNS6T42q=@el?9<}LQNr;cc#Xn45!dDHUv$nQ&%19*1I5{tYK3<0cFQ@`PSEGU3!-aQ_1f_u! z^IT1j$^E*VPPt{gEX0AsqF?SE1dqMtQm48fEc6=GH=(7Q>2;&Be@;TE%j&B54YCt= zZhb#n)7i;B&x|fvuC?51zCpn4AW5qX@3s#14qZ;)=k=sV@aR- z@l`}F*K!~{uI>!ZyX~}Do)Q$3Ym#A|@3qCxHz0NX+DpvL+-#d^-nJLk{`_m(QO$1L z7w`VQJA9+yFafl8*4c55chE69Yz?7jzT4=@?JS{zPnG--5z~CB)Xk>;KH0MWN5e2LrY9s#t@GXLHML z>WTHj-_+u6%lx$)&IRFtZr^8RHSSb53#rkR+7|wfxc;{WbO5z+yp) zBHZ8QZ=kqS+aD+Xm!cPy|N5mLHg0$SGZe%ng%oTQrM_}|p}-Rvxq}H%Qxdk$W!5pJ z28+g-xkeY5vPvp+sniO*lf!BVg@%f`%Px(K2D>V0&tnc?iE~|f@aDDqk(%yP z2tA}sMDLrOf2cEOhnvDZ*kQ60;!5ESIc$nNf;dA6$5ag5RFsa{=#Y%KwLF!u{l%Z! zKi_=XVDwdJms&;FA=hWtfEA2&ix*RskTVY9x!>)%^$z4@k$o@lU3IQ`>SlJ5PiSKf zVjFSufAGk~Nfmn8^uAAsh#R<3e$@8lxCa#4hwmAOb>T1i*p*>z$}7nc=!GHJ6EBj! zx0aAu)V}lnp4(j1SR5U~&3qm4k0{1e7;#AHx1>^ilvwUHsn3 z0oDn*ceKv`97kFWAzf5^w~N6m4NuvqkkHgM>&E^-p=v^Pvr5mWZ$j{U>l>cV%xdI* z^1ouzAL$?YZ%z8Ax_>Mwk>RsavanbVh>YIwjcUL<_9a(|Lx^)x>8M&&*=Z)bnafsi zSbEzOZ$F7UMaWZ7PWy$=n1I|bP!*ajyB$ltxMt8r;zNwb~A(8E=hKAK zqR50}1bMo|xzxCj=q=dimZ+SiKmZzpuMEJL)^&|+2TSEMDC4zo8Bvr4hMg1zUDrht zhlW)1Mj?#JvkKvv| zdE=v{iyJe_oTqIju{;s#GpYNk${&-l{e=>PI!^15Vz9 z!)prGV~f{dmeC}$!VAl9C*4!cQam%X{36HqzHOvOGrDfyaXalh$kFSVRmdtyByi`8tsR*d&j!&{waRk| z>Dw~YYpy&nu+)VZLe0Y}yvyMKyrr-Mszx#yX`B#Cm#ep|<}<7<7$vt14}=w$zaMqj zqMJ+kO89!TJvp2vsCRt$y9rZ{Et>b3ORrI{SuDjgpXD;PU~0YF-S7KOR0Zdns*xnm zJafKWe0=|ZX03rp=n$YDB2{7>Px-;^!&9nGqv2lHuk2E2_6hc_qN%^*CNJ9MQuE~d zl4!6gK8N$1#}nnwaeG|t6QT6${f4v)4@DWEae0v>G9y$|)JQ5X>?b9<&HDPP*W8Gs z3Q_@aAoCNyvqJKP6_KKaJei%D%wMG9$Pvh0DEoHTO!f}?Uc)59%X1QyW%rXJFh_qV z#Zo=3eFvhhTeY5r3U-fbRV-r0f0kkG|`-8 zYvJY4(?>Uf(jgB&NGC`1DN3bVkO z(O;hKONc|Ky%A_K=(;L7wtJ_MTTL|Rflv&1F?o&i|-J=}HM z#rjTVKBy5Jg_NpPKKZ{`l)i~f-dO@}7JSv2;G>DZt3Pj*J8xx>&LSOO5`V0+D%k

S>y33(kz_10RQB&ye{`Y(PuQaoZ2 z2Y!v{l@X#WEt1%JJKc;3GbHKC?y%XIxTC{I3%q8xf~D)oQ5{7ZtRQE?MQ)kK888AFY;$OaD-zYj=XUT3dF|Q z?O`~dng7&{Q(z6jQ*C7bioGbesxv-1q>ZJp6G3Td?tfD(Fw2qJ&3=++7AvTHSoRJJjX(2S(=^p!+s*UiZef{72r(ytm2Mrqt>xM@^wO9imEqrx zmFg$&J`-Np1FM#bdFHWjpS}ixOJ(rTF8=b%Z^H1>wi-fu4h{rK<=Y_X4HMh#LKMV& zF2eJMD|*+S;ik0?4)Jo@a58X=ahP&TQ#GoVgU@!mfwZaclZ{W)4n5Ifeg%FIbgBvN z;^o9&V#jN${0LT$Rt1XhtaS+mt)#I@FiU{4e1mce{F2k9SuC=4vqy_A6f}qM;mSL2 z{&pD42(t!Cd?Yy}rW#$0K1zy<{JOEE5fbGNr=B#_ny4{Zv2AK=oJ}zwXhu|&(D)*92#LG@V<)boFBc>Jp@pgoxK3j{m_pA103-m0ouP{J zUPzH>B4@xrEPm>#cc6WOY5KT?rUc$0V8Zr}6%)SayKk{sF~Ekox_KHYn1&W~u*c3Z z5Qg28hfZ3d{+qTcG~QuWvbqy9RD}jv#PZe}NmR_oFVGWfn&Lh8#5j))Cait-eyz9@ zV#MJLJq7OT7MzK~{3;fcecRCL&+ZVczj>VKHxQZkjGz@cP6+efZr|x&7Z?)X2G7OI zSwfIKngS+A8bYgxJ;+>sh_S{l450o=ZN!3VlSZ@Y@@n!<{E$=S8PTivaNn|+TWO{S zd`{FQ=tccP7qV%^>UYBMnu1;s6rPd_5*o%bGRC|Zp%W-4In{+VB#lS&PEr0HOyE6_ zUr7cGsvBuFv&~`1&*3T0nGbFcf_oj9Bhn&!oi!W;24L-kI8ODDTD;8RRLku;`?lcv z*%b%!z`u@heL_u!f*p~3X)-z4$aarn!ZH{xXp(i7aFwzCbTPgfEuCiw{{=LNQ&pp~ zuoz3kM&Hr-5_$c-?39ocD8dwe0M$$zSXV zo6f$|^JP~M5<)zCWzj7vqG0uM{wpv+!fvBfxoJyv_(gKH9(KH!mHXL6pMJ=ByLB_s z=yusG^{2Douw%8dSK)1@taErXAR&A7&kvhMz_1jfyFj@QnW{&_R(g1XE3PBK2HGKuzJ>*EDq(?L%&Hc99sR=zQJgM=AzPs=QWsA!T9R zqzKL1f3l)E@SD{&glEd}8n@l6af4FC@ zE#<|&#-masotNJ9T8-&`MyHCW&*V9!v=l#Nt7l!5m6gk8lfnlzW`N;}^V3%mbN+Gi3mst?X9@NkMC{$y7Ph|yuqNYa6($9eGB2wt4HNOgm}7sKlpuJ^eXwWY zgwV-R_QE(lB7XS~mQL*(P#*CA7TyNKFJZNZU6+6R`?1m?pN-_Utl)p>D=?9tdIJB8 znQwCheKEe;AT^68`Gic2tk6jV8H`~137?8Jj1*aMoYua{GOpX~$tB{bH&`NwEes=W zCzK6j8jzr+ry#`UtGUcXSoY9IV7qH<)e!2?yB$1ADxI>8+<1q==~Y_ci?t!wQ=lV>|+<8D~#iQZ`t+HI_RYAGJI|v|Olt}3m0wX4(kqyAzhAcrRyi3qO;E;I*D?}cnEiN2Yaw*ahn30%P z z{6Gb7do5K9NRwd8vLwKwg~f)bw4F=Fv%ZaHUVlnp2mT+TBM6C04%v6P9lFfDMg1RQ zX+-cRBi=R{SYlXvG&(7qFrFZj5Qwnr(B`E2SfHLlu@wzewkteqE2%2$JXBCfXZqJ& zWUe74%}zI#E^{U>yMv-}3L`N3d%$NXT=A?2z&yYe;Oxq!o>KHf8MR1Ki%!i$*P0)h zm_%BVUD*=kvzZ0gKTm|L41@!TuFiOZZofou=sJ#O-ewo~5qO`x(Hy^mhd|lR#$yY z;@c$i`ccOl&a~Hv7b`d@S`#F4qc^&q1DeifmsT$}{)=`mQ2aq$)9PGXy+5@nOJS^L zpD@a{%6SAzfGOdRMO`lWc{PG6%x?esrW zGfNT(K^oRPQcMr2flvLs{qXI;D8~sLGr$0yBrzmFHqg;W{u!YBTnsP(sQCKRe2ir>`U z=!@~FCV%>uI`AXAgYH&~&}ho;sE;U4?vvMUBB z!|kzTGMJL^sn!###0qqMfW7w605Rd@Aa7--+6(lG8uq)h@%1A=~Fz- zEA~26Z&o)7Jm#)*_PaP%i;Cn&M43knd>KlzJ*(6w5V230%Kf#~Thf(s^K( zSSEM6fbGWqc50JmJnNuTiRj!&T8qDLO;!6N-SdvC({GSQ9K8&~!CEiB<{1Bl$x3r^ zsxUvp$%~a<>$e<>5=kf=*VRie=xInul(yik(33~<|M2ef=rAIZ93)Q#` zAk98gjC&$jMXLY+W+5gLA7rRn)80K4%uZj$S>ad@>8iZ%^X?6|r{Jeiq@5>IW!Q%Wn%vbA1du)uZ}p46?KjBD@Y%*OnB6+0N4(F|_Yo7np^YpXZc4^dlxFqSJ&HG93C zyRxB>&T0(YKy^FiOrQIdw^5`oXKbWV@QgutjU0s<9XrDpAsL}mZCy<;$+Idi^8Qx` z;7&jMQDx!4j}C}34ny%tlH;{LC$E)!Xcr@Z;jkE#2i~?a-`fv93t2L+HJ)p7>KJL2 zNyeB;%KQtguF%zs4CdN%?&x+=yOXFSEDt|75?P^6t7!ytpi@?*{Y-Q% z_94(7q1Rb*7~S~V-W4yhz<+|o1LNL(qRM)p zy$-$&!Ik|}Tmxh)_Z06!5pO^!`r`Rph6ngD(I~Pho{{kf!-p9PQmC!)v@7Ej!AGCx zpg2()LS2#fLBT6QJrSS`!|FYyvkp&HfQ`5yr^ko!ZX11LZuJu=TE1n8!HY_4Be=?b zOEdU-f4~ymhNwg4LsV9FVBcz3oc1$sQx%9T8ybH`i&FAhtET~wz8^cFc4ZJB_wiqf4n8ImYvy}Zd6;FY~PR(%zh`JVU-d5q(#WAV759MD-K zx0QS|iqO~RS33kBc4j;UrGG~zPD<^OMM>PwH@$sw>)N$_2=$W$d(#yQh|Visd#Z)v~pi*k(Xce67)IXRqlA2ks<{;Beh)pVn}|u zw(m(rY)19;#IL#}2oadg9+wUVxpJ!2!gg2I%!JV6a)ymmHORFZFvXg>t>cNm<(sLV z*xJucJmY?5%#j#bqHVFw4^Qd(JbCPXsaVc7qo8J~8(G5EwpPj6=>8+z;my`#itT1~ zN5OO zI4Pg$f(p&9Y$(x6$K30MCLvS9x<)jkbvaiIQ8g$V0vf#H< zo8$lF^qAOBaqLHu>>-KfS54X!_@YKso{~m29=bb538v_#@ob@xUx~!y%NXS8d*cy9 zTAo|4&AxCDg+FxG@X=8*Ki44R6)eqpiB!$Jnf6~heS~&8%J%OH3I1w_kJ2W5QlYgt z$PcB;q+#}-e?u>57^)EmC&NQ!3VUgf@gXWm>BqZBi|8$`I%qkTONl|ol!oJb#IHo$T1AQv$ zZwV|Jo&!05N4r3tCF~K58VrRPGf|6S>E(u;hL19T3MX)|JA>Q)9%rrbYuRW-@b{?- zQEcqg_~ky;K`iYw=G62EJ}lSDGKL|~89K%(H+x+RxhD6biimZp8r>D4E~0_VyI(wZ z4mI1c1@I;^7m4Lr{MzNs<`eds61M}~uSPW5Tk5lkWrd6kuYA%@gB50!1~CFJkY85} zD4zN2|NNHGNllOofAhnJ1*N)t?wn)`7ox*w>3Amx$yv6d64{A$K{Tj&S#guQY*No$EGN<{ezrCXhP~9 zWF7M94&kcaBGLv`hx)ILEu!+QPI)!zWCREY+y zWy1BX+y6Bq`(f3AfWtoj4qV=PFvOQybyc~MY1;P=ql!+vMD1M zWvlPWaL^>EXqY6XR`)Y64G9+FQq-x>rPw~=A5!j55=gj|v)9^-+2F%)y_Qu1`!0(D zw)M~H3aiyAri3^5gisj4=`9m=$R_=~Bf3Q4pOxZx?`@9x@!D&AR7x(YTE;C7LO6;% zM}h-UJa>!PA>Zjcz36{7G@rBjVBL|fl*B}}o`fbYuA>7`?a!Y=W-}}X}z(Ju%co3fito+r2Gl% zcqX{UJnbV*Waf(OKm#uhs_~YU#pVMnA98bc7az$q#Z(>O6dU!38JpI#>~+TbAScEF zrdYVnX_4RSP*K0v>V=yxH(Vy`EakkOB@#2szW8$u#z|K+D&lk`e}>V9>_OB!kN8BU z;6*<|CL`<0>F1yw&Gb_d1I?*tqo$1i^ajy(45X(o($-nXPyaoa`nJiRnW-_$9;GfA zMoDKl9-^7|J+JB8RE<>F-5EAMR96_N#e(5|)+<^gb}22tSxQS_Hc?VyAz91Cw#VOu zbQ>WNsgT5%;othSE({MjI(MMlz*C8!0BfqJyt4=<;4o3Ez@-g|?~h1^&Aq|#^H0!- z_+_WrNPWY(wr3lK;w|P#0_}6tohlwgCtp?@)4Hzd%ZIcteEwH3?WLU7;@kt(xeA@p z-;DfFkCX~Maabj2;y?yZ$|FEvRO{k-_J)7_hff@FvK~9C0RcJW1>|ii}ou^_lzWUn4p` zirP|A=?lB9mNG2%^Ho2Y@47~3_eacRB{x?Pej2xrPZRroD%$2{P&F+H6ybWRWB7U+ zUgTmDgVTlF`Rg(9#uYPjOYO1w$tiD1D9AQkd{!$Tq$_*POIV00gm6F1j{MI7=_=7lQl|IW82?A;&t`D6--=lEz@tTvKNvx!>F zV1KyB8A91MzUahKqRayT*5Zk>wvXkiOtA!?F>Xz2QQ|Vsa+gm`4L7XpGFEi;EH1)y z_p$enTW}#E6Udy%IEP#M{=>9CiTyOA2FMKDaSgwxxQx2e?X@t1J)XFE0{nFDQQ>!880t^Hnp$lto*N|+Meko$l@Jfa{KbRv0@K30qlzvi3rJtKif?`Q zZkwX#N8hhlP4$DsrE|XBq1(MaS+iwuAqt*+kap&EusVV1x{U@@7b%962lx*;x0gQv zxKCkh5HbVzdslu0DQhK_le*^`|BtSBjIN~Zx`n%w9ou#~c6V&6W7{@+r(@ghSRLDT zcFc}#+y2t`dq2-P;~nQ4qkhz{`cc=aRco!e=A4nRF05-FwG1>mDm_qOyOOi_QZ^2X zg&iqi-(jw{P|Ojb^JRd86bJ-X;591CH}K`Mz6ZL*AA4?hscV;k5K7iJJMiu{s!{aK zW^KEp%a*CVkWK1Id_zgRtbpgZ2*7Mryb7IkihWE`%PcNr%sTE_d;$Gre0~yx-y6*BbK?BSF+rf(=pTp5< zS6Kk^@_KQBOpZ8B-b4P|pvrW{PIMAUd@4FD=#dY=>+_)!-G1n@_8LqmO=OyWLclOx zquTyN9f(rbB6YKvQ$fM9UW?UEEn3}k=`jW2_$DS&HVbQ5jZnOlfmC7W8uoO=D*YK}lN%-4I$ zgN_T<%b;x65%x>(YuFUSx~Jqy_C?JE8V}~^MTE4;oqo1U#Wu=S?ZFIiTFs^-_=Y_A z!A|EDr|GT9flm4EIi=h7aG#xrP@hF+x`}Bjc%*MbXZPw$l=w63U-RfqWew40%~FQ9 za0@!0q?=psVqBA4|1{qX4b5FmOP``2L!YkOf%qT$P^i799yb+3m@4!LOGu|hTq1YQ ze~jaRasN0g`?0v+do4UWtY%MyYA}Ia5wDzZoGCe7qAZxr#j_JzRT&Iw_)KA4v9=u5_t0Xxk{^qbR$t&tGmG&Vk0eZ} zLa$1~+rwc~N>jUor;sru9HFQa9CCbZ`bRlTz`+}qkW_b9uF#{Y zfj(xK#faFd2HRoEEX6kU)9a`v_Lq+vv9NZuE?_tWx&m=V5mN9ScH#vjZNQdA-<_xx(U-ds8@CMH?_e<-_`QJc&G|r-TzI4)uRM-*bHIvr5bH~?);2>T z#G{xej-5_}O|7dYQDNZSWiC)F>_=a7j9!tgo^p3azO4zi4pwM{T_DuFn9*E#A!m9A ze@s}5<2(kELqHZfA!tW5?%{4ZiHa;o=r&sqhh5t!;&x7vQadG+EJQ&6ssQI^5;*w7$;Vt zoQ0Bguj;LAlqZF)r?S`y`RyRBEy-KoW7wxm?Eeg|Klo3W^L-CoO)h=kohshIIeuW81RwD$>{<+QnsFG8 z66VU>ChRBPu@tyKw%KorC$isWeIuU8ra8CTN1(RSZX=vitNU2b7quW}EG{#&NWJlK z?yUP=&#BJyqZW1hWegn?8tb=}fUmwpS{sse_{&dS1&i0G=3-m`8j(L9>47y&Wg%=Y zEDo4OUv80B{a7+XTqfLO5)&j;TQT5g@WeC!3Hk`Yf))Rt@=ZGfT_imU<6SU?Em$m-@Cx4eya*AmPq5d5%UqEvJm|B>+ zn3`NiHjd7Pgo8GyaRS+#ix$0K)y%smscOK_!3TYxL&;K0=t0oBFlWcOosW?n`^%I! zLA=hxIJ=vx6zkT?yu>ySKf}o^KjgmJA{j}`qOPi@ofUAQQ92;Eui)_pZ7>?z3Ejlh zJ|l$@!1_R|(|YQ*XtsQB5!lD1es3(W;5s8QY3Dfte{^cU(MQm;8nfoY|uG>2KvZ`#m( z&_;xYFg691#wouW7xwwj2ZhJk8<+@*Ih*)?NRdeT(LV#1vIBAorctRq;U7P|=g6_# zj^`&%vfikL9Isrc|3i`aOPdQoF3RhS4IcaV&(2^BSX0~vevP^eHWQ?!7Q-2?OAClL zK@_4}vG>>Ay_V(QA@QRG3&J)A7xI7?hqr^jpZmfx`_L1F`BRjsMnfEYyNzNf>GDog zbR!bj7N~C}MU-yD)hEN%<=yXz0O1(ico2-#%611$I_Ds5)kPh6>&nonz0S9G;Miro zU+yUkk;j4jTL1zCSI<~7982;*2QXGfPNug~+89E$YeDi9Bl=(`UtI_YbY{gs32Bv2 zB$gGkQr1UrG=CBl;ula{q2|@9k;JZggWMr7im&$X?&O2TBWS67%C{Qfz*pVH-^Wwx zLO`uPm-@Yo7*Zp%ZKHSL= z-f!q(m=ec!+4b3q+d~4chKI%wVitQRWY7qX^v)6bT|q*yu8El!3wwS?dpo z1ipTL)|ZM zs$-5d-%28ogs7{c^qT@~=vRRqbv+9+0-|Kcj^cpo?{CPWe+vBn#1bz}o5fJ%lAjt< z&l9_d5O*qy?B$;<7=Y^Kepa~YApC92QGLT|{2QLTn2)C#)r`~GM}ocy7L42_E(D*t zYgA%~TL4#teC7ib(40djYEp@jdC*wnkDe_5p|*a=E+~=upy=j<>BeqRccodP*BE7u zpMvby+7|hy=amtUQ!H>|NU^PA2>4a7!5#(q&ZT}-C0e~B#*#I?p$#;bPmfKP^eCrv z!=8{Mz_$`34!p=rvttx8_@NAGc}t|{d029=&brm&t9Zirk9NhBg`X%IFZug6D`m0< zdp$~Xm$4Fe0ovB$=E&a**m$%+uGaD|BMH>xpLWEdZBAp5hLwrFNo~1-UPNsQGwXaC zCJ`HMzTo0R?JrIz?}syGSQXSI)BKTv1pJ0VM!q={h-eJgE&{ei7QG{fjtkbL6?Rr&~9v=7I)4(u2CMY->VR`k%o@{ zG3gphc0;*utD^m}pl%x4wJF0!?O7Cwed$EImCIvSu+mVbYomq87NloziuZU|d0xNX zfdigm>aTUWtjW69O>bp$%I0-zmDGein?9P=-i2~ONR9=BdfxjVdUXpaGLS}_F^>)i zj*#Xh^b{+B2=5fdJn6^2fIWk4?t3xtE{*L9>*KRg&UMJ7FX#P4BV?bds`x zze7YLgh;REp|OREM&6xvMVEVi-+M+>L}iphGDH}=)IKp7@-POAt>C08 zIAqH0DV`>o>7}7B!=FT`eUj9-{5rkRSjyc*sYA-DF4~|50g)-F{K9o4X^WXQY&WWh zbcq(JQ__NpjX_{ehf0Azn0ix#71>;dRX{OAf?HZ$0lHA73Qz~HkuXw1aPD+7oZBT< zJaG^AOOr_0J$msF(T8`6{^pC{af1F)O@$OE<8ex{B(x{Cc4_faq21y0eSUAj-?&Hd zz2empfgZ2PopvvYJ>1uFXOl@a6nBLEfQ`Jm$D`_`Pi<_PIaOo#0<;oK=AZ1}pN80) zJqi+kU*4eTX@a_`ykNceYJEO+HvgY$Kpx>UeAy~&Adk$){ z3V1zWcIB3~PN!skk(5h&h1q%_1l>&`E(K4|CFgTa_jBo~>=lnE(;y@H6G?{`rES0)jvwW*cXA?0pEDZ*?0wiht3ivGppPN$*Vz5Z6NQK@SPFUyaCmRwg2AbSpw zot)6GlY!-5&)rRP5xQ)v5XKz`1=**5fhYXdWlpP9<3 zgFcgcriMDdZNXG7-QaqE0)BVaESG+49gCrPl#MPE1@YX-NzHnyJ?8@-Y164k?@mv( z{aVvpOQ@hdwjHT!u>Eb@)A&DTsqcPsAZL7c}1b zmTF)nEkvNu=4{$ju3Wa_XetZ8SxCn8!?XAsni)gA=b3l}(7*v(uD;o+_cZIn-00fL zI+r#tdMsiC1I})@)9`m>W?tJ~}x3$fl1sI4|~LB|DUHMK9j;+2`JNk2=r zO5$KeI6<@W_#IF#)pR5oC3J`uuQMFtDMAnL7pSy1qW{&eTO*OL<_3wau#R-Z$D4_Y zx;0eI;NvlS23FKwCOx;(&9aZoVenX6wA|$F{{Qg3qCK=?8V1kwXmWFN7czAf&A+OC zU?V^y54m1IoAr;9|UOKl@q>beH8yRt_g)X<@%R7UBJ{}+|+hpua@+I!k6tCdeV z?TW4FBW?LX$9H$_{)n{t1w#4V-~1ipgqa-jJOeXqCc1I$^2(OW*Is5sbkFS=!JJXq z2)kbxm*UhQ7fSpTY3a31B%LUh<7`Y+9qL9M)#z*bn4?9PSX>`fzm!(ZB1JT~>0qhb z8swDcjfbmhq|InIk8oAv+Dfro1<>O#&A>`a)7$Nyy6Wxyun9i`5Bk3WlKhhu>tlPZ zs9h|&29lxw&F5ot>jPJ%ONk;_v|Ww@jEV=IdeW=ilMp1^RePtffH2EwQTN=~Oy8aE z6dgj8VU`GcfQc9`?K7~4m7krQr9H>bCXjATT<3&Uv&pM38ESpEy^K3Yq@e6+fxxye zpwoSc(E3s}W#>+J1F|lsU;jaQFQEHGed=lKH}^A82XF_t#g>>44J<0g=gCz{W5p4Nd&mZ!m@v2Q4s_vYHT8zb>04W%?X(Bxz(x7iEL`FA_C9r$-;VoMfj3+GbNd^}+BkHkPma2kV-Y7bv`7`!HbV zwjcg8O?B(B|4V5WSOgi7nRyShRdE$2XtFlMrNER z2CMAW`Tn4~%zSTE{DExS2Ln!TwT5)ED`RC{Om}wLlESTB%q`ik>+Y7gnA_$smjUalho);-?HY&R)%dw} zMdQkkwdEwLtp=4=Lar1Oq}Q@aPn!q(=j0P_S2t=V(oj#)$1%KzP z#sJ6up_*2)JD2Qg*Pd42)`-w|`>M?D^1OZJUZatQ5padh2SmF*kD& zd-gqh)BC#SU+yFYB`tSiSRA@TP?(iBQYO=$yZ!tMhx-@25&ThUm;O)tVvY}Bs?tq( zQ)toBIE#Cee6IfjWvK*5IKo7+SOYwwF2~qvBYoS|b0#%5H3T>j`uQ~8yI^E0C>0>X z@vw1%D+gKB3H*W&K{U_z)FgIV%}i*BHw1_meL3p7iC|;#&HEkXQNqD487o8`UHDvZ zE{!B|_}p_W>}hb|FC2W*yA3)eBM^>2PVOMJu?g@(jIfY*Q+Qg34X314J~uox7xlSu zAP?Lf~8IWV^Xq3kr_^3sf?e-f{jJ)+%S89@AHuny4t3yO2H$QEZ?bYs!I_QAxu z-UoEMGLF;s{=txcf%%$~wJ=`?-*jag)1u8ITDJ6vvpn#>_7a_>@JT;~!n?q4Z@dtm z&Wn062rHdurK5y>KKiYv?{Ou7Q*R1Y2n4*t?c*vC)2_uELaPnqC*&OolO8 z<++)7L*Q5G0|T`v_O!bTR9a5pLPPm$;%YM9(`k{aw*6EXSkuYTlxLmRanG}v5vAoRKo7uX|wv5mW2hX->`0kz*nt`gSX^~}@bmL(*{E!h zb`@l}KE6fc6!`&Ksy&Kge*MyM)rQkZ$wYsNuy0S$A0OYZ_z6%h{ojwMOxm&(e_=+1 zS9+<4$7Q{1NAjOQ7ts$p*(10Gp+3A5`tC)3vNGMFTd+(e3ktxEViz#YV8m#Wk*wMw10F!iPaJvAy+rKd3G3&>IO|z;{ILmFTnXkO?a5LW%S@%t* zCNXkzWZYGyZ)A5gSS7XoMrxAE}aF+a~R1g9We1FsxKxz5FEL zTUuIe*V#C}0Xj_3wPR+L?+dZ^y^DfessY`=^3CODi!-5qFBh+Ip3WBxIbD`g7N|H5 zDHF(G&?b9RCxRLiyA!3)Xv;FsezIeMykF2f@BHCB-fZ^0aBOdLkfbyo%O128Tu#X z4-Mk;q>6Yi?h=N1YNCrnnp2AY?1AGzC|-CgbTEV98+L_5=LP*71U(f7HOXTBd`$Ad zYum1E!F>`)u$oXWtJM$}A97SpMEXcw3cUBMC_kBunF)QfUl|Ktsygo55I9y~nV{ z&i7Wn?wbZO|1cLXd9*t5#h=ZekQbVr%-Xda_;~o0OWS_8CLDLf4U&>Z(qU*84r*Eu zpxNTe(pZm#=`HRddYi=8%|Us&J3YhK{z(V>SafZb8x!)PG^rqOxn$rMtl%T34k-mOF zLPry`@J4f6r#`E6e?H~5B-8yGx_In%y+Ary(h_03RJ?%4@xlquy7UahwU+_8=?e+^ zxc`5uxvyU+;0z6)|5six`whA*x%wUhC*Ws*Lthuv5{0xs6m1U)!-J@ou%?!yh=NWg z_7D)2X*D-v*pjxl9wHMLiQl^L=7PSK&rn_o@e)_swOHp*Dpz(47WP$LdEoB>?fgI$ zE!#C~n571N1i0DgJ1_DA2JZZ+8p(YUSRl(H<8Exm%Y(wcT2@OZrA{eu>dL7AC(kDc zdk&c!8JPzrw$(knRBlPreRgBXYF6+lhhEFMCqn_=6H{{+u}Bf?M{d-6rUGB5@~?N= zK#naL=vOh`uJE@&Dn%PoJ5y+Gs#OLXSQLb<0a{N%4a(W^IUr?0!C^czo=$9{dpCs2 zlQ{p^H6)3gdJC+_24Y6foTA<1%H!6NtM_@KwhdX%qL0~$8RX|`EIRuo^f>uQXUVEH za3wmWOq8!PyRA8uJqr&SNolU8jsZ`xdN!87Vp2Q?fV0Q0rhp@9(ph$bP97MCkSLK3 zI!s~9aD|BcSwG7(HJcA*7TsBzO>hP(fTh!`t~|nBghV=9WL#Clm*PBMTs~jkRtStx{u?Hewoh58Y74?XOj7%z&|R`WGEH1u@3)e?g2?( zvUE35&}YID3ujIp2frk5t(R53%Y}W8N`|tLDT`w)948mdkVJyGD!zJBw!6^0JGcA5 znL3o*>lY(%Ox^E_SPIieC{HblURsBnbyA%Zrum+nlM}cAuaHv$?|u-s0Hg~AnG>j6 z^U}Bsg#)<(jO_ydZ<4ns`4&v{KW}SPNkfakU3R7UXSV+cuDwNZ-z`~r z-Wz1KXI@v-LoHU3uW1;Q5`(?^`T*kI>=S3jP>?_WRh9r|{6r)%fQp&=bb?&tf9f*W z&LeSD@0MZVst?soP0A!i_Sud%hq#9d;3`JlBad(3+=F)^@eF>{M}n^Bb4^cQCilg| zG(z^AYsWyhp}Rd0K(MM-H4Gg^PSL%{;2Na?B~}kKM4nlIF%5pC2j-UxG|$8^0p2Y8 z5MBH75KJER2IUNP6oJM%FAHy0CI(SNy0LW~tjNTJ z0H`NsT7yT*CyWYj^YWhp{d3g4A-s6|z`{^7_3eG0H+Hrh$o0a+Suf7JCIVtV^Oq)f zEe3{xM@K&l?_N3Lo%9R}#|p%54Sp@+zh1*Po%mUkPGH{Gt$CK+1+Sb>l)MZEH-h6mc3r485`f=twg}2jx zEang}ZYAvNyYGefc7HKr5dkSF?rXF;(L+7{Lc|fd|0QoC+qUd0zY;nhVLx-KIz?|M zv>9)^1ff^QBPS&zEIC~-nmE;y{6g-5u#wh!AXZi%>$U^S-?;mG`J$n1d=2;x5cznQ z0)TN%utJ(BAc9e$7hXCF!b^Q-hNkPqB1r*L_c-;;eU~><7NC$fDvGv03P8u0-_@lC zX0(b(;7G8c!Ju}}Pd5>sE}<{dkD-=b7*+A4Wv78aN>tJ71y<~}zBO}SP)!o{4aibz2)C&0 z?);qm5tr$> zii>MrjealeFncY}w9P<95}8RBRMCr8#sA6&OPTa^yQ9+l=qhcR+1COi}VHY6=4_$rldmTsi6o!6sf_0 zJv|rIlX2+@adBnnH^&6}QgvYlRQVxFB zQP6fv1uC0q>GJJtku1fiErnhYj%pt zykS`m@6#-(O5gV{>Aj9M)gQj&MyM#&_T7JX`>wNENyt4K@}PSp<-2my)^0!*R?aF(4RGTkn`lF4j7LI+k`jy(isUAh+#s$KOW>o zYcJ9r`-c1+?Y@h=7}*To@D8SmFWVhiJvL?>VB1@AjXXVO5LN@!1RQ z#r6+Bob+B^$Y!or+aM9VC@$FNU^|SkSw4K!Sr&Wvz^@I_qYG!g5>8V@_(FkJ0`Ab` z2Z&(=FKrHQ=(<|x9J)qf|wQ1>r%Sg(uhJ(*B4QZIl-8tRMp-&QopjHX(fXfq)0l#A1LHv-buO9k@w6C z@%evp-@%6!@Ar$uo|BE*YguNW@$vJlZk)&}sudIyC~wB}=X;V zO)dBcbfkm>AdP`$7lAHq)2>^KiKyRIgvPr?O=BaLt1HP=fUKSg<- z&BsmL20WY{MQ1~VNR7I!wuglv+t3Tp!(ICg?2U4lGunS=0U~gpD@5EDPziSXo#xmD z*YY{Pu?>Ei!MPR4^o~%#bj_Ib3N}(Boxk5S9u5hkc);Yy^KE+JU2&I22*kZJ;R{e| zx^y^8-s}}d13d}1f6{%9XN8p_7uxhYEi{4@?`;(rJL~*dceu?SOcR3aNBQ-Gf$*L= z9Yo;U%5_=JuT&TmWJ3~)Wb!%t!_>N8zb;XdWmZL48b zsvm{kqe+uHB;E zeZb(#0H1PvJNpLv2LIA{K^c3t__NGC!^`zW3;9b`Va2$s;K_wZXma}~iZox?TrVfN zpC9zRp8tHe)g~_l2KnvqLyFv#uZgXn65R&dh}q)tMqQ^k<+CFlV<1vD*Lv=?PMK2$ z+ME8q=(na|p9?RnAs^4o0(V-4BqZX<=svsNM~P+Z>K(4*fjdQLO}KqGq-!2ZgLkaQ z#;zHA_#FiH@4I?cZBVj7bXg-w!q8Ijyctb=Z@tl}%aI!((%UAE_89 zxFPRnz0HMO<5RhesxHegtZCVq2V4S(b?;Ia()*WZ=ac03fppuExmhh&OTW{y7s}RB zs{T1v+xp)v^>fbNN%Y4&W`Q>N2{yAXw@LAsEm#3s`sX$kRW%4?))q#2iHx{bPG&0x zy+lQ#IJ>Sc8ouTE`jb=Ea+T(FFJV8eY|0xw((LXPy9A#6HJoftaviO#g%NNJz^Aj zm-2Q}tvR0SIE}V9<|0Br};uU7r(;Tuu{BUYq}DH1mUXQ zANMou&Ah!8(n1>6+RZb+2xC#V{9YXF!Fl-KN+jDGbpe?qsE@P@kzW+THHMmlyr*5l zhd@1=B8Ca93valV!0n+a;;iaez4EZ1^P{+O+r0`F4MRgm#765DZ>4yE+pJ*(J?V3B z?|VR0_Jfv1Q)&TL72xA7liN+v*TokcT%<-kM&hq3C!G!Ao}JNk+|}po7l#+^_L*6? z8^RD-o*J;p=pj6KJ{YnITvg(3Yj1Q{Zya7;~XjKv+kD09+P1uHX8P_wNg?#kNdT0F{4QLHL|Mc`hr2ce}wR8`&-iqKxt%XMd6 zKg$LxF_U!$>vE~x&xU=+rr}i8@?VZrk)d6%*rin?Wt@<=VU_uu#^F%(Wh*^G|N86E z*y@#AV{lh>?x-WC+VW1Ub)U6p*b_+YzLfhwS?p^iUlga#wcqhWzfmFdiV|I<0 z2@3_4e-?%lZ|93gI`at}gM`UPzxbA+bABTfg?%&}(v-nEtMsscc_ zk*=={9>{Kwd?YpbGuKDOOxksBn+hG`^Uoy!4~D;W!FA{01uZ607F@giZuOw~FpN#$ z6^4^|p|ZJ61iDi0LrEXT8S%s%-~3WG19u@_eHuzODzfPlopMs8=M!pTCWLPgOo$rd z9uF57M~05y#(wg$Lz&aK41W@)r%wnA&wC0>-q(xf@IsryzfG(D&X*p&;elT1r)EUd zkHLNtP|1miH*cBh1t#1UTv|!Fg}=)~fKTX;2pI_`;?^`4y9Ir(5MmDFZUt<{A{|(Z z#Iqp+MDj{31Nb%as0P**HP`}~Cw`nSo1J$&SDcD^sHmX%EuZd$+y2wUw zxh4#pYkl8sU*IQB5SwZl;SzcRpe@ZU+r+b+q&9-F8QuU}t(Da(T>h|6`hk6YX5`ye2n!4Mdgq5SK z0su*^ASopZjqa~@8a*LXY)J?l$j-TLB6HgnhyvB0Ma+V%_2;WW1~VCEYL^cFi!p*a zCi;=}Yp;YNlyo!k5A>Kd59DtrBxt@2A9I2hb#s}2d)pIw=MB7{&ReCEskea8AATx`GY_!^1HVNG87J!mUQ~@`Zdu-u&?#dz9lI%B$5`*t;@qt=_+&IA%d>c^xvWa zkKN{vSmr3vn91do*;@OOh7Cv26fNDs&YRBr?cQZFO=Mc6 z;>Z5Fn8CGniZ#_>8*0YdtDrNRyF1H8Z|L-$_oFv(F?x)D<|PMu0Iz7od*HXn+D+5z z`bH1y?;@Z?OqmdS?x&03%B`^;hl9Iql5x?%*7*}f^aaFs?T2*r(|Be_KOsPW1Q}Jh zA0!#i8}xlH`ilfn2nl6}PHXl+;FSOE z?-U2-^lPg=gs$yp47H70R{lQqTOKNK;6@*<+hgfyC?St+*QIxu2hRl6gP=8%DAfbR zyiV|Bw2W+o!D`$_^#@Sv1p}&X_xNMdHzdH(AI82Jv3D4*;L(h@du8rAKhULt+{;r%v_48i7mhAw5 zwnt0vEVX?S)23tjcRqS^&$JWfLe1rYJyEFRc*u+adPq2~QCxIoxa2+ou`xOfFj^vo zV+3>bm!XnUHflC2j(JSDRo7%1>gW%}t5qm#M}xdES`FiC7G3-MngyHNy1My(-H=D0ikW(5<1Wp| zc&lypYky_G+-Zm?%FxFBxoPJssL1pA?s5)iW(ma=9}DFT?`xiGNEfHr1~kQ|?>m)E zh5Ch0??!Z#gbATtoC5mbT88M?w%KdlW9KJB8LO!J39_6uN5b|uuUus zqSZ%HEQ<)1?1xFUv>+!BLa17q7rlpx3&yU>fN1~dAf?f++Gd2OQ8R1epvpc2mKm~( zXnS2)vWTBRG%qa?UMjAYh`Q3v;)|DyClz&F#KLT5uuLBkW-Jdv)`wtkCigoHVGs5{ zp}l80nWQ}rAuQF47FP0aKgo%{*K$vk1qk5uASb zFp)MiLRfCfHBZ1Hx&albC;U2M=NrI;M7q$y3&%?p_(~OXkz!$*5H71?30^@c)IdECa#F+@%56*O{iOPn^?xV0T(g|>}Un9?V z+cN5_&@I2)1rj;|-mN&1h7Z})vN-ArYY*6H_1dPlI^Y>LLBQ4TbZ&bIu4%$ z#9(3Y!JM`&4w~KoyWd6KBFwSDK#S={Q)3L>b8I{9ZPEKXG1snq{cOev??#WmD*3L4Lyv0*Ps2Ss3LyqFP>buniFH0Bldd+bI36pUF*3liJ&#r>1^aXM%k5@jw~kFsI}VJZ>R z<X6Z{J(>1eO1R96rY6I$#m9+3NNrTrCd5#9G>5ZhnkOM<=lCn7-g*x2`CfLJEFqWJO z2+f4D&;p2LPXM^GCZ4qY5YhjI5S$Xa-UWhhZU1BtT;5k_2H?CS2yO)71qf4i&oJmGOdRhwAgGy{N- z6jXIbaV-zXas|SOdCDUia^;h-S0C1dY{%|InDB+v*!Iln^;~b1+gHLjgcH1xK%bi8 z24Y>A1oY_wzrKj#zZZnm;1u+>p(|{~=!Wa@R+^Y|oJe25TvXd9jXintZmC<}Es2p) zE>F0&s6kzyazvQyi`1u(1@<6OdPm}`2IS9}#tOkK#s_~GOUmZ@{l!MO!8!uS@#aQ~ zVy`PMEn}cPdH@gU#2m#Yk7zB>iDeF}(Y9XU;uu-f5!w*q{_8KlSfoNr ze7~MS1lMP3F^`C-Cij_<6lNfvaMWTiQXXj$Oi&(h-~}B~Hn^H>oRgC(4yXVhk-7P` z@dsjND#1PGgAubxNT(3aN%|F@YHLgqgfV?v@>8qb_EP=+w z@dlAXk-jt&H>PBjhkMdFR&&4tk;icwN$+Z zYZufBvA$$9bi?1J=i?rvPQacYxQw370SFl%G5{|xzhml)H7-Mfao+(Ce|Fg?U&w>T zViit8cg9!4_f9ZG*EO*aCb`v58>PM&{Ck=|{-QN&Xe~%tj!NLFY8oc=@bSm~5O;M8 z<37(~2fb5S<0PIXPTBn>B}dxdHVc)kGE@LR#fh)n@_vX@CI8!Mrc(mmATqY>a_Fh; z!^m~jzmO48f#vs5_Ppct^lT5d!g+mZSZpSOk@F`K(zJ^JgXxE1I1HBGLqRNFtcN?# z@LY*v`_|MfhrQW_$Rip&Lm!hZ!JhA5*=@2j>iUp&G5;}1qx$uN`D~~`xFp5!t)|6C zSedE#lop7F*dJ+QFK2(5WS%(NMIDvE>{=3kDn-Wv@KCe2;2z`1PjkgPS^qa%Ww zg-N2=WtK)$!D&QU8GodS+nqK#cZVp?=lkXEB+TP3ZR+!FdhW9p{j9%}csdef>nfg* zl!9Y7P*`1dA{K>~r9E%cnCa+Hy;-j%wx4GNdNbz8roCMXlxjvb+WY4_5RtgL{s4au4t2LISDuRcI4I?Z@uV*} zoB6F}cyF5VLzoU9cg@#{ml#>?H@qsI)wyH?!k5VSGf_=)rYBMa76qmF_ApMK3Q>0| z7N)BpZ4QypM?GI|g8(oXUc(BEhRBG*9!~aQyiFTjq?&B~J{FIx*Rn-|A1SZPog||G z2MT>w%)@rphI?0S$}pxKxv9V@Qei7ge5*`ufq)L^IDel+v|MN52GkN z%YDoG{V%liy_y5!o)KU;`bJ+-SKEo5{W$|0o+y`8;m2+ix=#HOByg?#A#dKg{)<-_ z;jb4O`ODRemznhRH8<2#BiSWBIv77}d0w`{vn4Pr(lFxUZuIv06zN0zuF;4y!`*h{{j3^k+7 z=z-2-X6yBad!golfWm_wR@1e( z>m?F`@kK{96*m-aA`%O_ycoLB>w0vj>Br>K>$U>YMqSbiH?9UH#N58I&&zu`+6Dc8 z?7d}JRnHqXDjm`w-60^|9g-?iBHb;q36b7(cY{btiPGI&n+9pvG;B8A4Z_)|zki+g zI-k#n_qzBnYt7osnl&@e%-qlY+#}FI!q(-?&U{sF(>0rVxI+4S3=+b(swB$GX1CNQ z#9Q_4+(_Hm25&2<&LH1*xN6kzk_>3t<_E3blzVwf-GNC5^e1t^35Jc6gquXJ z$yC}5B@ykZv}5OpZr?_}ete`jJhB{E>5fvi9I$0Gh+nrKaLVEcJb?0EXV2WpVXPZ5 zX41YvUx1JajO?}E4k;dx(1g<)KO9GP*<5}8#h(t3+Jk4`AkzFx$*lolu;fVR>Pyx4 zE~U5-=Y3m*967A_?`Lm6D+H~f$>PiTaefT^NdmOkyuigUbS&eH4nh2QyPw@}6{loc z{Z_e&7>#Eovi3)SJxaigAjeRG@_fW#vNnFLHh&ov)PK9=7*o_t$&ViQUPv%kwzr)m ziW|wB00IyV<8};vG%S(0U*Y47Php$DZTzy}k@1QiN{)GBSq7x~ZJ7JtI7wCwAp0hp z&*VO5zNQZROWOy4IXm?q{sM!4`3qEJP_({!gzaY>0TA1#z?J@N$+r)`re#ZNY~AJ! zC^GENnTn3DZ*9E~T=ld=;6;i}UbiUvR4;wm8DImv_G2pxq4qniJ6u{laON7F`A@(f zBr|imzr;OIRl#aBI+SKwd*!~dY+Y1&304~w(A^n21ScSETbw3q|LUq@&0d!VtLht* zp_uDB>$gDi7`n|WAXe#oG|ON5K1_YmJ%7)4ko$9VqD5onw&g7gNkv~F85ux-#DPWU zoiV}>>)d_a;}RGHwP#7A3~tI_MB4jAj!wOd zcdG0|aJOr#I**rDK`MdfJMoWKqT9KjWYH{!dXZ)MS+N8yY|?&3E!5?!-u&Cfw$I7? zW|+!F9sT@b7$`qW(|Y!2w`T zM%$*ttU%9)VhOo`xSK}GY@7tHl5BjyX*9J&%P$tQ*Y*=8!;PyQXCb}R=QncW>PH+M zjO}H9;BSg{c#Eo96c`}&kJ5QqS%}zJH4R9h{C4JUJw(^GK$F*W+CcQZmIS5*&?7fu z1jEmzFEv#t$RdWd5_yXO(57o##B*2$evU0bB!{ag)(J8HU%AI}O-#Ye~-tC4RlsVh#33ieMn*YUAZ7m zvjZVHiN7~KzPX9j$L=fADw4}gwd0D!klhG#IR?G+p8JFbn0zoz=qH|oercK*$fDuy zh7LZ998R3*U#=ZP+?4=|jF=CRpH`~M_NANQg>UUjFOF*_Y-J9MT47AFM{O${!SmeC2U9A=Vv7 znh5$3#!?=W0|ylodh$RYwFciqKJ84G?wsF7xa5tbAQ!h6l7N<>N(~?upS-`nb@{L^ zC*qH$8elZcj`2$P+wvM`#;A`teXLA%SjjC$x=FGnfgIjy92=vq>temA-(uJahZJS< zU|c)=yEq(@d~>5;!G?qGmxpiyod2vX>!pdvkcI($j{uB>CR$ACl^yU`2B=(=FVl; zU!#cqA(^3eO7~?i{h)ykG}>WVb1|A?r`1qz+)*oX@FtE=BL$q-&F@)A-Sw_AWsQ>J zRy3m^lx#0J6)TijW5=%Z?xW0m)Wd6p&dyhP;+-DfZWk9Ds=nK?Y==b)OaPBFeLG8H zeMk66+f2=Ak6z=&N}jwPpKf@ZL15zr9sV$vkU)gV`sk;CZ}bC*nB8PJmW7bLIv4e& zc=)GqTHuwbfy?HyU!6&5R7;uwxFbVkF`dRU6&dP4JgV^(e#mNLO{+Gd56_n8zOi@8%-7RN&Jf%@k)xoOu`D7cA$5YL?E1=z|A0}s&sc{ zw95x6E5>WjA{Iq^RsJ0jAHrO}%S-yX5M%CJ@vHU=I;xq| zWU{Q{4)UH_tLKiYjJT&g&2vu)x7eMNUnc{5U3*QB2iE$Sl9hFQPYQGLVOv*M_>kzU zz0EeZiptx=%A6he+lVkUmu@w5VD6q1$>*vcV*RCA{KIx%2<$l$Tg*a`uWcuvX|A7Z zOVkWlEbSv`Xh*v95}qhM6~O`c&jeh^z0QRIJxhm2zF4fUyAz?KE!aU2eM~Yq%8MvF zPsr2KQcNdGsqFXPcg5HMG&Hn6)QHOz4*e=kV(ly6S>_F)&yK;;TJP}66rF5ITrdC5 z!cyx~a;~j0qL*ga_~a!&nXUbiAoTc+T&iZkp>m3*P{o>&Q_!zw_>XvYDaj6Di@qN+ zmRm-efMW*B<#2_eu13}7p#`_<{%<_7PotXQap}x29OgW1MCw6>kC?lPsoRTGRNy;A z+MrhDopj-tzpHFuAtIC8UPx8KNGPI9q6p{P?ij2)92sFm8h>CU?|pPnGXd`vD@aKQ zDM{wj5i^k7@3g{`K+i=43yT^TtP>b2lPeLUnK?r+#Te!$CyNA zs^lF+GZppe-;fU;4M*O$WEW@Ofr6KBHgdYwUSmrK_@eliH@A5wh?zL z&nL)YVi)q;*sp^l4irMcSPGS1=K>~f);Izzz}xAgh`rpTWA|a{GaEQ>y4*qaVxWhv z(<;NB6ZfbFaZa>%6Mb>nXhu{%D$56 z4SoI?OIE-5Z-0ISi!u+s3zu>p)-E4-S236(41Pffs2$REu+PpPt*B{hrery<|AF=C zb%u`~NW9;oSl=kY@~x}@#T<{@rQ#=Tpf_vRFV92bOtJAhu8|Z@)~P?JbTYMPqxp(n z_B(0$OV$ts)UpQeSaS=dk7X|f2D?AeYae(*{u2~V(Vr+uU#~zla7q%3O|^+@m|5y_4VcbRuXP-tNH*x)foi?Ps;}2QCceGN5lVIj5eyaj|9tydfB_*+ zq`6FP9l~{atj@pPQL1J%d<$2Zn!{5LATg;&``k&THf$b-1x1VRgsPA;(gQbz&k zukQO~57s@o{s9%95QU1{XDEm#^v+*gIQB!osNP=eum58ERIsiX2#>;}KZ~wyz@y ziX7W_WceGSP$5}DvnT-KOI&Z(T#p9I+mA1qZheeA@qmcaDEi(F+IH;RG&2eut8gM` zMG&g;hn*uXtthJpZ1YIal9^!cJ2xely%6l)8S+3lbe!Fl3EBYyy;Y2A@IsFj3U!w{X}YAqSuu>M3_QKpIMZz%RUgK9~^Jj zO^Wm!!=8I#`2*m{_${<7dDS#NdSXOEw#7~VD6KMWCU7S6Eq=bCT6(9 zw_HC+0I!b7Cj(<7fZZ!Z+*At9=A-8yz`!AsM(7fMir7pGFT2&x+Lp6Eh8e3R$Lx}^ zg3)-<7f2IqW6+N0Gbm105nS#$!DC%x<_&oGwk|_9Sf)Du0=l68YH|)g94lP zqXLwhExV<0t>S264L zI3dC~@y5PaylOharisLm+rW~=nn!UEcW=RJ!-90H;;f1?XlvIK*ORib&Ens~B_wQi zUUik49@OSMWN+1Aw^AKI%rl4~Jj7jvdp`>Hwl4M$cpQnho0V+JIiUD!!4r=wN+myE ziR35#p+O0|O}CuxTg>n2d#{0vx=e|Qfd)m)i@Rixje{w}F^b>vHl1jHCm?vDrPI#l zGXo>P&h+Fb1rQMx!c)shDFY5a1KP?9Af*JTk(YOPqYZMSV%G;m?}U8!aL7i*AL0lf9k82BE0X_DL|HJYZx* zA}A^22!C$BuN}rvCt})=Asw_}lz3-*jWmBMn|Hh*Ufe{(Tr9Hr@RfKnyn2HY@bZL& zOPSu-llfJ7D=+tovXW~@zi&FTIHp_+Q)a9fxZ7*$$ewz!&9zLw+>YY?voZ4~Bi4W! z0P$wPHLAN?X3LS|kyfv;V%PDI0LF;$ar(w7$=gWQG^_sXXr(Bu<&0FuzDi2r8b3+T zaC2#OZ8wy(Y$%W&Y53_xMMqWJA%S42DgMe4-pRIHuQ%%*hGemSgq(4tHEUW(^j(%I zqffV)5Yap0qfP3Ug1k`@g@C}B_6LrOx(VmJ9&tAg=HGgb zfR@sMze+%%1zN{c>o_pbqG+I@70V?10DxmW{!ky05apX^yX7OW(aJuHkNJ4iiC^1G{Ahz6+vq>v& z{U1L4N&?-A!mCQ-aMJ4y-`%&1Fh<~Zur%3UAT`W)#?MlwkDWI?i2nykDE&@J8BgVCHRX=@Dg+02mS0YrbAX=ex}g~jyuL#4R7(O~raGoPh8AnI z1;x7yZ6}!*AD}Jt#()DF02ud7!5D%k$B*taa&mkqcgRRmyjg9Cy(OG%LL=*s5G1n2+pw1o@z7e(jlrBAjNC zQ9>5=@*(?HOI88BF;#h0)tb+m4lGZ5(6kgzZ~31)=i%RsZhk4WgHplW8$Cv`{AC>@ z_+@2RJrLd@lZ#L)aRtU-=hfj_%3&{tUjO}MhW`cD(P80<-pF#z2`C%yIp<& z$PW%In3WM=U3ATL6gV=467h9H&z`DqG=Ga~N>>FMEr}*N3nddE=!vr~Hd79X7(J;= zSLHm4bl0ck$W9rApIn_eGTSI{SU;!IS}Hn1zjFGH-4m*=bbuj?Qe%G8MXQ$)PDl?q#GZZOM_G8^zt_QPh!+;9#;KJnCcci2TYQ(!6Tv0qlrm z@4=R79DwF%an`tt*&_InG5@qpd*tI&+e%M+?E`OWK^E)z3Q*y|j4s)f^PIbKyQhZG zAz2}E_#eVn`!>Bwc=SUQlLJP&;WzzvG9T&(Q1ggaqjPmZ}X^!3beutq6Nskdlw5QFE1 zDrKvAXjkSe)F=-%hzjc=8`xD%cvZE0_igS3f_jNMkJL9R%4oVI ztSkos_HhCNh}k+`p<|)UVcB=s_}58ethn$1@$ck~9ep!yu~!JVqk&g6&xuGZF9r>R zlUId-fnI7AN{&J94WdI{x403VXhv04*%m4zsA!Bshq6gWe#X3Yo>o<=>_|Au#Et}R zrIc|m$d~Yjncm;winz4TDapAM2XOQrk1l<}C%vZ&+>exh(?_g2LA36^MPN=JeHQdJ z8rP5KHMLPv#3`GQ(471ITA{=Hj+aHO`)@c5w2AOSuOrsP)`v|A7|pPHU-ug;bj;J9q4X6xRQuR**d z(BhWAABNYDv+Jgbde2+NTs?HH#hhx~f6b!b;?Jg@Ol7C`@j}W5HRM%wB9X4kYUfz% zwt{Ch%`_j}X2!0_Zt5e8ybG{3(pEH_*gV6r-x&RLhBvS@S9ANQG9TSm?4rkJA#H_q z*0yKPz1G1v6I@rlO09(dGZQtqrFCSnRI#>U^z|c0-mKxv(C1iNb6q!mlSz>`86Lc{ zY0xKdX!Ou_*>}(W%#H5T!=)i<$g0nld$j|EaLoKRl-PbogAuiBQv^ld z?Q5oc(Ic|5Y*@x#V%oaTZzgtwPp@QsZ1xjseWuEaNd&&LDMP_`fj}E;K+U}R1Yk;S zs$SyX-0HW6o=uBc=QGp3cN8J;8u~5WatjTUFf4c9iNVRXmnXNR_DBBQ-Mc@lgkzpGC%kxVdq;(;X-Sv?E# zYC`w?p?J1SA-v))CHLeH#)A5kj%S;AVT?>j(;Z;sj z$|~5pA*@Mtlf9U+QybJp-a4^hi@-$yMZKtM&Nw+nq4nIdT;ChTRlP8pi&>!m z!Io<$d7^i#?Gd*4Y2p)$E@vC1a5{&2t;S>KhmL%rxq1@l9%nGoPm~0h-ArvljFa-*wCO@{Pvvhd(d5` zXRVE{zf%CL?vemcH+@M)w2yqv^C>(*G0uuwOL&77J97z(zdSyUm`)4wd_dy@lUG~1 z8CyKlQoOdF+@NzUGpsO9TSTDG1eE>4)R?ffR19h;0$G>34Z{m*uDM(mO=P@Xz*J4)dNH(}M}!T9f(^dD*}cA|DE zwHeDWbux7k30{7*)90Ad`0MIsX7Py)BXqIKyqT|BIy^% z$<7X>muf~GboGPF{`msHkX_c0pD!ec1;>^^0XLpZJ{+~FZFRkOky^(&I!p2-@|QFa z7y!O^48px|>}$FB+=(e9$HVR7+!eq76}1|_^)>)|kK(F{DM4zK|LXbUCSc``cC5B_ z^0_&|tZoRt?b+36BNngjR)E9!ycS^jOJXQ$2z**%duCkq)r<$FuR{>A_ zLZHRo*Ms$zHRLK$?=EL;_`s}LKrc4x2aTJppZp%YWrM_NHP%TsQt5L%HoDo+UalLVgjxR@ZUbkIKz5NU@h{~`2ps}%G@y3ln!SiK-p?q z{n_ep4PO7oMB8tj*8&HdrGk#U!>KdZ%S|Jt5M=Stkv^f*Mmc=rYcE=rWeSjU47z1% zl-V>j_%_v<6=*Mi)`!K)EO|#ca&s}=XF-$>u>1sSTIl6yL!qum#4R}y&(R>JANe%R z_C=LEXH3dCI0tjLfWfXHAe1=TY1c+SQrPm`L4VS7!z467(IFx&Z!)pzN}8qubC9qjc+!KY{{xux}_0@u$K-oSLi z?JBR5iHdX19RhLi2KLEPH%Ho<3z1T4x^$+?YUOQ{y|^$t6}xLNh?Z)OF0wN#Bp5@E z^$h?hG&;wPw>(|>`LBQ*T4ua0MM*oZ0O5UKi3r3pwP!<5z^ zel72#21hx}f@tW~s%McNEbBcP_JfR55!asVGm*F9yUgP=T`E^N^Q4;_KCv9Rj1%8L zgnzON2@?>7atczFxr@q%f;`C|@M`TP8wfbq{dhW&B*=wdhDf2&_UIF!4Sq&!!;1#J z74bK{niZ~>cYn2G0gSZuKdnkLcR+ za0vuD>zQMlS2{I&;ZCxG-sC0K1)X`Vtpo1M<;&w8oJ0}cArhY zg$m8_ci1U5Y|o=GupcE- zW&5uF!0FBOyrL=NKMZIQY6RMF%$CIxwe;=6_uoY)8=Dxq#WP7-?oyPSM#p)a0G+)^ z#NXmgpAIVQ9TYRie)_OoYc$2}nib=sl!D}AqK|)?uk*Txwu$GI5EZ}r6N`2eMwhf{ zHHjOrifBG(*cF_36!cmiaisFNKDwD+`dZPiv0$X~Bz`!VkDC@Gw{XGUKRWIJ^eAg{~K#=Qu>NCxWcHH`3%HjL^*<43hCYFoVYu!3Xe z>+GrQe{hwwv{2yh@HD+e9N~bMAA?hPYc`X2=u-F~(F;@D{0zG-0dFWBLeXZ`AjBbO z+7B{vnZFhUaj>~8fLEJVe0+(h+dTIVk~B@y`$UL2PHNL~5u4IK9NDlk*Q<~>z>i28 zi%vN6BnzzwN=cbnpfiYO(jv+dhcm`q&|mmaq7@75UZ*%rr!`zbglP8!OoWg!;Vs=k zK-~)_BJD;Js4__mf$$-6*Q(o@vv~#nIC5DKhxkjOzP0Ww8m$wzGh;mxI9AQ`H7&D* zFv&LBa#K*Wc-^I~oA;KsJ5fGLb}rPbf{wVH&JnG5TeJ~F+8q96gp;&pG@YqVv}BPFNi~~>L~-7G){~9Y1JU!o5+EVd%@`c6UlB`R1#LJq5aEQ zq{T^il7+tHf2xq!*@NQXveW|N7hmBPUISd!twd%XIoidOi>gh|te^8JhZvNQEy+8s zRXMoaX(Rg}Ip8wlX843Z7oic140~nDKVS8VDgr_*C>!}kFjua0FYc0ZV^H=cWhGK2 zdsZ^{RmD?rVcG}L4cRDtO699eKhvn*^d*i>dJJ4h#^}U1loKC!N_=BQHs_^qMR%Ni!tmGRt_=o zWU;-DJrB&6B>=+O%Erl-KfQqHJo;mL{D>WV!Ns;v6ZqTwU$mi}ghnMoNi3I+3Fr_C z@)lgLxiT8eVt|F2%gmuZyhv9iY1NOV<_Ac9=QUyMl(uEcb0EeVT#dy=$GsDRNG0xf zquz&y8X{iHk&_}N8X6gH0LfS?hWqg4%2kezT4y;rJ;*LFBXFoKr~%~ZadZaa#f@9I za-Dlp_X=IG1M|{Mo}N~CBb1L$g_UtzkQosOPt$l=cMB~l!ni@0j?-pdr{ zY5bS)SRB@Coj1)dPvyehE}T%Y?=s>$(PW7aVtA)*$WHX4O??6(pKR3vx9@`D zopMyZf9+!TOQAIsuT2d(uH?Mk8gU&HMF;Eh6~M zsy>5C?@l7)Zc!oX5!gR`DAZy8+lvcQo`~E(b3iALB>WNFhOvy?hCafC*XSAWR3`ct zxDE{0ymRp++E}JXg=fS?q=1D9m_d!9Z)GZGx36W|4 zcU<&mtn2W3#wKimE}y(wc<=({aD#pf?FM3R_SgV3=%VCOH~8I!TDz!VAYpuL?Agfj`0MOfy&`B^~mGX25EZzcw~H1;J~k&Tg2;aBikG7=L|eFeMi+M31t&P>XMelgOQE zkCQuCl@@_((vmtDRsZOA8H^+td=8WH+5HX0`c)-K8YxFm5OeqTc7IOUur0YP&@99H zmllg#zN7lScN#aK@*2U@7V1aCZ--%iJz?fodZKLlqu|HK7vI|Owr;|HwBe~V{X^2j z!1?NSgbb5tK~2~!ck+5lei9PFe+}0i+M-q9M5_kqk6{%4kwf>yBTnx47}hiA2v~R|Mj6imY&SJYp}j4z+l0e<-<;AqnTvlI_XMAItcj zXd8j6lGAQ|0Rc)>K&J*pFB7%H@X%D2512_w(_@=vzw96&Q5g}L75wL4QR9_~>y=<5 z>oKB40+q9{8`jh4xCF_Ok15#S1jOtR$Yg$1fy*7^BtHn@36hdsYdREG4Ol~w#X-j- z(0tPgayY;Xe@+~^9^8o$OuYu(4KNH2F&d1$Ux!c!j<_rXi)b z`{h9-D|H;`zE!Ouc&aLF{2uKR8zzdFTues?leBse(xWQ=O;=hersEW}D#kSVo>4r5 zh{w}A|Kto0|Bo&R&@U1R`HGD$Y}us1;vdxz^37e1`yWY#xw0!~xGISK+onI_|2jFp zlEH=3xB2me=MlET-IJ5Y%fS2y>Wq30-!Z*dfS$7rO1S<%86$<=;SNaX-ZNFI0JD#d zDIfdj-E;XjZ}!$_4C}BR4LD8$JJDr7XX4TTh{K(p#L?fzrI>S$vN(`3WAP9BW#q$2A(>OROTlWEv0DcY!e@Sew4ZJ1etN{MGmdBvPU?NY}qzNcj=UOcpqgv zTRnYAxvXXyaoROhsQ`G|W;XWiWKEPsPit>JsfFM;&d*|Fx1Yht2Hn1nmR$9>M8}oJ zu7)=?a+=C@PlN)S$ig&xrfAz+L?sRw@L7;j@aCV03R6@Srnx6RxcA)YYtng+5_J5; z%?oO=D=ri;{S0$lkSg^YR>9UW7LW*d3DbdU3KgA;Kr?2}t7MK zQEbDcyh0|J$L>tKg$z1`C#+Yd9KvbI*QDd1O|zhjM=G++%3EC2+UEb2pfFKr7sf&= zZZrwIE|9QRRCKOof}OvtrN~^@^`b4sih+($+u1a?WRS#8R^f&1if<+##yrpRaAo`` zTjhN3^CF8@`GK*i!}5QC$2~MmgdbjwW88MFy?Dan)f7|DY8_Q-)n}%3m2~{o2^DK{ zu5R^6Y9N<$cMCsiD}_*_Hm%as@a#tgYUZcs837N4h9vO-OY^uzb+g*q+Mi#nHMO7Y zyBB{O7IsMnzu&7bYbM-TKD60y8foQuC9}kdBOP9;jQWU3o=!1P-|VV>rsXV zFW=0&QBmL5 zrx=pm4+m5z1T?kgdb2eQ^eq*f#*59nCN6fifJOFznqFu>L}VK0ZF#D!!oDYy3+2w8 zgNt?DiL1sv{w&5vTT+|BeUtKj!~QH3H{_(if3yIE_rwz0HjvuH^p?$>Aq=&7D{w`Y zAM#*p>L+lB%D-L9zh@Y60DKJ&nIL_Lv54DuIZdq&HT|YB{-FG; zZ2cxlrN4y1f;e2^WW}37Nn1E|LaVOu!8gW{)FV1Zu8L%q-o=aQYEM)VSVB*!_sC#@lJeL)l<0t?kcFm^W37B8*fh-!FQYu${(B6LQQevY1}zu~4%HxPnU9t2r$D z7e-7s6V2w??Dr}{(sVHj>ijeKYCRYZ*7xaf)-G9wh~iE0(R#GU_`3xQmWcvNTt7hZ z;^?ZeI7gW(7RW#iXq{E9Xq+*k_9DWS3vQ$SA+1*Uprf>>(oS}4?WsB0N(FKuCk9iDtnj%p6f!jk+i@J34S z%dVjOiNg8$)mm4$F1t*;mCk z53!n6+$1FC-KB+%D?I#Wz?#LZUMV)V?!ptoWaC^=WUub3{J#-3K@Q6gB)jP#b8t)O zmah2p2Eyf%o5lo{>aX+sI&HZQ9v9+$QVAE<3zrT|f$h)S(&u}PcCB!}4afQg*+-x0 zJDvIa@UCrqVWR~HWn(TtIC`MWcHb2I516r}Ny(Z@DKcwoLb=fyg_ z=1Z4C>xp|;{D6{<`~0^YpkNy6ULl9T;B_rzc%;$>1Ztx3FZG_}bHm@YYE^Y{Mn3Qw zly*uYw=FHtqIZd{;c6Tp=ipg&ex^T3LJHK4G%svw^*O`L} z0FX;srB5I_S+nZ3f#mcZYqaM^OA3)*yg}Jq)4F!58fvnI=Z*CnBT8n~i8d83UN@>L zVg6pOt*LL(%Eg=AWiXM~sTl1Z zLM0N)Qqx{Ve!~96{jV*mJPN! zSRIoH{$;DW`hjc@r#G-rcsg8J?!f^fKyC4l1Syof(TWp8?`I`wCR-TQ@uT~_T+DWc z9wW53kReAqFPhEudJ!A+JaU~zHmw>~DHVsXWMPpTp^$u8%RwQD#yJ)HP|P)Ti$#;& z6GpHeqY{ltzDsfu9i8yJF!q~D5*wn~4HC6QoUdmXM~Cz&W&*5VOj8?3YAe1kXqcI5 z*56IeJ?+@EOZy_eoRlbzvY(z2e(oDVy!~Q%AL|#|K_w_09dP5!1K?f?r^EM~cuCFs z_3Da2c5s4c7#v+|reoGvx6ek>GwzgOmFbjKH^P7b`W-t@jzLueJ4R#aovDteXH!ql zd8lkesxEBxyFlXrJD64B?OV}&^sL_;$KsR3!mj~;*ZDA_SbTdlg^1EgXz89M?1WNH zfRqh|8(YKmuMBBxkAs+6if%4Pu9)reV7{2SUFkLxq0gYeDo(bynI^9x=lrg;(4VOP ziJz2Q*;!G1&RR#!gNLmTtD}wDqm82DOeaz$uoQRPB}0&o?>6OIqzTLOCup7~@z04_ zIl3i`;3{k_Kr_%lh$=dr$JepO)lL^dfWzpQEeqzmKjq5ixsoY}FAxzym0@v){RJtK z|9~l$i>Gv>lZxeA+G;FIN*v*n{E4F4B}Q5{1)H&zv54 zY1b%{!$kjCK|k-;?I}iG!S0=}i2RmhUwwkie0c91&6zJiAW!Nb{pgSVFsXPlCJ9zF-YX>*rDy+yKL3~babSnVIela|;G5F^yN&p-GFGY|vvnK` zIscC@<`mcdu)K8LKC7OAa<7nT6z?}5_gZlWK1j;6;9GH;6fcgBlu46dk*_XesPoQ; z3Ux(D5`}XiPLnkW!Lt-51LNu?t!EZ$0_^6FHtBW?=U+*6P~`aN6MMjp;k%P6j1}P% zZW%Nf82y=tEtkVUr_F`igS5+~Ay0d6`NqRr&k-@G>*1_;)?t&hUmisnsZ;P1MCvDS zsFF|MaeV(Kzh)yc#qts`2E6=_n}3sI(XhPgb#>E`e?9*1hjsV8Bt}c7>ozeaI3>IX5aqAx+Kz4By(zIel)BU#w zo^t$$v(MAaqsZMHi&#^^?viqCr;%qRo^tFy$6xghrv-qvZN>Y$DH#DA{o|y`i_WV_ zmB!aE8aBh-`Od6kCVw7^F_L-K^~2&5C{53?eOh&HTtaPiZ{mS>g&+Ag46($h$!?d} zLNwV1^=G&Ggs#26)0oxVU3~`%d?F{I7~T;dzE{1zA@VdoHTpE4S;GD4bn2vvN{7LQ zy|M5;If;0!JRye!EdmE1MK%n6{D{SeahLx>9w8{J{~m$h)pOMjxIew+dlanu&AY{6 z!Y+-H@raWOD96_NOx%y!v-+xDRNz%<@ zW6-#&3AlSvu@=hie2|lLBL8d9e5)rR$9|ev>{qkxagGC2XFz{ypztx?#QJL3^#>#_HFYl2R5 zxl(AzL`B2EE7f-1iPuTaUKvxp!JZ$mOmZOBVz1G6+6D2n%CSEYtF*esHd zR&QrgKJNpUyx;H?{9}~HaA9`wQ@6Pp?qi#LQ83y_B4XIHfh15hSdWJ#FP+CW>v_0# zhVFsg(rm%50efP1#pLr3U(>-Ass~F>#p6&+67sE-8bg9P&#m&kBkS3gmY6q1)?6Gdkt??}l+}>OSJ#;+G zVy;rqc8w0&FE(h8obShXSfW7UN(B16cJ1OAm3AK≪khHt4!C>F{WF@AMsRO4)B}#ikLV~ zHR8Eq<~9Z0dVSrsYnMQ=sB3oEo{b09_o{onyuRKOg7(z*^G`Mf%@C8hR;WTx>;wln zI^AWz-!H%Ac7tn;&tKAoNoU!Tv4a?6gJTZj(mF}m=PK2(Fe%Y(>SbNQ%u3=yvT5iy%(ExNSXAyRVc}GV*%OS zY^9vs&8&zVT&q;ta2Ym`erCyc$LoEY0*Pz6g-o-!zh_vNTKPTC`eD(<-aUk1>Cz4Q zJx;cM!f27vnNR6hQxrDU@8?m|j`mx!;w(348@}rbC`UjpC6-yJmYt-;35!pcJQS81 zH=Z{*CG`=>4}jZG2nYx7+nSs1rhJP$%#C)PDuJg0kiA8PjRh8(^>=Y~h7NwL%?+9c z-tJzr#lv@oYKswe$(XB(EDxtguN#gp1|ej(otsX>>7K|;yx zMgKwWa-3p*+0jOKnKKK9^8Vd%Esb^!KvHATEvT8V@zwnxomVAvB;cdTRjJkOmx1fm zrKQ@N#v_Kj<66OHfsGY?%|!Biu=xn^8iKv0V5QurKEvMc9=0EQR@!U@{Q4CzN7dR| zRsC`KY(J^QW{<@lW;*(>gJZjW=&b8bcLKm>NS!G zG2Gs7x#n@)X^<{!yvHbUOgFriaHrzfR==@U8f^kCW7s%TvXrVV-RE!u5_qxCs+aS9Z#ez3xvX}lha%V+7tXY!JV6t|8(Uto{WjCznuS5b|(IoyiN zmN$$w{x!_+e#~bopzoIRP46psrcUqToCG6j5VF5yTX`?X^u%t~i-~}1N&QQFs{q8` z{j^K_9BR@W)uO3Ukl|j@De}qyH4EmeTO!or{79i&b5*i^_kpHHi1LZZt0h%R>UpUiI# zoU>>S444mYoWzx%>H=%@$nOj8GgZj7Pgi`?-L4@=h_PAQHKpH-_=q9wUsbhm;z8-23%dw`VTjn1G2fdszYU|^f|bzbt!MCeDDTj zb~mPN21F(%R*M9@n%Lvzkqt3+F>NU4sanZZVdu>r>S;GxS71>7Kh1q-R8!d(uOf~G z#SSV8jv`2j5fCCRU_q(`2?C)-sX{1Hr3J)>f)Hxx1f>~i6GB1Z~^-|Fz!N$0ruK+gw|va z;B7#A+p5o*kwl8~pSd-Z)wBkVr4)+xNkPo=Xn$Sw`TlOdbXT>Z@5giy%B4kA#Bu-i zBOMPGQQtz%P!~b`0Uwm5ie`n({ck+y<<;_*S0|K!Jezke%%r(=txsLS#C_yXdG1x` zvGK>L~!8df=e^hRla!3MYEJvU3lB4V8W9xyj1zg^NQCv~QC< zlL73Hzzd46P*ESh!U|lrNfcP(I6>}e4 z<=qW=PT-f&@*5wd!-icmvig| zqqJug5NCT2Oh?@+&W$z||GNgYGCG&NW6b_OPd?}F-M_9I28{4aJPUu&T3UVP+j^dK zSLL<*-LU8PO&?exZT7FY4Y>8recj%z=Ue@v=i|4HuCvV43V41_uB*AR)oX9>&QRBm zS$ytVUz%fVxpn`-q_~~QdBt5&#k|?h7MtqZ@_v$K{iIYT5%QFOA;i%F9Xd5oh~!50o9hRlD;2G>UGUwdw)@FjJDyY63vLVU46gRjFEiwB0UG~W2!3$wev$b#TXqYjyJz-HMb$Fvvr)1Q8}){^h|ec~Mz<^y3?-2A|3--ejn~cK`SsnsMGFu92bZshdHL$dM5L zgCos=SwN`8qedf)PMZV6X#+rE{Bf zl%jdJ*}v5Pp54W;JOAq46sc@SXYbm-wePZhccTOF|F*1AyZL{g6>u<{b$ns_Ug5r7 z|KkIoLsId?x?_-Q+vbs%bicMUVRZuqr=n)70)ouegG@&u&ehP>V%k$@AI?WnOdT$O zQD8IjPGBVZp=312DsVVCGFwPRxX>fB&)dhZvQXBga`O2I?fp8*+4|- z=yiz(9mPnP&#hJKanDGU%gWPSMCs*WNXDyrLiQgcU8wEU<0)wsf4U*4!8V^C%eTJt zF9}?$xf%R({6&J>Q_t8}qCULZoK55IAULc~Lb*6E+Nr?oOq|(V$fAoGsMFEc?756> zbdrj%8M&{>B(?l*P;ys=E_TM-*D)sDZw9LfnTdVaj3N$cQwq4mP@7>G}KW82XoYIaEo>C`zsex52Rwz4+G%OA^jK3DMHb) zNxL!vzlRojIP-w2Ckz%k6%#OZrL!pq5yhsueeT3hf!*QBQiIW)B;l&A{zCfeIGeEH0D7G+qHG1qDaB1-BjGT&?~U(PDgC?O z{!Ede6TLNscnV6yb!Jyjz;mO%(~~l*RQ6#G ztbKL#K6`gQSx@*1=s;hqXz1!vz4`Q=(|b_(!hwBS%0}xt_$z>OQ;BZh9;P!2Q1{dQpG(CNgXL2$U1x|sR*mKfNvAO$>MeP`jA%0`LUOsU+?t)$FhI=>P zsd7IRWAO`~u0NJ^kZ1hIlC~^xEBNC2?ROsDdlvMa`HB0_Z9!O(OKVa7bZo4&al**L zM#Fi85JAnFPK_%UJROBe^}TZwTyf*#6@ohUx%xh@{TnvRiA_wmkv_$d%1+6s(&?pQ zJ-YAyx)LRJ$OO~6E$HJy(8KR~8|)oP8MEX`>w&L(5ahqwmX|-&U3r45SZ=*L-gez* zx=6{x?gGZq`-Zc{-Gr3d?81NMh{az#;*T1e?|(J+Z`xE zg-5FF!#<0naUZYU{OIy_kISJ_Cz7MzEYXb}wqp45Mnlsqb|=qupV7v)!Xa`1q8O!m z5n7^&T{@uQov-@bcV(2LJ{!e(dC#;Xw%kHxaxOfq+W+>{2w=zF13i(Ro3b}I$V`bTc$)p(ccyOj&X?>FZPddT zi|avs@wqXce+YfsASC@7F7b(K?@VVeLG{`_Yp*puf)>!pRM^wVh#FQTe@{{LS$yu~6WZCK7zFElwonW4(wtoY*F{F#aZ%eAJ~e+A_xoV!;!_P(ev|iP zS#mjT%0#r#YTCqSZCvaG)K6cqoLy{f=de%lkz@$WY6epQ9*GP<%Q47j7Z+$ zkL&Q#q1`{wF5ZT_$9Z;O50a2z!#>{d3;?{AeOx@F#3z`#$%p-75(RCA8l_I&bB}V7 zCL0Co?t=$lQBRA*o)2msF=4H>!JK%IIS9$}U8^Gtt%Gt*8`ccyn^E=B(=c~$8wOT= zB(aY_IYzhrtPrgeAduydCLy7S!1cV?!W9woJaSFz_quxsLm%o*yLm>GO*L>|%9ja~ z?vldnioUtlj$H?Ur%zaGaBwG&aPHTOaTdzVTZuL<3yjF-q0LE%9sC7&Sdlq07g2lk z6O;(oM-RA=HPIpGJ7{(RZSaK(tyImX+vW$>G4>UBe^yNnD!e#5EOe zo~uouLH-E+#pD0lo3cK5zrCtFb7>~e@XY7CNLv5fP&n&`@V}1u=hsU&)2x<;^YqT( zvn>r^gM^%yTt9~KA33Ai&ppwd-q}_>^Kx<39Bh++C5~?S-BB=O2o6NPkP7)<1Lmt=fCO&k5VM?bxcn zg2WD8DBJ}u!{J)FPj=%06r(*d3WY@RTm4JD{WFS7396(@AJX#3q3muM^PN$)kLm_H9TSO&UW*xkLIp}1-263qy-faNOgr&zp z?^Uck)I0J#2Y4HHatX}QC`Hf6$VhBVU1jCav#57P8uvZ9R(2%~H1tdj5m%x!K^3Drh4wSCeqdBiwiI1A@J3St_wmwc0%SY_rpEOHFCKW$zar8okTH z9xhxUuF-CS_ARe5so*eHhpEd;LEk4WXIk>P7YQZIX2k-Ju1a&NiQ~Qi=)`LcaLFThubHfNCad)CjC#W(nP|t;u~vfVaY1k${vXv) zwtHMqk;D#1({%MOSKqfFF^`2n-l^(aw<6>TgS`Z2vR2#rwWe%+2~!u|0|#&mdw$BK zUtZ`JkhI@SD=ZF>SuD)f@YvS-WcBZMyMO`;2Wy44Do-37nlBkZMi0E@(!3=Kil6#6 z!hmL7&&dn6D2hy1$3Xdo|A$Qq56+<%(9}#*XYD#ev4{(j2O2+q zUZBX&AJ63aY*f8M6NTZR$|KQVex>!lgLC1gD!V<9WfbUn!P+$FlR^))V!Wz<#mC;t zd+^ox*s&{o4BQTnICFcOkHE?sS6p`4X$3NaaQW_l3%_~hF%6Gb#zx3U zQH{$~wLk17uu5vGdJ@}5IXpH>g2N|+)S58%$uj}U$T>G*=V9P(=0}55e!U*iRk+UKk{-k@ zE3f--3hgb2vrQU%CyLLFLXdsP^&W$s+it>8$!IXVti3~{S|e?)7@X%XT=$g=E%l&`8O`V0k3I$S#pkv13KhGX zKP5<1jL2z3Ijz$3i(1`l^trvFJu_0^&Pht>G* zun6Di`%Gl^7gt)r7^IrO=-A`Kbi$#oE zhd4Hd(z`!_R4j5+8irh}dR!a*Ckj|CNmrAUL2uSc`1be}QcYR24D>Q=H38{liiz{$ zWpb24@nC1DO8C7knJ{^%u6MZG5v{8Q!Nn2sy(Z>%9xPZjW7*aCTVS0hFX4SUD)ON& zl;Ijzfpf5x`H6Z7{WF9;a&GSVJas3j6dks72d(3J5<@L>U|ZFtH|vdKnawnntCnPX zj-U|zz-vPMN|AlOTr6G2G}8r(g5q5MUs+(0IG91Nt>JY^a&BG0>j2Mxd7JP4mswlo z4|J*ub9`1SVRGinOU9%5=gO!Lq>-%Jx%FERJSQus=p)_MOBT;Rz^~rkVf*YLm{#Db z9K1qG$SX_Lw(@#Q^$1OXIkibRwCav7`~PD9pB%mkTlZDC$fAof81#T#e}gfsd!h}U zqovrm)Vg?uGNojXnvPMVki?_-BF-mrsy4bur`EUL5ZUMd{mSz#(l<|C zl^sGeNgj4;`{8rEB+-XHc|<4X_@5b2(*8ZSc&i+mPdTdrKyGP-T& zBz+(Q02fzM-od+Rl6=}>z42oG{vxc$ruS~32Mo=Vj;TBHZkD@+!(fb4Ky1&Nu?>vV zwl=^&spd8W-IA%7+_^nw5qUN8K-+pF%Mb5cFIWA!Wck}VLaJ$AYSOBeoX-mUbd6*ex^`9})`wg{kn=P<4loMed(4n?hR1JrDS(N09NIP}s0x=U zl*T1#SZBQ4>2o=wHH9l*e-}tW3Fq#v(%SdwOU-IC=y3bsa3|l?qQ~mk_9{N2t7Y#R zqLm&MMQ^J@fWTOq`Z|0XB4=B<(H=jk(hc_89uws{CN#XXsTE58KoIL)^ zcTU}|mP76%n8lL$VrjgmDQ-H{XlPcMtYUVz#_v94T!)Js$jV_t+n5;`eCoq-Xy;It zAH%Z&ZXYn4qt?knR87zl=_WGD*pm?4XvcX0^D}rm>41B#k?$=hjFho_Mkgi-dHfwA z=dXfBlc?It!N+tB3cSXRu~xu{a1%X6$agjzcqCIr^NP<0LhSnva>bdN-*? z0w7hK)Lmk@TM8c#nvg2$lv{$~+;ISyJKK>})5OMDZHat~FSjEm5kkB|=@m0a(_sv{ z_UDqhdt|Kw6q0DAESsNCU2QVNH&G1OO_WBVvG{6xH(&td_?-|2Od-9`@nN4b$f>@MSYSBjG=FB%^(NufE)c;4%{r{HXBh~D~e<|l6aqLVF z=B7FuJB|Mk%(h1oZ`p=ryR)TSC}lkzMX(=>wx1=NuKFhQC4@tlNicbOwWTU+RcV%8 zHky@Tp&{YnjW0df=31e$WM5HtsI|7kkuwmNO_3tyF^qrhDF5H}ji z3N#hKO~_j-AA%Voc?I2sB5!Ov3DG!7hcniXxkt_UxVBgl0_(lf_X;Zz+HI>|4D!WJ z%<|KjI-Mm9LOajf8cbIKxpvVXKlGyMx((@EhEAQ7;`vH&2aRky1`*gwMVjxIa^@#0 zR5F1Kp~1-lS6-sYdxc7T<234Bl-G z>UjRe3^(k=oUCd65G=<^n9f`x4!uZ0+Dt)^*nQ@;dxf)-+MykViw1rE;%Jpw^(}?A zBz)Je(|bv*nq5=YZBbj+;}Z<_GH64aQC>~AmwJZzj1@x@vq9vB0s9q4!=M}d$6RKb z__a;nahh~Bo93H(H%t6m?itIPBP_2aGkl*!Uga2{5{}}k7 zW|6yoMy58{>GiCf#x_vudGza#lZh_m&$&_yYve3RJQ^*dh{d0p%`tT`4EhAq;XlT| z%iqisXLWGs6mi`cn*(i=rFvAps5*0)|N3Pk_o8YHKIP%lxu+%FKKfQY9%h4<<@X!M zUT+~jzk`3RJ2;SCB^%@d0d2b4)Ew=){ZlWZObFI#Nk+zT3NuC>DoiAz;7+glyz_P* zPSSIL7Z73wVej2^93-{b>lOJN*HEy~+geFouuO=J9>uI;x=DN*wF-QC z9?~?qbtq+0!5cX30#34YZ+oHa|2@W522NnxJO8~WLg==`TEta@tgIj+UVSZ;5 zw}2=>oxMQPcaCdvLQ*OD*rvaG#gwUbgy)|DkL(eNNb(O&C{l~h(@$byrrkW&WM&|O zCps5DAg+F@z<+o_ANLmVK9>X<3I=SM?0znCF-Rfl zib{iAwdQH0ClOu-h+LumbEpP!f8+dm2YH2Xx{a(r!_YwZYJyYiigyA()92YDFqom} z32UYt3ts|iSxGpJ$(zrOr?PfNmKa<5U;(Pj9GeTKCpr0Q*>c(oZc$#C*7J|u-I7;h zhcu?0nEp`PAJD#`7c$V?nsZETD8OgfK_`hNW;%?UprU9)KIoj>Dj!`gXu#H+0tZu=sYb6Socmp%3u=V+`PxB=3O8AXdJ(;%_I2Yxs5Cef;2l%2%E zO9|$o?PiKG5sbD!r$f3*E1cY=ko8N1ECw7DG5)4dZrZi6*P>W0fts;mWsctPKk0IV z$Q=KXgZRe6yMaq~?V0RupB&O(Z*mDOK1F2pO)$wT3yER)^`VdKQ08UZO;I3D z0<>W?!D6o=)IXf zcJugk_X&IW3=$S3?D9e3&+5|6WJgM}P66;UoRC^b8%qkyTwgO=aGN^SLFw(Gu4VZp zY!U&9;k|_j9z8lVw>lt+qiO=0gW-9a>OX*N8XHEeON!2(I@w02XmkVRA!ds9EVezS z@$Qz+y-zjUnF;MuI!5@W73=QN+%=d$8^2;vFx$`E3X2M0;@fSR(uk$-RiYy^=hf=U zafRQVkjKUC{U}?~6|9Y4HN%3BCQIc_iDp=2tpOSDV}p8=CxyyNx?Ei!L!~6W0m}3Z z&qC5h7kTF$=4#0VfOBoy;g5v^B&RLO;dWMZMvwY%j}9MAJLOFPy&-Dj6heM^i#tXG zt<$($0HnzF4_VL|u97zV^9)*xQiE)-HVw@z_1VZ(8nn~$1?+y3@t3d)x@mr=(*j*v zvkCCep{CfuvF>;}lgy9{2ULL&iB!|NYN>3K14{~nlS9zDnJ_}+=f?oOnoC@{wQbwp zM$H>n4gRs9o2(mTdr)KgUQUW=4s7a2xBy82#MXh}nUXlW8V}H59wNWTqSzaodmbWx z6OeTyX|h*5x0f*>c=KB@&9GJfCb3pW$p)5}78@#|WvzL-&5{7b+OCN$BebRCWeeWk zj{#PgJ{{v+b+&cvldt3CTDx6v@hu2rHIb@aV4A;@RVnN6Bo(47P6x`3nk^OThrr~2 zCDxMS<1C7q?_j2~<;iz8Ub&<9o&LQJZH0m=&R#v$P*@4H8xlf%ka=YmveUz>39wA^ z6*`)bPnMg6lSKmPH6pgQ#$kPFV`0ZA3qa$b9iNmMMf0Z($pwg0EjL3Ctf1+yBQ1aL zOuu(L6H)vHR#Q=s=sX{j98z#!sL~lb$%>)o6EGYoA6vSaMfl)*4l?dzm1#+!_5ww- zGa)rf49C)}(T6s`K083eP(;^;4(r}Ekzs%4x!?2RuGitW z-7vjo%Ar=iqjN}1vB3`Qs6)&a7O1>R6#yR#-Ly*?7h4uhtU;wdV{-&!uq7&7HYs|m zlz#L`G@_V+vGO5f5-c#u4oGv;zRp$0X{?o(cs4-OcW45Yw+rMf#06I?oXRxKBN$EC z4Kp>*rZ!u52>>|}8}s|NR_psKK?Z-TrUTN2_Quqin1L%u`M7G(Nw>0r_1F<|p->BB zm)hr*J@NRG%_H(P%}W@hdIRKaLz`??Q!|2Gt3q5GK4I_lZoM`A+veujf3h?|Bto3) zXad}@I%aV79Rpv&3DHUkG|a~w`w=MwStQUf6gCq%Y+w6F1#l7XsRkm*RzJ?p7u(pN zSyKUqVXPcXiKX!=QEG1b>vO+HRMqbAg+d0k{^j~WepWWHVSxX1iy8%J9=LfD3v3!a zZ4f@1_=Le9iwhVB8G!#6_oL5o~$LBR+5KFHD={2>)|Iw#B zvS;KNmp-9uY}#beAfKZ%p#%4=x64@|04y5Lxm9ZwA6Q?QkhJ7rl|4iNQ{1OeK9IaKIMrPE@lPcLg_D3>Tly*=HsDq zHkI81Oo!p@A(}sQ#`D=-vgT}3h#*_D8v$jRGMQ3ai}j3Nj4J7kDv$^ZjzT$V?9wtm z7dr;oR*1?(=-9l&U|LTaSL)Fmc39dhVn<0m>>S zWfWdb^44MUN3s?{(op#=9i5ZFzSfk{WKsyFN~!$5Bp4=U6xtj6g4sB06L|`UjE0&g z&7U3n48)j_$Fl?l&Uv#-;W>F($!2!hjcu8tqcv4s&55SsUepXL4V_H6`tO%5EpMgQQ@k4eTs20VmyNw!W(eaM;>pSj`m^dq%=@ZZ;8U0 z7D+DB(S3z(sCl5DH-93o{WzZtLYU$MMNG~$YJpY<1| z2KC=v;x=xFKlO^dBjVzYX>;Jv6qkD3LU+%CB{o_%9|JMNeGc>g;yyNNQ*(0E=qti1 z^WsfVDSl&%$=(J$bmoG|gBB^K8__as!AP+h>E0oa*8Rvz7-;Eq+oOffFK3ZF_@JC7$0RjpYXqdbDXpEgTG`s~di37o z@LSSXJz?O>kEz!qrO*Lwi-vvUFdJR9)uT=DucQ&WdD_je=!d+PTQZ)*ee#aZTbtxJ zrE1KzJBeCCgVnEnbDRgV6$(sNXi<}|VI-W;j{gySM=m%>wY{|fYgRpgUt(HaHgI7z z1t>FR6?}OYHbaGF-Y4Y3bKxH(_jNabb>%<&y* zC#7zFVRgoK<|nP*Y%Y(qqIpV<@7uCP9eA&(>=Gu3UaM z(%s{C-}FfJ5Z7t*gD@?e63M1OErJ6951J diff --git a/examples/calibrated_orientation/LSM6DS_LIS3MDL.h b/examples/calibrated_orientation/LSM6DS_LIS3MDL.h new file mode 100644 index 0000000..5e3ad8b --- /dev/null +++ b/examples/calibrated_orientation/LSM6DS_LIS3MDL.h @@ -0,0 +1,31 @@ +#include +Adafruit_LIS3MDL lis3mdl; + +// Can change this to be LSM6DSOX or whatever ya like +#include +Adafruit_LSM6DS33 lsm6ds; + +bool init_sensors(void) { + if (!lsm6ds.begin_I2C() || !lis3mdl.begin_I2C()) { + return false; + } + accelerometer = lsm6ds.getAccelerometerSensor(); + gyroscope = lsm6ds.getGyroSensor(); + magnetometer = &lis3mdl; + + return true; +} + +void setup_sensors(void) { + // set lowest range + lsm6ds.setAccelRange(LSM6DS_ACCEL_RANGE_2_G); + lsm6ds.setGyroRange(LSM6DS_GYRO_RANGE_250_DPS); + lis3mdl.setRange(LIS3MDL_RANGE_4_GAUSS); + + // set slightly above refresh rate + lsm6ds.setAccelDataRate(LSM6DS_RATE_104_HZ); + lsm6ds.setGyroDataRate(LSM6DS_RATE_104_HZ); + lis3mdl.setDataRate(LIS3MDL_DATARATE_1000_HZ); + lis3mdl.setPerformanceMode(LIS3MDL_MEDIUMMODE); + lis3mdl.setOperationMode(LIS3MDL_CONTINUOUSMODE); +} diff --git a/examples/calibrated_orientation/LSM9DS.h b/examples/calibrated_orientation/LSM9DS.h new file mode 100644 index 0000000..c32cee5 --- /dev/null +++ b/examples/calibrated_orientation/LSM9DS.h @@ -0,0 +1,30 @@ +#include +Adafruit_LSM9DS1 lsm9ds = Adafruit_LSM9DS1(); + +// Or if you have the older LSM9DS0 +//#include +// Adafruit_LSM9DS0 lsm9ds = Adafruit_LSM9DS0(); + +bool init_sensors(void) { + if (!lsm9ds.begin()) { + return false; + } + accelerometer = &lsm9ds.getAccel(); + gyroscope = &lsm9ds.getGyro(); + magnetometer = &lsm9ds.getMag(); + + return true; +} + +void setup_sensors(void) { + // set lowest range +#ifdef __LSM9DS0_H__ + lsm9ds.setupAccel(lsm9ds.LSM9DS0_ACCELRANGE_2G); + lsm9ds.setupMag(lsm9ds.LSM9DS0_MAGGAIN_4GAUSS); + lsm9ds.setupGyro(lsm9ds.LSM9DS0_GYROSCALE_245DPS); +#else + lsm9ds.setupAccel(lsm9ds.LSM9DS1_ACCELRANGE_2G); + lsm9ds.setupMag(lsm9ds.LSM9DS1_MAGGAIN_4GAUSS); + lsm9ds.setupGyro(lsm9ds.LSM9DS1_GYROSCALE_245DPS); +#endif +} diff --git a/examples/calibrated_orientation/LSM9DS1.h b/examples/calibrated_orientation/LSM9DS1.h new file mode 100644 index 0000000..935aad0 --- /dev/null +++ b/examples/calibrated_orientation/LSM9DS1.h @@ -0,0 +1,20 @@ +#include +Adafruit_LSM9DS1 lsm9ds1 = Adafruit_LSM9DS1(); + +bool init_sensors(void) { + if (!lsm9ds1.begin()) { + return false; + } + accelerometer = &lsm9ds1.getAccel(); + gyroscope = &lsm9ds1.getGyro(); + magnetometer = &lsm9ds1.getMag(); + + return true; +} + +void setup_sensors(void) { + // set lowest range + lsm9ds1.setupAccel(lsm9ds1.LSM9DS1_ACCELRANGE_2G); + lsm9ds1.setupMag(lsm9ds1.LSM9DS1_MAGGAIN_4GAUSS); + lsm9ds1.setupGyro(lsm9ds1.LSM9DS1_GYROSCALE_245DPS); +} diff --git a/examples/calibrated_orientation/NXP_FXOS_FXAS.h b/examples/calibrated_orientation/NXP_FXOS_FXAS.h new file mode 100644 index 0000000..0f52980 --- /dev/null +++ b/examples/calibrated_orientation/NXP_FXOS_FXAS.h @@ -0,0 +1,18 @@ +#include +#include + +Adafruit_FXOS8700 fxos = Adafruit_FXOS8700(0x8700A, 0x8700B); +Adafruit_FXAS21002C fxas = Adafruit_FXAS21002C(0x0021002C); + +bool init_sensors(void) { + if (!fxos.begin() || !fxas.begin()) { + return false; + } + accelerometer = fxos.getAccelerometerSensor(); + gyroscope = &fxas; + magnetometer = fxos.getMagnetometerSensor(); + + return true; +} + +void setup_sensors(void) {} diff --git a/examples/calibrated_orientation/calibrated_orientation.ino b/examples/calibrated_orientation/calibrated_orientation.ino new file mode 100644 index 0000000..83c4702 --- /dev/null +++ b/examples/calibrated_orientation/calibrated_orientation.ino @@ -0,0 +1,111 @@ +// Full orientation sensing using NXP/Madgwick/Mahony and a range of 9-DoF +// sensor sets. +// You *must* perform a magnetic calibration before this code will work. +// +// To view this data, use the Arduino Serial Monitor to watch the +// scrolling angles, or run the OrientationVisualiser example in Processing. +// Based on https://github.com/PaulStoffregen/NXPMotionSense with adjustments +// to Adafruit Unified Sensor interface + +#include +#include + +#define SENSORS_RADS_TO_DPS (180.0 / 3.141592653589793238463) + +Adafruit_Sensor *accelerometer, *gyroscope, *magnetometer; + +// uncomment one combo 9-DoF! +//#include "LSM6DS_LIS3MDL.h" // can adjust to LSM6DS33, LSM6DS3U, LSM6DSOX... +#include "LSM9DS.h" // LSM9DS1 or LSM9DS0 +//#include "NXP_FXOS_FXAS.h" // NXP 9-DoF breakout + +Adafruit_Sensor_Calibration cal; + +// pick your filter! slower == better quality output +//Adafruit_NXPSensorFusion filter; // slowest +//Adafruit_Madgwick filter; // faster than NXP +Adafruit_Mahony filter; // fastest/smalleset + +#define FILTER_UPDATE_RATE_HZ 100 +uint32_t timestamp; + +void setup() { + Serial.begin(115200); + while (!Serial) yield(); + + if (!cal.begin()) { + Serial.println("Failed to initialize calibration helper"); + } else if (! cal.loadCalibration()) { + Serial.println("No calibration loaded/found"); + } + + if (!init_sensors()) { + Serial.println("Failed to find sensors"); + while (1) delay(10); + } + + accelerometer->printSensorDetails(); + gyroscope->printSensorDetails(); + magnetometer->printSensorDetails(); + + setup_sensors(); + filter.begin(FILTER_UPDATE_RATE_HZ); + timestamp = millis(); + + Wire.setClock(400000); // 400KHz +} + + +void loop() { + float roll, pitch, heading; + float gx, gy, gz; + + if ((millis() - timestamp) < (1000 / FILTER_UPDATE_RATE_HZ)) { + return; + } + timestamp = millis(); + // Read the motion sensors + sensors_event_t accel, gyro, mag; + accelerometer->getEvent(&accel); + gyroscope->getEvent(&gyro); + magnetometer->getEvent(&mag); + //Serial.print("I2C took "); Serial.print(millis()-timestamp); Serial.println(" ms"); + + cal.calibrate(mag); + cal.calibrate(accel); + cal.calibrate(gyro); + // Gyroscope needs to be converted from Rad/s to Degree/s + // the rest are not unit-important + gx = gyro.gyro.x * SENSORS_RADS_TO_DPS; + gy = gyro.gyro.y * SENSORS_RADS_TO_DPS; + gz = gyro.gyro.z * SENSORS_RADS_TO_DPS; + + // Update the SensorFusion filter + filter.update(gx, gy, gz, + accel.acceleration.x, accel.acceleration.y, accel.acceleration.z, + mag.magnetic.x, mag.magnetic.y, mag.magnetic.z); + //Serial.print("Update took "); Serial.print(millis()-timestamp); Serial.println(" ms"); + + Serial.print("Raw: "); + Serial.print(accel.acceleration.x, 4); Serial.print(", "); + Serial.print(accel.acceleration.y, 4); Serial.print(", "); + Serial.print(accel.acceleration.z, 4); Serial.print(", "); + Serial.print(gx, 4); Serial.print(", "); + Serial.print(gy, 4); Serial.print(", "); + Serial.print(gz, 4); Serial.print(", "); + Serial.print(mag.magnetic.x, 4); Serial.print(", "); + Serial.print(mag.magnetic.y, 4); Serial.print(", "); + Serial.print(mag.magnetic.z, 4); Serial.println(""); + + // print the heading, pitch and roll + roll = filter.getRoll(); + pitch = filter.getPitch(); + heading = filter.getYaw(); + Serial.print("Orientation: "); + Serial.print(heading); + Serial.print(" "); + Serial.print(pitch); + Serial.print(" "); + Serial.println(roll); + Serial.print("Took "); Serial.print(millis()-timestamp); Serial.println(" ms"); +} diff --git a/examples/calibration/LSM6DS_LIS3MDL.h b/examples/calibration/LSM6DS_LIS3MDL.h new file mode 100644 index 0000000..2d7b1de --- /dev/null +++ b/examples/calibration/LSM6DS_LIS3MDL.h @@ -0,0 +1,31 @@ +#include +Adafruit_LIS3MDL lis3mdl; + +// Can change this to be LSM6DSOX or whatever ya like +#include +Adafruit_LSM6DSOX lsm6ds; + +bool init_sensors(void) { + if (!lsm6ds.begin_I2C() || !lis3mdl.begin_I2C()) { + return false; + } + accelerometer = lsm6ds.getAccelerometerSensor(); + gyroscope = lsm6ds.getGyroSensor(); + magnetometer = &lis3mdl; + + return true; +} + +void setup_sensors(void) { + // set lowest range + lsm6ds.setAccelRange(LSM6DS_ACCEL_RANGE_2_G); + lsm6ds.setGyroRange(LSM6DS_GYRO_RANGE_250_DPS); + lis3mdl.setRange(LIS3MDL_RANGE_4_GAUSS); + + // set slightly above refresh rate + lsm6ds.setAccelDataRate(LSM6DS_RATE_104_HZ); + lsm6ds.setGyroDataRate(LSM6DS_RATE_104_HZ); + lis3mdl.setDataRate(LIS3MDL_DATARATE_1000_HZ); + lis3mdl.setPerformanceMode(LIS3MDL_MEDIUMMODE); + lis3mdl.setOperationMode(LIS3MDL_CONTINUOUSMODE); +} diff --git a/examples/calibration/LSM9DS.h b/examples/calibration/LSM9DS.h new file mode 100644 index 0000000..2b51fe7 --- /dev/null +++ b/examples/calibration/LSM9DS.h @@ -0,0 +1,30 @@ +//#include +// Adafruit_LSM9DS1 lsm9ds = Adafruit_LSM9DS1(); + +// Or if you have the older LSM9DS0 +#include +Adafruit_LSM9DS0 lsm9ds = Adafruit_LSM9DS0(); + +bool init_sensors(void) { + if (!lsm9ds.begin()) { + return false; + } + accelerometer = &lsm9ds.getAccel(); + gyroscope = &lsm9ds.getGyro(); + magnetometer = &lsm9ds.getMag(); + + return true; +} + +void setup_sensors(void) { + // set lowest range +#ifdef __LSM9DS0_H__ + lsm9ds.setupAccel(lsm9ds.LSM9DS0_ACCELRANGE_2G); + lsm9ds.setupMag(lsm9ds.LSM9DS0_MAGGAIN_4GAUSS); + lsm9ds.setupGyro(lsm9ds.LSM9DS0_GYROSCALE_245DPS); +#else + lsm9ds.setupAccel(lsm9ds.LSM9DS1_ACCELRANGE_2G); + lsm9ds.setupMag(lsm9ds.LSM9DS1_MAGGAIN_4GAUSS); + lsm9ds.setupGyro(lsm9ds.LSM9DS1_GYROSCALE_245DPS); +#endif +} diff --git a/examples/calibration/NXP_FXOS_FXAS.h b/examples/calibration/NXP_FXOS_FXAS.h new file mode 100644 index 0000000..0f52980 --- /dev/null +++ b/examples/calibration/NXP_FXOS_FXAS.h @@ -0,0 +1,18 @@ +#include +#include + +Adafruit_FXOS8700 fxos = Adafruit_FXOS8700(0x8700A, 0x8700B); +Adafruit_FXAS21002C fxas = Adafruit_FXAS21002C(0x0021002C); + +bool init_sensors(void) { + if (!fxos.begin() || !fxas.begin()) { + return false; + } + accelerometer = fxos.getAccelerometerSensor(); + gyroscope = &fxas; + magnetometer = fxos.getMagnetometerSensor(); + + return true; +} + +void setup_sensors(void) {} diff --git a/examples/calibration/calibration.ino b/examples/calibration/calibration.ino new file mode 100644 index 0000000..07af72b --- /dev/null +++ b/examples/calibration/calibration.ino @@ -0,0 +1,221 @@ +/*************************************************************************** + This is an example for the Adafruit AHRS library + It will look for a supported magnetometer and output + PJRC Motion Sensor Calibration Tool-compatible serial data + + PJRC & Adafruit invest time and resources providing this open source code, + please support PJRC and open-source hardware by purchasing products + from PJRC! + + Written by PJRC, adapted by Limor Fried for Adafruit Industries. + ***************************************************************************/ + +#include + +#define SENSORS_RADS_TO_DPS (180.0 / 3.141592653589793238463) + +Adafruit_Sensor *accelerometer, *gyroscope, *magnetometer; + +// uncomment one combo 9-DoF! +#include "LSM6DS_LIS3MDL.h" // can adjust to LSM6DS33, LSM6DS3U, LSM6DSOX... +//#include "LSM9DS.h" // LSM9DS1 or LSM9DS0 +//#include "NXP_FXOS_FXAS.h" // NXP 9-DoF breakout + +Adafruit_Sensor_Calibration cal; +sensors_event_t mag_event, gyro_event, accel_event; + +int loopcount = 0; + +void setup(void) { + Serial.begin(115200); + while (!Serial) delay(10); // will pause Zero, Leonardo, etc until serial console opens + + Serial.println(F("Adafruit AHRS - IMU Calibration!")); + + Serial.println("Calibration filesys test"); + if (!cal.begin()) { + Serial.println("Failed to initialize calibration helper"); + while (1) yield(); + } + if (! cal.loadCalibration()) { + Serial.println("No calibration loaded/found... will start with defaults"); + } else { + Serial.println("Loaded existing calibration"); + } + + if (!init_sensors()) { + Serial.println("Failed to find sensors"); + while (1) delay(10); + } + accelerometer->printSensorDetails(); + gyroscope->printSensorDetails(); + magnetometer->printSensorDetails(); + + setup_sensors(); + + Wire.setClock(400000); // 400KHz +} + +void loop() { + magnetometer->getEvent(&mag_event); + gyroscope->getEvent(&gyro_event); + accelerometer->getEvent(&accel_event); + + // 'Raw' values to match expectation of MotionCal + Serial.print("Raw:"); + Serial.print(int(accel_event.acceleration.x*8192/9.8)); Serial.print(","); + Serial.print(int(accel_event.acceleration.y*8192/9.8)); Serial.print(","); + Serial.print(int(accel_event.acceleration.z*8192/9.8)); Serial.print(","); + Serial.print(int(gyro_event.gyro.x*SENSORS_RADS_TO_DPS*16)); Serial.print(","); + Serial.print(int(gyro_event.gyro.y*SENSORS_RADS_TO_DPS*16)); Serial.print(","); + Serial.print(int(gyro_event.gyro.z*SENSORS_RADS_TO_DPS*16)); Serial.print(","); + Serial.print(int(mag_event.magnetic.x*10)); Serial.print(","); + Serial.print(int(mag_event.magnetic.y*10)); Serial.print(","); + Serial.print(int(mag_event.magnetic.z*10)); Serial.println(""); + + // unified data + Serial.print("Uni:"); + Serial.print(accel_event.acceleration.x); Serial.print(","); + Serial.print(accel_event.acceleration.y); Serial.print(","); + Serial.print(accel_event.acceleration.z); Serial.print(","); + Serial.print(gyro_event.gyro.x, 4); Serial.print(","); + Serial.print(gyro_event.gyro.y, 4); Serial.print(","); + Serial.print(gyro_event.gyro.z, 4); Serial.print(","); + Serial.print(mag_event.magnetic.x); Serial.print(","); + Serial.print(mag_event.magnetic.y); Serial.print(","); + Serial.print(mag_event.magnetic.z); Serial.println(""); + loopcount++; + receiveCalibration(); + + // occasionally print calibration + if (loopcount == 50 || loopcount > 100) { + Serial.print("Cal1:"); + for (int i=0; i<3; i++) { + Serial.print(cal.accel_zerog[i], 3); + Serial.print(","); + } + for (int i=0; i<3; i++) { + Serial.print(cal.gyro_zerorate[i], 3); + Serial.print(","); + } + for (int i=0; i<3; i++) { + Serial.print(cal.mag_hardiron[i], 3); + Serial.print(","); + } + Serial.println(cal.mag_field, 3); + loopcount++; + } + if (loopcount >= 100) { + Serial.print("Cal2:"); + for (int i=0; i<9; i++) { + Serial.print(cal.mag_softiron[i], 4); + if (i < 8) Serial.print(','); + } + Serial.println(); + loopcount = 0; + } + + delay(10); +} + +/********************************************************/ + +byte caldata[68]; // buffer to receive magnetic calibration data +byte calcount=0; + +void receiveCalibration() { + uint16_t crc; + byte b, i; + + while (Serial.available()) { + b = Serial.read(); + if (calcount == 0 && b != 117) { + // first byte must be 117 + return; + } + if (calcount == 1 && b != 84) { + // second byte must be 84 + calcount = 0; + return; + } + // store this byte + caldata[calcount++] = b; + if (calcount < 68) { + // full calibration message is 68 bytes + return; + } + // verify the crc16 check + crc = 0xFFFF; + for (i=0; i < 68; i++) { + crc = crc16_update(crc, caldata[i]); + } + if (crc == 0) { + // data looks good, use it + float offsets[16]; + memcpy(offsets, caldata+2, 16*4); + cal.accel_zerog[0] = offsets[0]; + cal.accel_zerog[1] = offsets[1]; + cal.accel_zerog[2] = offsets[2]; + + cal.gyro_zerorate[0] = offsets[3]; + cal.gyro_zerorate[1] = offsets[4]; + cal.gyro_zerorate[2] = offsets[5]; + + cal.mag_hardiron[0] = offsets[6]; + cal.mag_hardiron[1] = offsets[7]; + cal.mag_hardiron[2] = offsets[8]; + + cal.mag_field = offsets[9]; + + cal.mag_softiron[0] = offsets[10]; + cal.mag_softiron[1] = offsets[13]; + cal.mag_softiron[2] = offsets[14]; + cal.mag_softiron[3] = offsets[13]; + cal.mag_softiron[4] = offsets[11]; + cal.mag_softiron[5] = offsets[15]; + cal.mag_softiron[6] = offsets[14]; + cal.mag_softiron[7] = offsets[15]; + cal.mag_softiron[8] = offsets[12]; + + if (! cal.saveCalibration()) { + Serial.println("**WARNING** Couldn't save calibration"); + } else { + Serial.println("Wrote calibration"); + } + cal.printSavedCalibration(); + calcount = 0; + return; + } + // look for the 117,84 in the data, before discarding + for (i=2; i < 67; i++) { + if (caldata[i] == 117 && caldata[i+1] == 84) { + // found possible start within data + calcount = 68 - i; + memmove(caldata, caldata + i, calcount); + return; + } + } + // look for 117 in last byte + if (caldata[67] == 117) { + caldata[0] = 117; + calcount = 1; + } else { + calcount = 0; + } + } +} + + +uint16_t crc16_update(uint16_t crc, uint8_t a) +{ + int i; + crc ^= a; + for (i = 0; i < 8; i++) { + if (crc & 1) { + crc = (crc >> 1) ^ 0xA001; + } else { + crc = (crc >> 1); + } + } + return crc; +} diff --git a/examples/ahrs_10dof/ahrs_10dof.ino b/examples/deprecated/ahrs_10dof/ahrs_10dof.ino similarity index 100% rename from examples/ahrs_10dof/ahrs_10dof.ino rename to examples/deprecated/ahrs_10dof/ahrs_10dof.ino diff --git a/examples/ahrs_9dof/ahrs_9dof.ino b/examples/deprecated/ahrs_9dof/ahrs_9dof.ino similarity index 100% rename from examples/ahrs_9dof/ahrs_9dof.ino rename to examples/deprecated/ahrs_9dof/ahrs_9dof.ino diff --git a/library.properties b/library.properties index b8d8883..4b4ca32 100644 --- a/library.properties +++ b/library.properties @@ -1,9 +1,10 @@ name=Adafruit AHRS -version=1.1.4 +version=2.0.0 author=Adafruit maintainer=Adafruit -sentence=AHRS (Altitude and Heading Reference System) for Adafruit's 9DOF and 10DOF breakouts -paragraph=AHRS (Altitude and Heading Reference System) for Adafruit's 9DOF and 10DOF breakouts +sentence=AHRS (Altitude and Heading Reference System) for various Adafruit motion sensors +paragraph=Includes motion calibration example sketches, as well as calibration orientation output using Mahony, Madgwick, NXP Fusion, etc fusion filters category=Sensors url=https://github.com/adafruit/Adafruit_AHRS architectures=* +depends=Adafruit Unified Sensor, Adafruit LSM6DS, Adafruit LIS3MDL, Adafruit FXOS8700, Adafruit FXAS21002C, Adafruit LSM9DS1 Library, Adafruit LSM9DS0 Library, Adafruit LSM303DLHC, Adafruit BMP085 Unified, Adafruit BluefruitLE nRF51, SdFat - Adafruit Fork, ArduinoJson, Adafruit SPIFlash \ No newline at end of file diff --git a/src/Adafruit_AHRS.h b/src/Adafruit_AHRS.h new file mode 100644 index 0000000..115b0ac --- /dev/null +++ b/src/Adafruit_AHRS.h @@ -0,0 +1,3 @@ +#include +#include +#include diff --git a/src/Adafruit_AHRS_Madgwick.cpp b/src/Adafruit_AHRS_Madgwick.cpp new file mode 100644 index 0000000..b7e978c --- /dev/null +++ b/src/Adafruit_AHRS_Madgwick.cpp @@ -0,0 +1,289 @@ +//============================================================================================= +// Madgwick.c +//============================================================================================= +// +// Implementation of Madgwick's IMU and AHRS algorithms. +// See: http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/ +// +// From the x-io website "Open-source resources available on this website are +// provided under the GNU General Public Licence unless an alternative licence +// is provided in source." +// +// Date Author Notes +// 29/09/2011 SOH Madgwick Initial release +// 02/10/2011 SOH Madgwick Optimised for reduced CPU load +// 19/02/2012 SOH Madgwick Magnetometer measurement is normalised +// +//============================================================================================= + +//------------------------------------------------------------------------------------------- +// Header files + +#include "Adafruit_AHRS_Madgwick.h" +#include + +//------------------------------------------------------------------------------------------- +// Definitions + +#define sampleFreqDef 512.0f // sample frequency in Hz +#define betaDef 0.1f // 2 * proportional gain + +//============================================================================================ +// Functions + +//------------------------------------------------------------------------------------------- +// AHRS algorithm update + +Adafruit_Madgwick::Adafruit_Madgwick() { + beta = betaDef; + q0 = 1.0f; + q1 = 0.0f; + q2 = 0.0f; + q3 = 0.0f; + invSampleFreq = 1.0f / sampleFreqDef; + anglesComputed = 0; +} + +void Adafruit_Madgwick::update(float gx, float gy, float gz, float ax, float ay, + float az, float mx, float my, float mz) { + float recipNorm; + float s0, s1, s2, s3; + float qDot1, qDot2, qDot3, qDot4; + float hx, hy; + float _2q0mx, _2q0my, _2q0mz, _2q1mx, _2bx, _2bz, _4bx, _4bz, _2q0, _2q1, + _2q2, _2q3, _2q0q2, _2q2q3, q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, + q2q2, q2q3, q3q3; + + // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in + // magnetometer normalisation) + if ((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { + updateIMU(gx, gy, gz, ax, ay, az); + return; + } + + // Convert gyroscope degrees/sec to radians/sec + gx *= 0.0174533f; + gy *= 0.0174533f; + gz *= 0.0174533f; + + // Rate of change of quaternion from gyroscope + qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); + qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); + qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); + qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx); + + // Compute feedback only if accelerometer measurement valid (avoids NaN in + // accelerometer normalisation) + if (!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { + + // Normalise accelerometer measurement + recipNorm = invSqrt(ax * ax + ay * ay + az * az); + ax *= recipNorm; + ay *= recipNorm; + az *= recipNorm; + + // Normalise magnetometer measurement + recipNorm = invSqrt(mx * mx + my * my + mz * mz); + mx *= recipNorm; + my *= recipNorm; + mz *= recipNorm; + + // Auxiliary variables to avoid repeated arithmetic + _2q0mx = 2.0f * q0 * mx; + _2q0my = 2.0f * q0 * my; + _2q0mz = 2.0f * q0 * mz; + _2q1mx = 2.0f * q1 * mx; + _2q0 = 2.0f * q0; + _2q1 = 2.0f * q1; + _2q2 = 2.0f * q2; + _2q3 = 2.0f * q3; + _2q0q2 = 2.0f * q0 * q2; + _2q2q3 = 2.0f * q2 * q3; + q0q0 = q0 * q0; + q0q1 = q0 * q1; + q0q2 = q0 * q2; + q0q3 = q0 * q3; + q1q1 = q1 * q1; + q1q2 = q1 * q2; + q1q3 = q1 * q3; + q2q2 = q2 * q2; + q2q3 = q2 * q3; + q3q3 = q3 * q3; + + // Reference direction of Earth's magnetic field + hx = mx * q0q0 - _2q0my * q3 + _2q0mz * q2 + mx * q1q1 + _2q1 * my * q2 + + _2q1 * mz * q3 - mx * q2q2 - mx * q3q3; + hy = _2q0mx * q3 + my * q0q0 - _2q0mz * q1 + _2q1mx * q2 - my * q1q1 + + my * q2q2 + _2q2 * mz * q3 - my * q3q3; + _2bx = sqrtf(hx * hx + hy * hy); + _2bz = -_2q0mx * q2 + _2q0my * q1 + mz * q0q0 + _2q1mx * q3 - mz * q1q1 + + _2q2 * my * q3 - mz * q2q2 + mz * q3q3; + _4bx = 2.0f * _2bx; + _4bz = 2.0f * _2bz; + + // Gradient decent algorithm corrective step + s0 = -_2q2 * (2.0f * q1q3 - _2q0q2 - ax) + + _2q1 * (2.0f * q0q1 + _2q2q3 - ay) - + _2bz * q2 * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + + (-_2bx * q3 + _2bz * q1) * + (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + + _2bx * q2 * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); + s1 = _2q3 * (2.0f * q1q3 - _2q0q2 - ax) + + _2q0 * (2.0f * q0q1 + _2q2q3 - ay) - + 4.0f * q1 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + + _2bz * q3 * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + + (_2bx * q2 + _2bz * q0) * + (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + + (_2bx * q3 - _4bz * q1) * + (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); + s2 = -_2q0 * (2.0f * q1q3 - _2q0q2 - ax) + + _2q3 * (2.0f * q0q1 + _2q2q3 - ay) - + 4.0f * q2 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + + (-_4bx * q2 - _2bz * q0) * + (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + + (_2bx * q1 + _2bz * q3) * + (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + + (_2bx * q0 - _4bz * q2) * + (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); + s3 = _2q1 * (2.0f * q1q3 - _2q0q2 - ax) + + _2q2 * (2.0f * q0q1 + _2q2q3 - ay) + + (-_4bx * q3 + _2bz * q1) * + (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + + (-_2bx * q0 + _2bz * q2) * + (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + + _2bx * q1 * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); + recipNorm = invSqrt(s0 * s0 + s1 * s1 + s2 * s2 + + s3 * s3); // normalise step magnitude + s0 *= recipNorm; + s1 *= recipNorm; + s2 *= recipNorm; + s3 *= recipNorm; + + // Apply feedback step + qDot1 -= beta * s0; + qDot2 -= beta * s1; + qDot3 -= beta * s2; + qDot4 -= beta * s3; + } + + // Integrate rate of change of quaternion to yield quaternion + q0 += qDot1 * invSampleFreq; + q1 += qDot2 * invSampleFreq; + q2 += qDot3 * invSampleFreq; + q3 += qDot4 * invSampleFreq; + + // Normalise quaternion + recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); + q0 *= recipNorm; + q1 *= recipNorm; + q2 *= recipNorm; + q3 *= recipNorm; + anglesComputed = 0; +} + +//------------------------------------------------------------------------------------------- +// IMU algorithm update + +void Adafruit_Madgwick::updateIMU(float gx, float gy, float gz, float ax, + float ay, float az) { + float recipNorm; + float s0, s1, s2, s3; + float qDot1, qDot2, qDot3, qDot4; + float _2q0, _2q1, _2q2, _2q3, _4q0, _4q1, _4q2, _8q1, _8q2, q0q0, q1q1, q2q2, + q3q3; + + // Convert gyroscope degrees/sec to radians/sec + gx *= 0.0174533f; + gy *= 0.0174533f; + gz *= 0.0174533f; + + // Rate of change of quaternion from gyroscope + qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); + qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); + qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); + qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx); + + // Compute feedback only if accelerometer measurement valid (avoids NaN in + // accelerometer normalisation) + if (!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { + + // Normalise accelerometer measurement + recipNorm = invSqrt(ax * ax + ay * ay + az * az); + ax *= recipNorm; + ay *= recipNorm; + az *= recipNorm; + + // Auxiliary variables to avoid repeated arithmetic + _2q0 = 2.0f * q0; + _2q1 = 2.0f * q1; + _2q2 = 2.0f * q2; + _2q3 = 2.0f * q3; + _4q0 = 4.0f * q0; + _4q1 = 4.0f * q1; + _4q2 = 4.0f * q2; + _8q1 = 8.0f * q1; + _8q2 = 8.0f * q2; + q0q0 = q0 * q0; + q1q1 = q1 * q1; + q2q2 = q2 * q2; + q3q3 = q3 * q3; + + // Gradient decent algorithm corrective step + s0 = _4q0 * q2q2 + _2q2 * ax + _4q0 * q1q1 - _2q1 * ay; + s1 = _4q1 * q3q3 - _2q3 * ax + 4.0f * q0q0 * q1 - _2q0 * ay - _4q1 + + _8q1 * q1q1 + _8q1 * q2q2 + _4q1 * az; + s2 = 4.0f * q0q0 * q2 + _2q0 * ax + _4q2 * q3q3 - _2q3 * ay - _4q2 + + _8q2 * q1q1 + _8q2 * q2q2 + _4q2 * az; + s3 = 4.0f * q1q1 * q3 - _2q1 * ax + 4.0f * q2q2 * q3 - _2q2 * ay; + recipNorm = invSqrt(s0 * s0 + s1 * s1 + s2 * s2 + + s3 * s3); // normalise step magnitude + s0 *= recipNorm; + s1 *= recipNorm; + s2 *= recipNorm; + s3 *= recipNorm; + + // Apply feedback step + qDot1 -= beta * s0; + qDot2 -= beta * s1; + qDot3 -= beta * s2; + qDot4 -= beta * s3; + } + + // Integrate rate of change of quaternion to yield quaternion + q0 += qDot1 * invSampleFreq; + q1 += qDot2 * invSampleFreq; + q2 += qDot3 * invSampleFreq; + q3 += qDot4 * invSampleFreq; + + // Normalise quaternion + recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); + q0 *= recipNorm; + q1 *= recipNorm; + q2 *= recipNorm; + q3 *= recipNorm; + anglesComputed = 0; +} + +//------------------------------------------------------------------------------------------- +// Fast inverse square-root +// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root + +float Adafruit_Madgwick::invSqrt(float x) { + float halfx = 0.5f * x; + float y = x; + long i = *(long *)&y; + i = 0x5f3759df - (i >> 1); + y = *(float *)&i; + y = y * (1.5f - (halfx * y * y)); + y = y * (1.5f - (halfx * y * y)); + return y; +} + +//------------------------------------------------------------------------------------------- + +void Adafruit_Madgwick::computeAngles() { + roll = atan2f(q0 * q1 + q2 * q3, 0.5f - q1 * q1 - q2 * q2); + pitch = asinf(-2.0f * (q1 * q3 - q0 * q2)); + yaw = atan2f(q1 * q2 + q0 * q3, 0.5f - q2 * q2 - q3 * q3); + anglesComputed = 1; +} diff --git a/src/Adafruit_AHRS_Madgwick.h b/src/Adafruit_AHRS_Madgwick.h new file mode 100644 index 0000000..ad5a35a --- /dev/null +++ b/src/Adafruit_AHRS_Madgwick.h @@ -0,0 +1,87 @@ +//============================================================================================= +// Madgwick.h +//============================================================================================= +// +// Implementation of Madgwick's IMU and AHRS algorithms. +// See: http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/ +// +// From the x-io website "Open-source resources available on this website are +// provided under the GNU General Public Licence unless an alternative licence +// is provided in source." +// +// Date Author Notes +// 29/09/2011 SOH Madgwick Initial release +// 02/10/2011 SOH Madgwick Optimised for reduced CPU load +// +//============================================================================================= +#ifndef __Adafruit_Madgwick_h__ +#define __Adafruit_Madgwick_h__ +#include + +//-------------------------------------------------------------------------------------------- +// Variable declaration +class Adafruit_Madgwick { +private: + static float invSqrt(float x); + float beta; // algorithm gain + float q0; + float q1; + float q2; + float q3; // quaternion of sensor frame relative to auxiliary frame + float invSampleFreq; + float roll; + float pitch; + float yaw; + char anglesComputed; + void computeAngles(); + + //------------------------------------------------------------------------------------------- + // Function declarations +public: + Adafruit_Madgwick(void); + void begin(float sampleFrequency) { invSampleFreq = 1.0f / sampleFrequency; } + void update(float gx, float gy, float gz, float ax, float ay, float az, + float mx, float my, float mz); + void updateIMU(float gx, float gy, float gz, float ax, float ay, float az); + // float getPitch(){return atan2f(2.0f * q2 * q3 - 2.0f * q0 * q1, 2.0f * q0 * + // q0 + 2.0f * q3 * q3 - 1.0f);}; float getRoll(){return -1.0f * asinf(2.0f * + // q1 * q3 + 2.0f * q0 * q2);}; float getYaw(){return atan2f(2.0f * q1 * q2 + // - 2.0f * q0 * q3, 2.0f * q0 * q0 + 2.0f * q1 * q1 - 1.0f);}; + float getRoll() { + if (!anglesComputed) + computeAngles(); + return roll * 57.29578f; + } + float getPitch() { + if (!anglesComputed) + computeAngles(); + return pitch * 57.29578f; + } + float getYaw() { + if (!anglesComputed) + computeAngles(); + return yaw * 57.29578f + 180.0f; + } + float getRollRadians() { + if (!anglesComputed) + computeAngles(); + return roll; + } + float getPitchRadians() { + if (!anglesComputed) + computeAngles(); + return pitch; + } + float getYawRadians() { + if (!anglesComputed) + computeAngles(); + return yaw; + } + void getQuaternion(float *w, float *x, float *y, float *z) { + *w = q0; + *x = q1; + *y = q2; + *z = q3; + } +}; +#endif diff --git a/src/Adafruit_AHRS_Mahony.cpp b/src/Adafruit_AHRS_Mahony.cpp new file mode 100644 index 0000000..a3d54e2 --- /dev/null +++ b/src/Adafruit_AHRS_Mahony.cpp @@ -0,0 +1,272 @@ +//============================================================================================= +// Adafruit_Mahony.c +//============================================================================================= +// +// Madgwick's implementation of Mayhony's AHRS algorithm. +// See: http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/ +// +// From the x-io website "Open-source resources available on this website are +// provided under the GNU General Public Licence unless an alternative licence +// is provided in source." +// +// Date Author Notes +// 29/09/2011 SOH Madgwick Initial release +// 02/10/2011 SOH Madgwick Optimised for reduced CPU load +// +// Algorithm paper: +// http://ieeexplore.ieee.org/xpl/login.jsp?tp=&arnumber=4608934&url=http%3A%2F%2Fieeexplore.ieee.org%2Fstamp%2Fstamp.jsp%3Ftp%3D%26arnumber%3D4608934 +// +//============================================================================================= + +//------------------------------------------------------------------------------------------- +// Header files + +#include "Adafruit_AHRS_Mahony.h" +#include + +//------------------------------------------------------------------------------------------- +// Definitions + +#define DEFAULT_SAMPLE_FREQ 512.0f // sample frequency in Hz +#define twoKpDef (2.0f * 0.5f) // 2 * proportional gain +#define twoKiDef (2.0f * 0.0f) // 2 * integral gain + +//============================================================================================ +// Functions + +//------------------------------------------------------------------------------------------- +// AHRS algorithm update + +Adafruit_Mahony::Adafruit_Mahony() { + twoKp = twoKpDef; // 2 * proportional gain (Kp) + twoKi = twoKiDef; // 2 * integral gain (Ki) + q0 = 1.0f; + q1 = 0.0f; + q2 = 0.0f; + q3 = 0.0f; + integralFBx = 0.0f; + integralFBy = 0.0f; + integralFBz = 0.0f; + anglesComputed = 0; + invSampleFreq = 1.0f / DEFAULT_SAMPLE_FREQ; +} + +void Adafruit_Mahony::update(float gx, float gy, float gz, float ax, float ay, + float az, float mx, float my, float mz) { + float recipNorm; + float q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; + float hx, hy, bx, bz; + float halfvx, halfvy, halfvz, halfwx, halfwy, halfwz; + float halfex, halfey, halfez; + float qa, qb, qc; + + // Use IMU algorithm if magnetometer measurement invalid + // (avoids NaN in magnetometer normalisation) + if ((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { + updateIMU(gx, gy, gz, ax, ay, az); + return; + } + + // Convert gyroscope degrees/sec to radians/sec + gx *= 0.0174533f; + gy *= 0.0174533f; + gz *= 0.0174533f; + + // Compute feedback only if accelerometer measurement valid + // (avoids NaN in accelerometer normalisation) + if (!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { + + // Normalise accelerometer measurement + recipNorm = invSqrt(ax * ax + ay * ay + az * az); + ax *= recipNorm; + ay *= recipNorm; + az *= recipNorm; + + // Normalise magnetometer measurement + recipNorm = invSqrt(mx * mx + my * my + mz * mz); + mx *= recipNorm; + my *= recipNorm; + mz *= recipNorm; + + // Auxiliary variables to avoid repeated arithmetic + q0q0 = q0 * q0; + q0q1 = q0 * q1; + q0q2 = q0 * q2; + q0q3 = q0 * q3; + q1q1 = q1 * q1; + q1q2 = q1 * q2; + q1q3 = q1 * q3; + q2q2 = q2 * q2; + q2q3 = q2 * q3; + q3q3 = q3 * q3; + + // Reference direction of Earth's magnetic field + hx = 2.0f * + (mx * (0.5f - q2q2 - q3q3) + my * (q1q2 - q0q3) + mz * (q1q3 + q0q2)); + hy = 2.0f * + (mx * (q1q2 + q0q3) + my * (0.5f - q1q1 - q3q3) + mz * (q2q3 - q0q1)); + bx = sqrtf(hx * hx + hy * hy); + bz = 2.0f * + (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2)); + + // Estimated direction of gravity and magnetic field + halfvx = q1q3 - q0q2; + halfvy = q0q1 + q2q3; + halfvz = q0q0 - 0.5f + q3q3; + halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2); + halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3); + halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2); + + // Error is sum of cross product between estimated direction + // and measured direction of field vectors + halfex = (ay * halfvz - az * halfvy) + (my * halfwz - mz * halfwy); + halfey = (az * halfvx - ax * halfvz) + (mz * halfwx - mx * halfwz); + halfez = (ax * halfvy - ay * halfvx) + (mx * halfwy - my * halfwx); + + // Compute and apply integral feedback if enabled + if (twoKi > 0.0f) { + // integral error scaled by Ki + integralFBx += twoKi * halfex * invSampleFreq; + integralFBy += twoKi * halfey * invSampleFreq; + integralFBz += twoKi * halfez * invSampleFreq; + gx += integralFBx; // apply integral feedback + gy += integralFBy; + gz += integralFBz; + } else { + integralFBx = 0.0f; // prevent integral windup + integralFBy = 0.0f; + integralFBz = 0.0f; + } + + // Apply proportional feedback + gx += twoKp * halfex; + gy += twoKp * halfey; + gz += twoKp * halfez; + } + + // Integrate rate of change of quaternion + gx *= (0.5f * invSampleFreq); // pre-multiply common factors + gy *= (0.5f * invSampleFreq); + gz *= (0.5f * invSampleFreq); + qa = q0; + qb = q1; + qc = q2; + q0 += (-qb * gx - qc * gy - q3 * gz); + q1 += (qa * gx + qc * gz - q3 * gy); + q2 += (qa * gy - qb * gz + q3 * gx); + q3 += (qa * gz + qb * gy - qc * gx); + + // Normalise quaternion + recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); + q0 *= recipNorm; + q1 *= recipNorm; + q2 *= recipNorm; + q3 *= recipNorm; + anglesComputed = 0; +} + +//------------------------------------------------------------------------------------------- +// IMU algorithm update + +void Adafruit_Mahony::updateIMU(float gx, float gy, float gz, float ax, + float ay, float az) { + float recipNorm; + float halfvx, halfvy, halfvz; + float halfex, halfey, halfez; + float qa, qb, qc; + + // Convert gyroscope degrees/sec to radians/sec + gx *= 0.0174533f; + gy *= 0.0174533f; + gz *= 0.0174533f; + + // Compute feedback only if accelerometer measurement valid + // (avoids NaN in accelerometer normalisation) + if (!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { + + // Normalise accelerometer measurement + recipNorm = invSqrt(ax * ax + ay * ay + az * az); + ax *= recipNorm; + ay *= recipNorm; + az *= recipNorm; + + // Estimated direction of gravity + halfvx = q1 * q3 - q0 * q2; + halfvy = q0 * q1 + q2 * q3; + halfvz = q0 * q0 - 0.5f + q3 * q3; + + // Error is sum of cross product between estimated + // and measured direction of gravity + halfex = (ay * halfvz - az * halfvy); + halfey = (az * halfvx - ax * halfvz); + halfez = (ax * halfvy - ay * halfvx); + + // Compute and apply integral feedback if enabled + if (twoKi > 0.0f) { + // integral error scaled by Ki + integralFBx += twoKi * halfex * invSampleFreq; + integralFBy += twoKi * halfey * invSampleFreq; + integralFBz += twoKi * halfez * invSampleFreq; + gx += integralFBx; // apply integral feedback + gy += integralFBy; + gz += integralFBz; + } else { + integralFBx = 0.0f; // prevent integral windup + integralFBy = 0.0f; + integralFBz = 0.0f; + } + + // Apply proportional feedback + gx += twoKp * halfex; + gy += twoKp * halfey; + gz += twoKp * halfez; + } + + // Integrate rate of change of quaternion + gx *= (0.5f * invSampleFreq); // pre-multiply common factors + gy *= (0.5f * invSampleFreq); + gz *= (0.5f * invSampleFreq); + qa = q0; + qb = q1; + qc = q2; + q0 += (-qb * gx - qc * gy - q3 * gz); + q1 += (qa * gx + qc * gz - q3 * gy); + q2 += (qa * gy - qb * gz + q3 * gx); + q3 += (qa * gz + qb * gy - qc * gx); + + // Normalise quaternion + recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); + q0 *= recipNorm; + q1 *= recipNorm; + q2 *= recipNorm; + q3 *= recipNorm; + anglesComputed = 0; +} + +//------------------------------------------------------------------------------------------- +// Fast inverse square-root +// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root + +float Adafruit_Mahony::invSqrt(float x) { + float halfx = 0.5f * x; + float y = x; + long i = *(long *)&y; + i = 0x5f3759df - (i >> 1); + y = *(float *)&i; + y = y * (1.5f - (halfx * y * y)); + y = y * (1.5f - (halfx * y * y)); + return y; +} + +//------------------------------------------------------------------------------------------- + +void Adafruit_Mahony::computeAngles() { + roll = atan2f(q0 * q1 + q2 * q3, 0.5f - q1 * q1 - q2 * q2); + pitch = asinf(-2.0f * (q1 * q3 - q0 * q2)); + yaw = atan2f(q1 * q2 + q0 * q3, 0.5f - q2 * q2 - q3 * q3); + anglesComputed = 1; +} + +//============================================================================================ +// END OF CODE +//============================================================================================ diff --git a/src/Adafruit_AHRS_Mahony.h b/src/Adafruit_AHRS_Mahony.h new file mode 100644 index 0000000..77d88ce --- /dev/null +++ b/src/Adafruit_AHRS_Mahony.h @@ -0,0 +1,81 @@ +//============================================================================================= +// Adafruit_AHRS_Mahony.h +//============================================================================================= +// +// Madgwick's implementation of Mayhony's AHRS algorithm. +// See: http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/ +// +// Date Author Notes +// 29/09/2011 SOH Madgwick Initial release +// 02/10/2011 SOH Madgwick Optimised for reduced CPU load +// +//============================================================================================= +#ifndef __Adafruit_Mahony_h__ +#define __Adafruit_Mahony_h__ +#include + +//-------------------------------------------------------------------------------------------- +// Variable declaration + +class Adafruit_Mahony { +private: + float twoKp; // 2 * proportional gain (Kp) + float twoKi; // 2 * integral gain (Ki) + float q0, q1, q2, + q3; // quaternion of sensor frame relative to auxiliary frame + float integralFBx, integralFBy, + integralFBz; // integral error terms scaled by Ki + float invSampleFreq; + float roll, pitch, yaw; + char anglesComputed; + static float invSqrt(float x); + void computeAngles(); + + //------------------------------------------------------------------------------------------- + // Function declarations + +public: + Adafruit_Mahony(); + void begin(float sampleFrequency) { invSampleFreq = 1.0f / sampleFrequency; } + void update(float gx, float gy, float gz, float ax, float ay, float az, + float mx, float my, float mz); + void updateIMU(float gx, float gy, float gz, float ax, float ay, float az); + float getRoll() { + if (!anglesComputed) + computeAngles(); + return roll * 57.29578f; + } + float getPitch() { + if (!anglesComputed) + computeAngles(); + return pitch * 57.29578f; + } + float getYaw() { + if (!anglesComputed) + computeAngles(); + return yaw * 57.29578f + 180.0f; + } + float getRollRadians() { + if (!anglesComputed) + computeAngles(); + return roll; + } + float getPitchRadians() { + if (!anglesComputed) + computeAngles(); + return pitch; + } + float getYawRadians() { + if (!anglesComputed) + computeAngles(); + return yaw; + } + void getQuaternion(float *w, float *x, float *y, float *z) { + *w = q0; + *x = q1; + *y = q2; + *z = q3; + } +}; + +#endif diff --git a/src/Adafruit_AHRS_NXPFusion.cpp b/src/Adafruit_AHRS_NXPFusion.cpp new file mode 100644 index 0000000..d4deaa0 --- /dev/null +++ b/src/Adafruit_AHRS_NXPFusion.cpp @@ -0,0 +1,1487 @@ +// Copyright (c) 2014, Freescale Semiconductor, Inc. +// All rights reserved. +// vim: set ts=4: +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Freescale Semiconductor, Inc. nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL FREESCALE SEMICONDUCTOR, INC. BE LIABLE FOR +// ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +// OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// This is the file that contains the fusion routines. It is STRONGLY +// RECOMMENDED that the casual developer NOT TOUCH THIS FILE. The mathematics +// behind this file is extremely complex, and it will be very easy (almost +// inevitable) that you screw it up. +// + +#include "Adafruit_AHRS_NXPFusion.h" + +// kalman filter noise variances +#define FQVA_9DOF_GBY_KALMAN 2E-6F // accelerometer noise g^2 so 1.4mg RMS +#define FQVM_9DOF_GBY_KALMAN 0.1F // magnetometer noise uT^2 +#define FQVG_9DOF_GBY_KALMAN 0.3F // gyro noise (deg/s)^2 +#define FQWB_9DOF_GBY_KALMAN \ + 1E-9F // gyro offset drift (deg/s)^2: 1E-9 implies 0.09deg/s max at 50Hz +#define FQWA_9DOF_GBY_KALMAN \ + 1E-4F // linear acceleration drift g^2 (increase slows convergence to g but + // reduces sensitivity to shake) +#define FQWD_9DOF_GBY_KALMAN \ + 0.5F // magnetic disturbance drift uT^2 (increase slows convergence to B but + // reduces sensitivity to magnet) +// initialization of Qw covariance matrix +#define FQWINITTHTH_9DOF_GBY_KALMAN 2000E-5F // th_e * th_e terms +#define FQWINITBB_9DOF_GBY_KALMAN 250E-3F // b_e * b_e terms +#define FQWINITTHB_9DOF_GBY_KALMAN 0.0F // th_e * b_e terms +#define FQWINITAA_9DOF_GBY_KALMAN \ + 10E-5F // a_e * a_e terms (increase slows convergence to g but reduces + // sensitivity to shake) +#define FQWINITDD_9DOF_GBY_KALMAN \ + 600E-3F // d_e * d_e terms (increase slows convergence to B but reduces + // sensitivity to magnet) +// linear acceleration and magnetic disturbance time constants +#define FCA_9DOF_GBY_KALMAN 0.5F // linear acceleration decay factor +#define FCD_9DOF_GBY_KALMAN 0.5F // magnetic disturbance decay factor +// maximum geomagnetic inclination angle tracked by Kalman filter +#define SINDELTAMAX \ + 0.9063078F // sin of max +ve geomagnetic inclination angle: here 65.0 deg +#define COSDELTAMAX \ + 0.4226183F // cos of max +ve geomagnetic inclination angle: here 65.0 deg +#define DEFAULTB 50.0F // default geomagnetic field (uT) +#define X 0 // vector components +#define Y 1 +#define Z 2 +#define FDEGTORAD 0.01745329251994F // degrees to radians conversion = pi / 180 +#define FRADTODEG 57.2957795130823F // radians to degrees conversion = 180 / pi +#define ONEOVER48 0.02083333333F // 1 / 48 +#define ONEOVER3840 0.0002604166667F // 1 / 3840 + +#define Quaternion_t Adafruit_NXPSensorFusion::Quaternion_t + +static void fqAeq1(Quaternion_t *pqA); +static void feCompassNED(float fR[][3], float *pfDelta, const float fBc[], + const float fGp[]); +static void fNEDAnglesDegFromRotationMatrix(float R[][3], float *pfPhiDeg, + float *pfTheDeg, float *pfPsiDeg, + float *pfRhoDeg, float *pfChiDeg); +static void fQuaternionFromRotationMatrix(float R[][3], Quaternion_t *pq); +static void fQuaternionFromRotationVectorDeg(Quaternion_t *pq, + const float rvecdeg[], + float fscaling); +static void fRotationMatrixFromQuaternion(float R[][3], const Quaternion_t *pq); +static void fRotationVectorDegFromQuaternion(Quaternion_t *pq, float rvecdeg[]); +static void qAeqAxB(Quaternion_t *pqA, const Quaternion_t *pqB); +static void qAeqBxC(Quaternion_t *pqA, const Quaternion_t *pqB, + const Quaternion_t *pqC); +// static Quaternion_t qconjgAxB(const Quaternion_t *pqA, const Quaternion_t +// *pqB); +static void fqAeqNormqA(Quaternion_t *pqA); +static float fasin_deg(float x); +static float facos_deg(float x); +static float fatan_deg(float x); +static float fatan2_deg(float y, float x); +static float fatan_15deg(float x); + +extern "C" { +void f3x3matrixAeqI(float A[][3]); +void fmatrixAeqI(float *A[], int16_t rc); +void f3x3matrixAeqScalar(float A[][3], float Scalar); +void f3x3matrixAeqInvSymB(float A[][3], float B[][3]); +void f3x3matrixAeqAxScalar(float A[][3], float Scalar); +void f3x3matrixAeqMinusA(float A[][3]); +float f3x3matrixDetA(float A[][3]); +void eigencompute(float A[][10], float eigval[], float eigvec[][10], int8_t n); +void fmatrixAeqInvA(float *A[], int8_t iColInd[], int8_t iRowInd[], + int8_t iPivot[], int8_t isize); +void fmatrixAeqRenormRotA(float A[][3]); +} + +// initialize the 9DOF Kalman filter +void Adafruit_NXPSensorFusion::begin(float sampleRate) { + int8_t i, j; + + // reset the flag denoting that a first 9DOF orientation lock has been + // achieved + FirstOrientationLock = 0; + + // compute and store useful product terms to save floating point calculations + // later + Fastdeltat = 1.0f / sampleRate; + deltat = Fastdeltat; + deltatsq = deltat * deltat; + casq = FCA_9DOF_GBY_KALMAN * FCA_9DOF_GBY_KALMAN; + cdsq = FCD_9DOF_GBY_KALMAN * FCD_9DOF_GBY_KALMAN; + QwbplusQvG = FQWB_9DOF_GBY_KALMAN + FQVG_9DOF_GBY_KALMAN; + + // initialize the fixed entries in the measurement matrix C + for (i = 0; i < 6; i++) { + for (j = 0; j < 12; j++) { + C6x12[i][j] = 0.0F; + } + } + C6x12[0][6] = C6x12[1][7] = C6x12[2][8] = 1.0F; + C6x12[3][9] = C6x12[4][10] = C6x12[5][11] = -1.0F; + + // zero a posteriori orientation, error vector xe+ (thetae+, be+, de+, ae+) + // and b+ and inertial + f3x3matrixAeqI(RPl); + fqAeq1(&qPl); + for (i = X; i <= Z; i++) { + ThErrPl[i] = bErrPl[i] = aErrSePl[i] = dErrSePl[i] = bPl[i] = 0.0F; + } + + // initialize the reference geomagnetic vector (uT, global frame) + DeltaPl = 0.0F; + // initialize NED geomagnetic vector to zero degrees inclination + mGl[X] = DEFAULTB; + mGl[Y] = 0.0F; + mGl[Z] = 0.0F; + + // initialize noise variances for Qv and Qw matrix updates + QvAA = FQVA_9DOF_GBY_KALMAN + FQWA_9DOF_GBY_KALMAN + + FDEGTORAD * FDEGTORAD * deltatsq * + (FQWB_9DOF_GBY_KALMAN + FQVG_9DOF_GBY_KALMAN); + QvMM = FQVM_9DOF_GBY_KALMAN + FQWD_9DOF_GBY_KALMAN + + FDEGTORAD * FDEGTORAD * deltatsq * DEFAULTB * DEFAULTB * + (FQWB_9DOF_GBY_KALMAN + FQVG_9DOF_GBY_KALMAN); + + // initialize the 12x12 noise covariance matrix Qw of the a priori error + // vector xe- Qw is then recursively updated as P+ = (1 - K * C) * P- = (1 - K + // * C) * Qw and Qw updated from P+ zero the matrix Qw + for (i = 0; i < 12; i++) { + for (j = 0; j < 12; j++) { + Qw12x12[i][j] = 0.0F; + } + } + // loop over non-zero values + for (i = 0; i < 3; i++) { + // theta_e * theta_e terms + Qw12x12[i][i] = FQWINITTHTH_9DOF_GBY_KALMAN; + // b_e * b_e terms + Qw12x12[i + 3][i + 3] = FQWINITBB_9DOF_GBY_KALMAN; + // th_e * b_e terms + Qw12x12[i][i + 3] = Qw12x12[i + 3][i] = FQWINITTHB_9DOF_GBY_KALMAN; + // a_e * a_e terms + Qw12x12[i + 6][i + 6] = FQWINITAA_9DOF_GBY_KALMAN; + // d_e * d_e terms + Qw12x12[i + 9][i + 9] = FQWINITDD_9DOF_GBY_KALMAN; + } + + // clear the reset flag + resetflag = 0; +} + +// 9DOF orientation function implemented using a 12 element Kalman filter +// void fRun_9DOF_GBY_KALMAN(SV_9DOF_GBY_KALMAN_t *SV, +// const AccelSensor_t *Accel, const MagSensor_t *Mag, const GyroSensor_t *Gyro, +// const MagCalibration_t *MagCal) + +void Adafruit_NXPSensorFusion::update(float gx, float gy, float gz, float ax, + float ay, float az, float mx, float my, + float mz) { + float Accel[3] = {ax, ay, az}; // Accel + float Yp[3] = {gx, gy, gz}; // Gryo + float Mag[3] = {mx, my, mz}; // Mag + + // local scalars and arrays + float fopp, fadj, fhyp; // opposite, adjacent and hypoteneuse + float fsindelta, fcosdelta; // sin and cos of inclination angle delta + float rvec[3]; // rotation vector + float ftmp; // scratch variable + float ftmpA12x6[12][6]; // scratch array + int8_t i, j, k; // loop counters + int8_t iMagJamming; // magnetic jamming flag + int8_t ValidMagCal; + + // assorted array pointers + float *pfPPlus12x12ij; + float *pfPPlus12x12kj; + float *pfQw12x12ij; + float *pfQw12x12ik; + float *pfQw12x12kj; + float *pfK12x6ij; + float *pfK12x6ik; + float *pftmpA12x6ik; + float *pftmpA12x6kj; + float *pftmpA12x6ij; + float *pfC6x12ik; + float *pfC6x12jk; + + // working arrays for 6x6 matrix inversion + float *pfRows[6]; + int8_t iColInd[6]; + int8_t iRowInd[6]; + int8_t iPivot[6]; + + // do a reset and return if requested + if (resetflag) { + begin(1.0f / deltat); + return; + } + + // ********************************************************************************* + // initial orientation lock to accelerometer and magnetometer eCompass + // orientation + // ********************************************************************************* + if (fabsf(mx) >= 20.0f && fabsf(mx) >= 20.0f && fabsf(mx) >= 20.0f) { + ValidMagCal = 1; + } else { + ValidMagCal = 0; + } + + // do a once-only orientation lock after the first valid magnetic calibration + if (ValidMagCal && !FirstOrientationLock) { + // get the 6DOF orientation matrix and initial inclination angle + feCompassNED(RPl, &DeltaPl, Mag, Accel); + + // get the orientation quaternion from the orientation matrix + fQuaternionFromRotationMatrix(RPl, &qPl); + + // set the orientation lock flag so this initial alignment is only performed + // once + FirstOrientationLock = 1; + } + + // ********************************************************************************* + // calculate a priori rotation matrix + // ********************************************************************************* + + // compute the angular velocity from the averaged high frequency gyro reading. + // omega[k] = yG[k] - b-[k] = yG[k] - b+[k-1] (deg/s) + Omega[X] = Yp[X] - bPl[X]; + Omega[Y] = Yp[Y] - bPl[Y]; + Omega[Z] = Yp[Z] - bPl[Z]; + + // initialize the a priori orientation quaternion to the previous a posteriori + // estimate + qMi = qPl; + + // integrate the buffered high frequency (typically 200Hz) gyro readings + // for (j = 0; j < OVERSAMPLE_RATIO; j++) { + // compute the incremental fast (typically 200Hz) rotation vector rvec (deg) + for (i = X; i <= Z; i++) { + rvec[i] = (Yp[i] - bPl[i]) * Fastdeltat; + } + + // compute the incremental quaternion fDeltaq from the rotation vector + fQuaternionFromRotationVectorDeg(&Deltaq, rvec, 1.0F); + + // incrementally rotate the a priori orientation quaternion fqMi + // the a posteriori quaternion fqPl is re-normalized later so this update is + // stable + qAeqAxB(&qMi, &Deltaq); + //} + + // get the a priori rotation matrix from the a priori quaternion + fRotationMatrixFromQuaternion(RMi, &qMi); + + // ********************************************************************************* + // calculate a priori gyro, accelerometer and magnetometer estimates + // of the gravity and geomagnetic vectors and errors + // the most recent 'Fast' measurements are used to reduce phase errors + // ********************************************************************************* + + for (i = X; i <= Z; i++) { + // compute the a priori gyro estimate of the gravitational vector (g, sensor + // frame) using an absolute rotation of the global frame gravity vector + // (with magnitude 1g) NED gravity is along positive z axis + gSeGyMi[i] = RMi[i][Z]; + + // compute a priori acceleration (a-) (g, sensor frame) from decayed a + // posteriori estimate (g, sensor frame) + aSeMi[i] = FCA_9DOF_GBY_KALMAN * aSePl[i]; + + // compute the a priori gravity error vector (accelerometer minus gyro + // estimates) (g, sensor frame) NED and Windows 8 have positive sign for + // gravity: y = g - a and g = y + a + gErrSeMi[i] = Accel[i] + aSeMi[i] - gSeGyMi[i]; + + // compute the a priori gyro estimate of the geomagnetic vector (uT, sensor + // frame) using an absolute rotation of the global frame geomagnetic vector + // (with magnitude B uT) NED y component of geomagnetic vector in global + // frame is zero + mSeGyMi[i] = RMi[i][X] * mGl[X] + RMi[i][Z] * mGl[Z]; + + // compute the a priori geomagnetic error vector (magnetometer minus gyro + // estimates) (g, sensor frame) + mErrSeMi[i] = Mag[i] - mSeGyMi[i]; + } + + // ********************************************************************************* + // update variable elements of measurement matrix C + // ********************************************************************************* + + // update measurement matrix C with -alpha(g-)x and -alpha(m-)x from gyro (g, + // uT, sensor frame) + C6x12[0][1] = FDEGTORAD * gSeGyMi[Z]; + C6x12[0][2] = -FDEGTORAD * gSeGyMi[Y]; + C6x12[1][2] = FDEGTORAD * gSeGyMi[X]; + C6x12[1][0] = -C6x12[0][1]; + C6x12[2][0] = -C6x12[0][2]; + C6x12[2][1] = -C6x12[1][2]; + C6x12[3][1] = FDEGTORAD * mSeGyMi[Z]; + C6x12[3][2] = -FDEGTORAD * mSeGyMi[Y]; + C6x12[4][2] = FDEGTORAD * mSeGyMi[X]; + C6x12[4][0] = -C6x12[3][1]; + C6x12[5][0] = -C6x12[3][2]; + C6x12[5][1] = -C6x12[4][2]; + C6x12[0][4] = -deltat * C6x12[0][1]; + C6x12[0][5] = -deltat * C6x12[0][2]; + C6x12[1][5] = -deltat * C6x12[1][2]; + C6x12[1][3] = -C6x12[0][4]; + C6x12[2][3] = -C6x12[0][5]; + C6x12[2][4] = -C6x12[1][5]; + C6x12[3][4] = -deltat * C6x12[3][1]; + C6x12[3][5] = -deltat * C6x12[3][2]; + C6x12[4][5] = -deltat * C6x12[4][2]; + C6x12[4][3] = -C6x12[3][4]; + C6x12[5][3] = -C6x12[3][5]; + C6x12[5][4] = -C6x12[4][5]; + + // ********************************************************************************* + // calculate the Kalman gain matrix K + // K = P- * C^T * inv(C * P- * C^T + Qv) = Qw * C^T * inv(C * Qw * C^T + Qv) + // Qw is used as a proxy for P- throughout the code + // P+ is used here as a working array to reduce RAM usage and is re-computed + // later + // ********************************************************************************* + + // set ftmpA12x6 = P- * C^T = Qw * C^T where Qw and C are both sparse + // C also has a significant number of +1 and -1 entries + // ftmpA12x6 is also sparse but not symmetric + for (i = 0; i < 12; i++) { // loop over rows of ftmpA12x6 + // initialize pftmpA12x6ij for current i, j=0 + pftmpA12x6ij = ftmpA12x6[i]; + + for (j = 0; j < 6; j++) { // loop over columns of ftmpA12x6 + // zero ftmpA12x6[i][j] + *pftmpA12x6ij = 0.0F; + + // initialize pfC6x12jk for current j, k=0 + pfC6x12jk = C6x12[j]; + + // initialize pfQw12x12ik for current i, k=0 + pfQw12x12ik = Qw12x12[i]; + + // sum matrix products over inner loop over k + for (k = 0; k < 12; k++) { + if ((*pfQw12x12ik != 0.0F) && (*pfC6x12jk != 0.0F)) { + if (*pfC6x12jk == 1.0F) + *pftmpA12x6ij += *pfQw12x12ik; + else if (*pfC6x12jk == -1.0F) + *pftmpA12x6ij -= *pfQw12x12ik; + else + *pftmpA12x6ij += *pfQw12x12ik * *pfC6x12jk; + } + + // increment pfC6x12jk and pfQw12x12ik for next iteration of k + pfC6x12jk++; + pfQw12x12ik++; + } + + // increment pftmpA12x6ij for next iteration of j + pftmpA12x6ij++; + } + } + + // set symmetric P+ (6x6 scratch sub-matrix) to C * P- * C^T + Qv + // = C * (Qw * C^T) + Qv = C * ftmpA12x6 + Qv + // both C and ftmpA12x6 are sparse but not symmetric + for (i = 0; i < 6; i++) { // loop over rows of P+ + // initialize pfPPlus12x12ij for current i, j=i + pfPPlus12x12ij = PPlus12x12[i] + i; + + for (j = i; j < 6; j++) { // loop over above diagonal columns of P+ + // zero P+[i][j] + *pfPPlus12x12ij = 0.0F; + + // initialize pfC6x12ik for current i, k=0 + pfC6x12ik = C6x12[i]; + + // initialize pftmpA12x6kj for current j, k=0 + pftmpA12x6kj = *ftmpA12x6 + j; + + // sum matrix products over inner loop over k + for (k = 0; k < 12; k++) { + if ((*pfC6x12ik != 0.0F) && (*pftmpA12x6kj != 0.0F)) { + if (*pfC6x12ik == 1.0F) + *pfPPlus12x12ij += *pftmpA12x6kj; + else if (*pfC6x12ik == -1.0F) + *pfPPlus12x12ij -= *pftmpA12x6kj; + else + *pfPPlus12x12ij += *pfC6x12ik * *pftmpA12x6kj; + } + + // update pfC6x12ik and pftmpA12x6kj for next iteration of k + pfC6x12ik++; + pftmpA12x6kj += 6; + } + + // increment pfPPlus12x12ij for next iteration of j + pfPPlus12x12ij++; + } + } + + // add in noise covariance terms to the diagonal + PPlus12x12[0][0] += QvAA; + PPlus12x12[1][1] += QvAA; + PPlus12x12[2][2] += QvAA; + PPlus12x12[3][3] += QvMM; + PPlus12x12[4][4] += QvMM; + PPlus12x12[5][5] += QvMM; + + // copy above diagonal elements of P+ (6x6 scratch sub-matrix) to below + // diagonal + for (i = 1; i < 6; i++) + for (j = 0; j < i; j++) + PPlus12x12[i][j] = PPlus12x12[j][i]; + + // calculate inverse of P+ (6x6 scratch sub-matrix) = inv(C * P- * C^T + Qv) = + // inv(C * Qw * C^T + Qv) + for (i = 0; i < 6; i++) { + pfRows[i] = PPlus12x12[i]; + } + fmatrixAeqInvA(pfRows, iColInd, iRowInd, iPivot, 3); + + // set K = P- * C^T * inv(C * P- * C^T + Qv) = Qw * C^T * inv(C * Qw * C^T + + // Qv) = ftmpA12x6 * P+ (6x6 sub-matrix) ftmpA12x6 = Qw * C^T is sparse but P+ + // (6x6 sub-matrix) is not K is not symmetric because C is not symmetric + for (i = 0; i < 12; i++) { // loop over rows of K12x6 + // initialize pfK12x6ij for current i, j=0 + pfK12x6ij = K12x6[i]; + + for (j = 0; j < 6; j++) { // loop over columns of K12x6 + // zero the matrix element fK12x6[i][j] + *pfK12x6ij = 0.0F; + + // initialize pftmpA12x6ik for current i, k=0 + pftmpA12x6ik = ftmpA12x6[i]; + + // initialize pfPPlus12x12kj for current j, k=0 + pfPPlus12x12kj = *PPlus12x12 + j; + + // sum matrix products over inner loop over k + for (k = 0; k < 6; k++) { + if (*pftmpA12x6ik != 0.0F) { + *pfK12x6ij += *pftmpA12x6ik * *pfPPlus12x12kj; + } + + // increment pftmpA12x6ik and pfPPlus12x12kj for next iteration of k + pftmpA12x6ik++; + pfPPlus12x12kj += 12; + } + + // increment pfK12x6ij for the next iteration of j + pfK12x6ij++; + } + } + + // ********************************************************************************* + // calculate a posteriori error estimate: xe+ = K * ze- + // ********************************************************************************* + + // first calculate all four error vector components using accelerometer error + // component only for fThErrPl, fbErrPl, faErrSePl but also magnetometer for + // fdErrSePl + for (i = X; i <= Z; i++) { + ThErrPl[i] = K12x6[i][0] * gErrSeMi[X] + K12x6[i][1] * gErrSeMi[Y] + + K12x6[i][2] * gErrSeMi[Z]; + bErrPl[i] = K12x6[i + 3][0] * gErrSeMi[X] + K12x6[i + 3][1] * gErrSeMi[Y] + + K12x6[i + 3][2] * gErrSeMi[Z]; + aErrSePl[i] = K12x6[i + 6][0] * gErrSeMi[X] + + K12x6[i + 6][1] * gErrSeMi[Y] + K12x6[i + 6][2] * gErrSeMi[Z]; + dErrSePl[i] = + K12x6[i + 9][0] * gErrSeMi[X] + K12x6[i + 9][1] * gErrSeMi[Y] + + K12x6[i + 9][2] * gErrSeMi[Z] + K12x6[i + 9][3] * mErrSeMi[X] + + K12x6[i + 9][4] * mErrSeMi[Y] + K12x6[i + 9][5] * mErrSeMi[Z]; + } + + // set the magnetic jamming flag if there is a significant magnetic error + // power after calibration + ftmp = dErrSePl[X] * dErrSePl[X] + dErrSePl[Y] * dErrSePl[Y] + + dErrSePl[Z] * dErrSePl[Z]; + // iMagJamming = (ValidMagCal) && (ftmp > MagCal->FourBsq); + iMagJamming = (ValidMagCal) && + (ftmp > (DEFAULTB * DEFAULTB * 4.0f)); // TODO: FourBsq.... + + // add the remaining magnetic error terms if there is calibration and no + // magnetic jamming + if (ValidMagCal && !iMagJamming) { + for (i = X; i <= Z; i++) { + ThErrPl[i] += K12x6[i][3] * mErrSeMi[X] + K12x6[i][4] * mErrSeMi[Y] + + K12x6[i][5] * mErrSeMi[Z]; + bErrPl[i] += K12x6[i + 3][3] * mErrSeMi[X] + + K12x6[i + 3][4] * mErrSeMi[Y] + + K12x6[i + 3][5] * mErrSeMi[Z]; + aErrSePl[i] += K12x6[i + 6][3] * mErrSeMi[X] + + K12x6[i + 6][4] * mErrSeMi[Y] + + K12x6[i + 6][5] * mErrSeMi[Z]; + } + } + + // ********************************************************************************* + // apply the a posteriori error corrections to the a posteriori state vector + // ********************************************************************************* + + // get the a posteriori delta quaternion + fQuaternionFromRotationVectorDeg(&Deltaq, ThErrPl, -1.0F); + + // compute the a posteriori orientation quaternion fqPl = fqMi * + // Deltaq(-thetae+) the resulting quaternion may have negative scalar + // component q0 + qAeqBxC(&qPl, &qMi, &Deltaq); + + // normalize the a posteriori orientation quaternion to stop error propagation + // the renormalization function ensures that the scalar component q0 is + // non-negative + fqAeqNormqA(&qPl); + + // compute the a posteriori rotation matrix from the a posteriori quaternion + fRotationMatrixFromQuaternion(RPl, &qPl); + + // compute the rotation vector from the a posteriori quaternion + fRotationVectorDegFromQuaternion(&qPl, RVecPl); + + // update the a posteriori gyro offset vector b+ and + // assign the entire linear acceleration error vector to update the linear + // acceleration + for (i = X; i <= Z; i++) { + // b+[k] = b-[k] - be+[k] = b+[k] - be+[k] (deg/s) + bPl[i] -= bErrPl[i]; + // a+ = a- - ae+ (g, sensor frame) + aSePl[i] = aSeMi[i] - aErrSePl[i]; + } + + // compute the linear acceleration in the global frame from the accelerometer + // measurement (sensor frame). de-rotate the accelerometer measurement from + // the sensor to global frame using the inverse (transpose) of the a + // posteriori rotation matrix + aGlPl[X] = RPl[X][X] * Accel[X] + RPl[Y][X] * Accel[Y] + RPl[Z][X] * Accel[Z]; + aGlPl[Y] = RPl[X][Y] * Accel[X] + RPl[Y][Y] * Accel[Y] + RPl[Z][Y] * Accel[Z]; + aGlPl[Z] = RPl[X][Z] * Accel[X] + RPl[Y][Z] * Accel[Y] + RPl[Z][Z] * Accel[Z]; + // remove gravity and correct the sign if the coordinate system is gravity + // positive / acceleration negative gravity positive NED + aGlPl[X] = -aGlPl[X]; + aGlPl[Y] = -aGlPl[Y]; + aGlPl[Z] = -(aGlPl[Z] - 1.0F); + + // update the reference geomagnetic vector using magnetic disturbance error if + // valid calibration and no jamming + if (ValidMagCal && !iMagJamming) { + // de-rotate the NED magnetic disturbance error de+ from the sensor to the + // global reference frame using the inverse (transpose) of the a posteriori + // rotation matrix + dErrGlPl[X] = RPl[X][X] * dErrSePl[X] + RPl[Y][X] * dErrSePl[Y] + + RPl[Z][X] * dErrSePl[Z]; + dErrGlPl[Z] = RPl[X][Z] * dErrSePl[X] + RPl[Y][Z] * dErrSePl[Y] + + RPl[Z][Z] * dErrSePl[Z]; + + // compute components of the new geomagnetic vector + // the north pointing component fadj must always be non-negative + fopp = mGl[Z] - dErrGlPl[Z]; + fadj = mGl[X] - dErrGlPl[X]; + if (fadj < 0.0F) { + fadj = 0.0F; + } + fhyp = sqrtf(fopp * fopp + fadj * fadj); + + // check for the pathological condition of zero geomagnetic field + if (fhyp != 0.0F) { + // compute the sine and cosine of the new geomagnetic vector + ftmp = 1.0F / fhyp; + fsindelta = fopp * ftmp; + fcosdelta = fadj * ftmp; + + // limit the inclination angle between limits to prevent runaway + if (fsindelta > SINDELTAMAX) { + fsindelta = SINDELTAMAX; + fcosdelta = COSDELTAMAX; + } else if (fsindelta < -SINDELTAMAX) { + fsindelta = -SINDELTAMAX; + fcosdelta = COSDELTAMAX; + } + + // compute the new geomagnetic vector (always north pointing) + DeltaPl = fasin_deg(fsindelta); + // mGl[X] = MagCal->B * fcosdelta; // TODO: MagCal->B + // mGl[Z] = MagCal->B * fsindelta; + mGl[X] = DEFAULTB * fcosdelta; // TODO: MagCal->B + mGl[Z] = DEFAULTB * fsindelta; + } // end hyp == 0.0F + } // end ValidMagCal + + // ********************************************************************************* + // compute the a posteriori Euler angles from the orientation matrix + // ********************************************************************************* + + // calculate the NED Euler angles + fNEDAnglesDegFromRotationMatrix(RPl, &PhiPl, &ThePl, &PsiPl, &RhoPl, &ChiPl); + + // *********************************************************************************** + // calculate (symmetric) a posteriori error covariance matrix P+ + // P+ = (I12 - K * C) * P- = (I12 - K * C) * Qw = Qw - K * (C * Qw) + // both Qw and P+ are used as working arrays in this section + // at the end of this section, P+ is valid but Qw is over-written + // *********************************************************************************** + + // set P+ (6x12 scratch sub-matrix) to the product C (6x12) * Qw (12x12) + // where both C and Qw are sparse and C has a significant number of +1 and -1 + // entries the resulting matrix is sparse but not symmetric + for (i = 0; i < 6; i++) { + // initialize pfPPlus12x12ij for current i, j=0 + pfPPlus12x12ij = PPlus12x12[i]; + + for (j = 0; j < 12; j++) { + // zero P+[i][j] + *pfPPlus12x12ij = 0.0F; + + // initialize pfC6x12ik for current i, k=0 + pfC6x12ik = C6x12[i]; + + // initialize pfQw12x12kj for current j, k=0 + pfQw12x12kj = &Qw12x12[0][j]; + + // sum matrix products over inner loop over k + for (k = 0; k < 12; k++) { + if ((*pfC6x12ik != 0.0F) && (*pfQw12x12kj != 0.0F)) { + if (*pfC6x12ik == 1.0F) + *pfPPlus12x12ij += *pfQw12x12kj; + else if (*pfC6x12ik == -1.0F) + *pfPPlus12x12ij -= *pfQw12x12kj; + else + *pfPPlus12x12ij += *pfC6x12ik * *pfQw12x12kj; + } + + // update pfC6x12ik and pfQw12x12kj for next iteration of k + pfC6x12ik++; + pfQw12x12kj += 12; + } + + // increment pfPPlus12x12ij for next iteration of j + pfPPlus12x12ij++; + } + } + + // compute P+ = (I12 - K * C) * Qw = Qw - K * (C * Qw) = Qw - K * P+ (6x12 + // sub-matrix) storing result P+ in Qw and over-writing Qw which is OK since + // Qw is later computed from P+ where working array P+ (6x12 sub-matrix) is + // sparse but K is not sparse only on and above diagonal terms of P+ are + // computed since P+ is symmetric + for (i = 0; i < 12; i++) { + // initialize pfQw12x12ij for current i, j=i + pfQw12x12ij = Qw12x12[i] + i; + + for (j = i; j < 12; j++) { + // initialize pfK12x6ik for current i, k=0 + pfK12x6ik = K12x6[i]; + + // initialize pfPPlus12x12kj for current j, k=0 + pfPPlus12x12kj = *PPlus12x12 + j; + + // compute on and above diagonal matrix entry + for (k = 0; k < 6; k++) { + // check for non-zero values since P+ (6x12 scratch sub-matrix) is + // sparse + if (*pfPPlus12x12kj != 0.0F) { + *pfQw12x12ij -= *pfK12x6ik * *pfPPlus12x12kj; + } + // increment pfK12x6ik and pfPPlus12x12kj for next iteration of k + pfK12x6ik++; + pfPPlus12x12kj += 12; + } + + // increment pfQw12x12ij for next iteration of j + pfQw12x12ij++; + } + } + + // Qw now holds the on and above diagonal elements of P+ + // so perform a simple copy to the all elements of P+ + // after execution of this code P+ is valid but Qw remains invalid + for (i = 0; i < 12; i++) { + // initialize pfPPlus12x12ij and pfQw12x12ij for current i, j=i + pfPPlus12x12ij = PPlus12x12[i] + i; + pfQw12x12ij = Qw12x12[i] + i; + + // copy the on-diagonal elements and increment pointers to enter loop at + // j=i+1 + *(pfPPlus12x12ij++) = *(pfQw12x12ij++); + + // loop over above diagonal columns j copying to below-diagonal elements + for (j = i + 1; j < 12; j++) { + *(pfPPlus12x12ij++) = PPlus12x12[j][i] = *(pfQw12x12ij++); + } + } + + // ********************************************************************************* + // re-create the noise covariance matrix Qw=fn(P+) for the next iteration + // using the elements of P+ which are now valid + // Qw was over-written earlier but is here recomputed (all elements) + // ********************************************************************************* + + // zero the matrix Qw + for (i = 0; i < 12; i++) { + for (j = 0; j < 12; j++) { + Qw12x12[i][j] = 0.0F; + } + } + + // update the covariance matrix components + for (i = 0; i < 3; i++) { + // Qw[th-th-] = Qw[0-2][0-2] = E[th-(th-)^T] = Q[th+th+] + deltat^2 * + // (Q[b+b+] + (Qwb + QvG) * I) + Qw12x12[i][i] = + PPlus12x12[i][i] + deltatsq * (PPlus12x12[i + 3][i + 3] + QwbplusQvG); + + // Qw[b-b-] = Qw[3-5][3-5] = E[b-(b-)^T] = Q[b+b+] + Qwb * I + Qw12x12[i + 3][i + 3] = PPlus12x12[i + 3][i + 3] + FQWB_9DOF_GBY_KALMAN; + + // Qw[th-b-] = Qw[0-2][3-5] = E[th-(b-)^T] = -deltat * (Q[b+b+] + Qwb * I) = + // -deltat * Qw[b-b-] + Qw12x12[i][i + 3] = Qw12x12[i + 3][i] = -deltat * Qw12x12[i + 3][i + 3]; + + // Qw[a-a-] = Qw[6-8][6-8] = E[a-(a-)^T] = ca^2 * Q[a+a+] + Qwa * I + Qw12x12[i + 6][i + 6] = + casq * PPlus12x12[i + 6][i + 6] + FQWA_9DOF_GBY_KALMAN; + + // Qw[d-d-] = Qw[9-11][9-11] = E[d-(d-)^T] = cd^2 * Q[d+d+] + Qwd * I + Qw12x12[i + 9][i + 9] = + cdsq * PPlus12x12[i + 9][i + 9] + FQWD_9DOF_GBY_KALMAN; + } +} + +// compile time constants that are private to this file +#define SMALLQ0 \ + 0.01F // limit of quaternion scalar component requiring special algorithm +#define CORRUPTQUAT \ + 0.001F // threshold for deciding rotation quaternion is corrupt +#define SMALLMODULUS 0.01F // limit where rounding errors may appear + +// Aerospace NED accelerometer 3DOF tilt function computing rotation matrix fR +void f3DOFTiltNED(float fR[][3], float fGp[]) { + // the NED self-consistency twist occurs at 90 deg pitch + + // local variables + int16_t i; // counter + float fmodGxyz; // modulus of the x, y, z accelerometer readings + float fmodGyz; // modulus of the y, z accelerometer readings + float frecipmodGxyz; // reciprocal of modulus + float ftmp; // scratch variable + + // compute the accelerometer squared magnitudes + fmodGyz = fGp[Y] * fGp[Y] + fGp[Z] * fGp[Z]; + fmodGxyz = fmodGyz + fGp[X] * fGp[X]; + + // check for freefall special case where no solution is possible + if (fmodGxyz == 0.0F) { + f3x3matrixAeqI(fR); + return; + } + + // check for vertical up or down gimbal lock case + if (fmodGyz == 0.0F) { + f3x3matrixAeqScalar(fR, 0.0F); + fR[Y][Y] = 1.0F; + if (fGp[X] >= 0.0F) { + fR[X][Z] = 1.0F; + fR[Z][X] = -1.0F; + } else { + fR[X][Z] = -1.0F; + fR[Z][X] = 1.0F; + } + return; + } + + // compute moduli for the general case + fmodGyz = sqrtf(fmodGyz); + fmodGxyz = sqrtf(fmodGxyz); + frecipmodGxyz = 1.0F / fmodGxyz; + ftmp = fmodGxyz / fmodGyz; + + // normalize the accelerometer reading into the z column + for (i = X; i <= Z; i++) { + fR[i][Z] = fGp[i] * frecipmodGxyz; + } + + // construct x column of orientation matrix + fR[X][X] = fmodGyz * frecipmodGxyz; + fR[Y][X] = -fR[X][Z] * fR[Y][Z] * ftmp; + fR[Z][X] = -fR[X][Z] * fR[Z][Z] * ftmp; + + // // construct y column of orientation matrix + fR[X][Y] = 0.0F; + fR[Y][Y] = fR[Z][Z] * ftmp; + fR[Z][Y] = -fR[Y][Z] * ftmp; +} + +// Aerospace NED magnetometer 3DOF flat eCompass function computing rotation +// matrix fR +void f3DOFMagnetometerMatrixNED(float fR[][3], float fBc[]) { + // local variables + float fmodBxy; // modulus of the x, y magnetometer readings + + // compute the magnitude of the horizontal (x and y) magnetometer reading + fmodBxy = sqrtf(fBc[X] * fBc[X] + fBc[Y] * fBc[Y]); + + // check for zero field special case where no solution is possible + if (fmodBxy == 0.0F) { + f3x3matrixAeqI(fR); + return; + } + + // define the fixed entries in the z row and column + fR[Z][X] = fR[Z][Y] = fR[X][Z] = fR[Y][Z] = 0.0F; + fR[Z][Z] = 1.0F; + + // define the remaining entries + fR[X][X] = fR[Y][Y] = fBc[X] / fmodBxy; + fR[Y][X] = fBc[Y] / fmodBxy; + fR[X][Y] = -fR[Y][X]; +} + +// NED: 6DOF e-Compass function computing rotation matrix fR +static void feCompassNED(float fR[][3], float *pfDelta, const float fBc[], + const float fGp[]) { + // local variables + float fmod[3]; // column moduli + float fmodBc; // modulus of Bc + float fGdotBc; // dot product of vectors G.Bc + float ftmp; // scratch variable + int8_t i, j; // loop counters + + // set the inclination angle to zero in case it is not computed later + *pfDelta = 0.0F; + + // place the un-normalized gravity and geomagnetic vectors into the rotation + // matrix z and x axes + for (i = X; i <= Z; i++) { + fR[i][Z] = fGp[i]; + fR[i][X] = fBc[i]; + } + + // set y vector to vector product of z and x vectors + fR[X][Y] = fR[Y][Z] * fR[Z][X] - fR[Z][Z] * fR[Y][X]; + fR[Y][Y] = fR[Z][Z] * fR[X][X] - fR[X][Z] * fR[Z][X]; + fR[Z][Y] = fR[X][Z] * fR[Y][X] - fR[Y][Z] * fR[X][X]; + + // set x vector to vector product of y and z vectors + fR[X][X] = fR[Y][Y] * fR[Z][Z] - fR[Z][Y] * fR[Y][Z]; + fR[Y][X] = fR[Z][Y] * fR[X][Z] - fR[X][Y] * fR[Z][Z]; + fR[Z][X] = fR[X][Y] * fR[Y][Z] - fR[Y][Y] * fR[X][Z]; + + // calculate the rotation matrix column moduli + fmod[X] = + sqrtf(fR[X][X] * fR[X][X] + fR[Y][X] * fR[Y][X] + fR[Z][X] * fR[Z][X]); + fmod[Y] = + sqrtf(fR[X][Y] * fR[X][Y] + fR[Y][Y] * fR[Y][Y] + fR[Z][Y] * fR[Z][Y]); + fmod[Z] = + sqrtf(fR[X][Z] * fR[X][Z] + fR[Y][Z] * fR[Y][Z] + fR[Z][Z] * fR[Z][Z]); + + // normalize the rotation matrix columns + if (!((fmod[X] == 0.0F) || (fmod[Y] == 0.0F) || (fmod[Z] == 0.0F))) { + // loop over columns j + for (j = X; j <= Z; j++) { + ftmp = 1.0F / fmod[j]; + // loop over rows i + for (i = X; i <= Z; i++) { + // normalize by the column modulus + fR[i][j] *= ftmp; + } + } + } else { + // no solution is possible to set rotation to identity matrix + f3x3matrixAeqI(fR); + return; + } + + // compute the geomagnetic inclination angle + fmodBc = sqrtf(fBc[X] * fBc[X] + fBc[Y] * fBc[Y] + fBc[Z] * fBc[Z]); + fGdotBc = fGp[X] * fBc[X] + fGp[Y] * fBc[Y] + fGp[Z] * fBc[Z]; + if (!((fmod[Z] == 0.0F) || (fmodBc == 0.0F))) { + *pfDelta = fasin_deg(fGdotBc / (fmod[Z] * fmodBc)); + } +} + +// extract the NED angles in degrees from the NED rotation matrix +static void fNEDAnglesDegFromRotationMatrix(float R[][3], float *pfPhiDeg, + float *pfTheDeg, float *pfPsiDeg, + float *pfRhoDeg, float *pfChiDeg) { + // calculate the pitch angle -90.0 <= Theta <= 90.0 deg + *pfTheDeg = fasin_deg(-R[X][Z]); + + // calculate the roll angle range -180.0 <= Phi < 180.0 deg + *pfPhiDeg = fatan2_deg(R[Y][Z], R[Z][Z]); + + // map +180 roll onto the functionally equivalent -180 deg roll + if (*pfPhiDeg == 180.0F) { + *pfPhiDeg = -180.0F; + } + + // calculate the yaw (compass) angle 0.0 <= Psi < 360.0 deg + if (*pfTheDeg == 90.0F) { + // vertical upwards gimbal lock case + *pfPsiDeg = fatan2_deg(R[Z][Y], R[Y][Y]) + *pfPhiDeg; + } else if (*pfTheDeg == -90.0F) { + // vertical downwards gimbal lock case + *pfPsiDeg = fatan2_deg(-R[Z][Y], R[Y][Y]) - *pfPhiDeg; + } else { + // general case + *pfPsiDeg = fatan2_deg(R[X][Y], R[X][X]); + } + + // map yaw angle Psi onto range 0.0 <= Psi < 360.0 deg + if (*pfPsiDeg < 0.0F) { + *pfPsiDeg += 360.0F; + } + + // check for rounding errors mapping small negative angle to 360 deg + if (*pfPsiDeg >= 360.0F) { + *pfPsiDeg = 0.0F; + } + + // for NED, the compass heading Rho equals the yaw angle Psi + *pfRhoDeg = *pfPsiDeg; + + // calculate the tilt angle from vertical Chi (0 <= Chi <= 180 deg) + *pfChiDeg = facos_deg(R[Z][Z]); + + return; +} + +// computes normalized rotation quaternion from a rotation vector (deg) +static void fQuaternionFromRotationVectorDeg(Quaternion_t *pq, + const float rvecdeg[], + float fscaling) { + float fetadeg; // rotation angle (deg) + float fetarad; // rotation angle (rad) + float fetarad2; // eta (rad)^2 + float fetarad4; // eta (rad)^4 + float sinhalfeta; // sin(eta/2) + float fvecsq; // q1^2+q2^2+q3^2 + float ftmp; // scratch variable + + // compute the scaled rotation angle eta (deg) which can be both positve or + // negative + fetadeg = fscaling * sqrtf(rvecdeg[X] * rvecdeg[X] + rvecdeg[Y] * rvecdeg[Y] + + rvecdeg[Z] * rvecdeg[Z]); + fetarad = fetadeg * FDEGTORAD; + fetarad2 = fetarad * fetarad; + + // calculate the sine and cosine using small angle approximations or exact + // angles under sqrt(0.02)=0.141 rad is 8.1 deg and 1620 deg/s (=936deg/s in 3 + // axes) at 200Hz and 405 deg/s at 50Hz + if (fetarad2 <= 0.02F) { + // use MacLaurin series up to and including third order + sinhalfeta = fetarad * (0.5F - ONEOVER48 * fetarad2); + } else if (fetarad2 <= 0.06F) { + // use MacLaurin series up to and including fifth order + // angles under sqrt(0.06)=0.245 rad is 14.0 deg and 2807 deg/s (=1623deg/s + // in 3 axes) at 200Hz and 703 deg/s at 50Hz + fetarad4 = fetarad2 * fetarad2; + sinhalfeta = + fetarad * (0.5F - ONEOVER48 * fetarad2 + ONEOVER3840 * fetarad4); + } else { + // use exact calculation + sinhalfeta = (float)sinf(0.5F * fetarad); + } + + // compute the vector quaternion components q1, q2, q3 + if (fetadeg != 0.0F) { + // general case with non-zero rotation angle + ftmp = fscaling * sinhalfeta / fetadeg; + pq->q1 = rvecdeg[X] * ftmp; // q1 = nx * sin(eta/2) + pq->q2 = rvecdeg[Y] * ftmp; // q2 = ny * sin(eta/2) + pq->q3 = rvecdeg[Z] * ftmp; // q3 = nz * sin(eta/2) + } else { + // zero rotation angle giving zero vector component + pq->q1 = pq->q2 = pq->q3 = 0.0F; + } + + // compute the scalar quaternion component q0 by explicit normalization + // taking care to avoid rounding errors giving negative operand to sqrt + fvecsq = pq->q1 * pq->q1 + pq->q2 * pq->q2 + pq->q3 * pq->q3; + if (fvecsq <= 1.0F) { + // normal case + pq->q0 = sqrtf(1.0F - fvecsq); + } else { + // rounding errors are present + pq->q0 = 0.0F; + } +} + +// compute the orientation quaternion from a 3x3 rotation matrix +static void fQuaternionFromRotationMatrix(float R[][3], Quaternion_t *pq) { + float fq0sq; // q0^2 + float recip4q0; // 1/4q0 + + // the quaternion is not explicitly normalized in this function on the + // assumption that it is supplied with a normalized rotation matrix. if the + // rotation matrix is normalized then the quaternion will also be normalized + // even if the case of small q0 + + // get q0^2 and q0 + fq0sq = 0.25F * (1.0F + R[X][X] + R[Y][Y] + R[Z][Z]); + pq->q0 = sqrtf(fabs(fq0sq)); + + // normal case when q0 is not small meaning rotation angle not near 180 deg + if (pq->q0 > SMALLQ0) { + // calculate q1 to q3 (general case) + recip4q0 = 0.25F / pq->q0; + pq->q1 = recip4q0 * (R[Y][Z] - R[Z][Y]); + pq->q2 = recip4q0 * (R[Z][X] - R[X][Z]); + pq->q3 = recip4q0 * (R[X][Y] - R[Y][X]); + } else { + // special case of near 180 deg corresponds to nearly symmetric matrix + // which is not numerically well conditioned for division by small q0 + // instead get absolute values of q1 to q3 from leading diagonal + pq->q1 = sqrtf(fabs(0.5F * (1.0F + R[X][X]) - fq0sq)); + pq->q2 = sqrtf(fabs(0.5F * (1.0F + R[Y][Y]) - fq0sq)); + pq->q3 = sqrtf(fabs(0.5F * (1.0F + R[Z][Z]) - fq0sq)); + + // correct the signs of q1 to q3 by examining the signs of differenced + // off-diagonal terms + if ((R[Y][Z] - R[Z][Y]) < 0.0F) + pq->q1 = -pq->q1; + if ((R[Z][X] - R[X][Z]) < 0.0F) + pq->q2 = -pq->q2; + if ((R[X][Y] - R[Y][X]) < 0.0F) + pq->q3 = -pq->q3; + } +} + +// compute the rotation matrix from an orientation quaternion +static void fRotationMatrixFromQuaternion(float R[][3], + const Quaternion_t *pq) { + float f2q; + float f2q0q0, f2q0q1, f2q0q2, f2q0q3; + float f2q1q1, f2q1q2, f2q1q3; + float f2q2q2, f2q2q3; + float f2q3q3; + + // calculate products + f2q = 2.0F * pq->q0; + f2q0q0 = f2q * pq->q0; + f2q0q1 = f2q * pq->q1; + f2q0q2 = f2q * pq->q2; + f2q0q3 = f2q * pq->q3; + f2q = 2.0F * pq->q1; + f2q1q1 = f2q * pq->q1; + f2q1q2 = f2q * pq->q2; + f2q1q3 = f2q * pq->q3; + f2q = 2.0F * pq->q2; + f2q2q2 = f2q * pq->q2; + f2q2q3 = f2q * pq->q3; + f2q3q3 = 2.0F * pq->q3 * pq->q3; + + // calculate the rotation matrix assuming the quaternion is normalized + R[X][X] = f2q0q0 + f2q1q1 - 1.0F; + R[X][Y] = f2q1q2 + f2q0q3; + R[X][Z] = f2q1q3 - f2q0q2; + R[Y][X] = f2q1q2 - f2q0q3; + R[Y][Y] = f2q0q0 + f2q2q2 - 1.0F; + R[Y][Z] = f2q2q3 + f2q0q1; + R[Z][X] = f2q1q3 + f2q0q2; + R[Z][Y] = f2q2q3 - f2q0q1; + R[Z][Z] = f2q0q0 + f2q3q3 - 1.0F; +} + +// function calculate the rotation vector from a rotation matrix +void fRotationVectorDegFromRotationMatrix(float R[][3], float rvecdeg[]) { + float ftrace; // trace of the rotation matrix + float fetadeg; // rotation angle eta (deg) + float fmodulus; // modulus of axis * angle vector = 2|sin(eta)| + float ftmp; // scratch variable + + // calculate the trace of the rotation matrix = 1+2cos(eta) in range -1 to +3 + // and eta (deg) in range 0 to 180 deg inclusive + // checking for rounding errors that might take the trace outside this range + ftrace = R[X][X] + R[Y][Y] + R[Z][Z]; + if (ftrace >= 3.0F) { + fetadeg = 0.0F; + } else if (ftrace <= -1.0F) { + fetadeg = 180.0F; + } else { + fetadeg = acosf(0.5F * (ftrace - 1.0F)) * FRADTODEG; + } + + // set the rvecdeg vector to differences across the diagonal = 2*n*sin(eta) + // and calculate its modulus equal to 2|sin(eta)| + // the modulus approaches zero near 0 and 180 deg (when sin(eta) approaches + // zero) + rvecdeg[X] = R[Y][Z] - R[Z][Y]; + rvecdeg[Y] = R[Z][X] - R[X][Z]; + rvecdeg[Z] = R[X][Y] - R[Y][X]; + fmodulus = sqrtf(rvecdeg[X] * rvecdeg[X] + rvecdeg[Y] * rvecdeg[Y] + + rvecdeg[Z] * rvecdeg[Z]); + + // normalize the rotation vector for general, 0 deg and 180 deg rotation cases + if (fmodulus > SMALLMODULUS) { + // general case away from 0 and 180 deg rotation + ftmp = fetadeg / fmodulus; + rvecdeg[X] *= ftmp; // set x component to eta(deg) * nx + rvecdeg[Y] *= ftmp; // set y component to eta(deg) * ny + rvecdeg[Z] *= ftmp; // set z component to eta(deg) * nz + } else if (ftrace >= 0.0F) { + // near 0 deg rotation (trace = 3): matrix is nearly identity matrix + // R[Y][Z]-R[Z][Y]=2*nx*eta(rad) and similarly for other components + ftmp = 0.5F * FRADTODEG; + rvecdeg[X] *= ftmp; + rvecdeg[Y] *= ftmp; + rvecdeg[Z] *= ftmp; + } else { + // near 180 deg (trace = -1): matrix is nearly symmetric + // calculate the absolute value of the components of the axis-angle vector + rvecdeg[X] = 180.0F * sqrtf(fabs(0.5F * (R[X][X] + 1.0F))); + rvecdeg[Y] = 180.0F * sqrtf(fabs(0.5F * (R[Y][Y] + 1.0F))); + rvecdeg[Z] = 180.0F * sqrtf(fabs(0.5F * (R[Z][Z] + 1.0F))); + + // correct the signs of the three components by examining the signs of + // differenced off-diagonal terms + if ((R[Y][Z] - R[Z][Y]) < 0.0F) + rvecdeg[X] = -rvecdeg[X]; + if ((R[Z][X] - R[X][Z]) < 0.0F) + rvecdeg[Y] = -rvecdeg[Y]; + if ((R[X][Y] - R[Y][X]) < 0.0F) + rvecdeg[Z] = -rvecdeg[Z]; + } +} + +// computes rotation vector (deg) from rotation quaternion +static void fRotationVectorDegFromQuaternion(Quaternion_t *pq, + float rvecdeg[]) { + float fetarad; // rotation angle (rad) + float fetadeg; // rotation angle (deg) + float sinhalfeta; // sin(eta/2) + float ftmp; // scratch variable + + // calculate the rotation angle in the range 0 <= eta < 360 deg + if ((pq->q0 >= 1.0F) || (pq->q0 <= -1.0F)) { + // rotation angle is 0 deg or 2*180 deg = 360 deg = 0 deg + fetarad = 0.0F; + fetadeg = 0.0F; + } else { + // general case returning 0 < eta < 360 deg + fetarad = 2.0F * acosf(pq->q0); + fetadeg = fetarad * FRADTODEG; + } + + // map the rotation angle onto the range -180 deg <= eta < 180 deg + if (fetadeg >= 180.0F) { + fetadeg -= 360.0F; + fetarad = fetadeg * FDEGTORAD; + } + + // calculate sin(eta/2) which will be in the range -1 to +1 + sinhalfeta = (float)sinf(0.5F * fetarad); + + // calculate the rotation vector (deg) + if (sinhalfeta == 0.0F) { + // the rotation angle eta is zero and the axis is irrelevant + rvecdeg[X] = rvecdeg[Y] = rvecdeg[Z] = 0.0F; + } else { + // general case with non-zero rotation angle + ftmp = fetadeg / sinhalfeta; + rvecdeg[X] = pq->q1 * ftmp; + rvecdeg[Y] = pq->q2 * ftmp; + rvecdeg[Z] = pq->q3 * ftmp; + } +} + +#if 0 +// function low pass filters an orientation quaternion and computes virtual gyro rotation rate +void fLPFOrientationQuaternion(Quaternion_t *pq, Quaternion_t *pLPq, float flpf, float fdeltat, + float fOmega[], int32_t loopcounter) +{ + // local variables + Quaternion_t fdeltaq; // delta rotation quaternion + float rvecdeg[3]; // rotation vector (deg) + float ftmp; // scratch variable + + // initialize delay line on first pass: LPq[n]=q[n] + if (loopcounter == 0) { + *pLPq = *pq; + } + + // set fdeltaqn to the delta rotation quaternion conjg(fLPq[n-1) . fqn + fdeltaq = qconjgAxB(pLPq, pq); + if (fdeltaq.q0 < 0.0F) { + fdeltaq.q0 = -fdeltaq.q0; + fdeltaq.q1 = -fdeltaq.q1; + fdeltaq.q2 = -fdeltaq.q2; + fdeltaq.q3 = -fdeltaq.q3; + } + + // set ftmp to a scaled lpf value which equals flpf in the limit of small rotations (q0=1) + // but which rises as the delta rotation angle increases (q0 tends to zero) + ftmp = flpf + 0.75F * (1.0F - fdeltaq.q0); + if (ftmp > 1.0F) { + ftmp = 1.0F; + } + + // scale the delta rotation by the corrected lpf value + fdeltaq.q1 *= ftmp; + fdeltaq.q2 *= ftmp; + fdeltaq.q3 *= ftmp; + + // compute the scalar component q0 + ftmp = fdeltaq.q1 * fdeltaq.q1 + fdeltaq.q2 * fdeltaq.q2 + fdeltaq.q3 * fdeltaq.q3; + if (ftmp <= 1.0F) { + // normal case + fdeltaq.q0 = sqrtf(1.0F - ftmp); + } else { + // rounding errors present so simply set scalar component to 0 + fdeltaq.q0 = 0.0F; + } + + // calculate the delta rotation vector from fdeltaqn and the virtual gyro angular velocity (deg/s) + fRotationVectorDegFromQuaternion(&fdeltaq, rvecdeg); + ftmp = 1.0F / fdeltat; + fOmega[X] = rvecdeg[X] * ftmp; + fOmega[Y] = rvecdeg[Y] * ftmp; + fOmega[Z] = rvecdeg[Z] * ftmp; + + // set LPq[n] = LPq[n-1] . deltaq[n] + qAeqAxB(pLPq, &fdeltaq); + + // renormalize the low pass filtered quaternion to prevent error accumulation + // the renormalization function ensures that q0 is non-negative + fqAeqNormqA(pLPq); +} + +// function low pass filters a scalar +void fLPFScalar(float *pfS, float *pfLPS, float flpf, int32_t loopcounter) +{ + // set S[LP,n]=S[n] on first pass + if (loopcounter == 0) { + *pfLPS = *pfS; + } + + // apply the exponential low pass filter + *pfLPS += flpf * (*pfS - *pfLPS); +} +#endif + +// function compute the quaternion product qA * qB +static void qAeqBxC(Quaternion_t *pqA, const Quaternion_t *pqB, + const Quaternion_t *pqC) { + pqA->q0 = pqB->q0 * pqC->q0 - pqB->q1 * pqC->q1 - pqB->q2 * pqC->q2 - + pqB->q3 * pqC->q3; + pqA->q1 = pqB->q0 * pqC->q1 + pqB->q1 * pqC->q0 + pqB->q2 * pqC->q3 - + pqB->q3 * pqC->q2; + pqA->q2 = pqB->q0 * pqC->q2 - pqB->q1 * pqC->q3 + pqB->q2 * pqC->q0 + + pqB->q3 * pqC->q1; + pqA->q3 = pqB->q0 * pqC->q3 + pqB->q1 * pqC->q2 - pqB->q2 * pqC->q1 + + pqB->q3 * pqC->q0; +} + +// function compute the quaternion product qA = qA * qB +static void qAeqAxB(Quaternion_t *pqA, const Quaternion_t *pqB) { + Quaternion_t qProd; + + // perform the quaternion product + qProd.q0 = pqA->q0 * pqB->q0 - pqA->q1 * pqB->q1 - pqA->q2 * pqB->q2 - + pqA->q3 * pqB->q3; + qProd.q1 = pqA->q0 * pqB->q1 + pqA->q1 * pqB->q0 + pqA->q2 * pqB->q3 - + pqA->q3 * pqB->q2; + qProd.q2 = pqA->q0 * pqB->q2 - pqA->q1 * pqB->q3 + pqA->q2 * pqB->q0 + + pqA->q3 * pqB->q1; + qProd.q3 = pqA->q0 * pqB->q3 + pqA->q1 * pqB->q2 - pqA->q2 * pqB->q1 + + pqA->q3 * pqB->q0; + + // copy the result back into qA + *pqA = qProd; +} + +#if 0 +// function compute the quaternion product conjg(qA) * qB +static Quaternion_t qconjgAxB(const Quaternion_t *pqA, const Quaternion_t *pqB) +{ + Quaternion_t qProd; + + qProd.q0 = pqA->q0 * pqB->q0 + pqA->q1 * pqB->q1 + pqA->q2 * pqB->q2 + pqA->q3 * pqB->q3; + qProd.q1 = pqA->q0 * pqB->q1 - pqA->q1 * pqB->q0 - pqA->q2 * pqB->q3 + pqA->q3 * pqB->q2; + qProd.q2 = pqA->q0 * pqB->q2 + pqA->q1 * pqB->q3 - pqA->q2 * pqB->q0 - pqA->q3 * pqB->q1; + qProd.q3 = pqA->q0 * pqB->q3 - pqA->q1 * pqB->q2 + pqA->q2 * pqB->q1 - pqA->q3 * pqB->q0; + + return qProd; +} +#endif + +// function normalizes a rotation quaternion and ensures q0 is non-negative +static void fqAeqNormqA(Quaternion_t *pqA) { + float fNorm; // quaternion Norm + + // calculate the quaternion Norm + fNorm = sqrtf(pqA->q0 * pqA->q0 + pqA->q1 * pqA->q1 + pqA->q2 * pqA->q2 + + pqA->q3 * pqA->q3); + if (fNorm > CORRUPTQUAT) { + // general case + fNorm = 1.0F / fNorm; + pqA->q0 *= fNorm; + pqA->q1 *= fNorm; + pqA->q2 *= fNorm; + pqA->q3 *= fNorm; + } else { + // return with identity quaternion since the quaternion is corrupted + pqA->q0 = 1.0F; + pqA->q1 = pqA->q2 = pqA->q3 = 0.0F; + } + + // correct a negative scalar component if the function was called with + // negative q0 + if (pqA->q0 < 0.0F) { + pqA->q0 = -pqA->q0; + pqA->q1 = -pqA->q1; + pqA->q2 = -pqA->q2; + pqA->q3 = -pqA->q3; + } +} + +// set a quaternion to the unit quaternion +static void fqAeq1(Quaternion_t *pqA) { + pqA->q0 = 1.0F; + pqA->q1 = pqA->q2 = pqA->q3 = 0.0F; +} + +// function returns an approximation to angle(deg)=asin(x) for x in the range -1 +// <= x <= 1 and returns -90 <= angle <= 90 deg maximum error is 10.29E-6 deg +static float fasin_deg(float x) { + // for robustness, check for invalid argument + if (x >= 1.0F) + return 90.0F; + if (x <= -1.0F) + return -90.0F; + + // call the atan which will return an angle in the correct range -90 to 90 deg + // this line cannot fail from division by zero or negative square root since + // |x| < 1 + return (fatan_deg(x / sqrtf(1.0F - x * x))); +} + +// function returns an approximation to angle(deg)=acos(x) for x in the range -1 +// <= x <= 1 and returns 0 <= angle <= 180 deg maximum error is 14.67E-6 deg +static float facos_deg(float x) { + // for robustness, check for invalid arguments + if (x >= 1.0F) + return 0.0F; + if (x <= -1.0F) + return 180.0F; + + // call the atan which will return an angle in the incorrect range -90 to 90 + // deg these lines cannot fail from division by zero or negative square root + if (x == 0.0F) + return 90.0F; + if (x > 0.0F) + return fatan_deg((sqrtf(1.0F - x * x) / x)); + return 180.0F + fatan_deg((sqrtf(1.0F - x * x) / x)); +} + +// function returns angle in range -90 to 90 deg +// maximum error is 9.84E-6 deg +static float fatan_deg(float x) { + float fangledeg; // compute computed (deg) + int8_t ixisnegative; // argument x is negative + int8_t ixexceeds1; // argument x is greater than 1.0 + int8_t ixmapped; // argument in range tan(15 deg) to tan(45 deg)=1.0 + +#define TAN15DEG 0.26794919243F // tan(15 deg) = 2 - sqrt(3) +#define TAN30DEG 0.57735026919F // tan(30 deg) = 1/sqrt(3) + + // reset all flags + ixisnegative = ixexceeds1 = ixmapped = 0; + + // test for negative argument to allow use of tan(-x)=-tan(x) + if (x < 0.0F) { + x = -x; + ixisnegative = 1; + } + + // test for argument above 1 to allow use of atan(x)=pi/2-atan(1/x) + if (x > 1.0F) { + x = 1.0F / x; + ixexceeds1 = 1; + } + + // at this point, x is in the range 0 to 1 inclusive + // map argument onto range -tan(15 deg) to tan(15 deg) + // using tan(angle-30deg) = (tan(angle)-tan(30deg)) / (1 + + // tan(angle)tan(30deg)) tan(15deg) maps to tan(-15 deg) = -tan(15 deg) + // 1. maps to (sqrt(3) - 1) / (sqrt(3) + 1) = 2 - sqrt(3) = tan(15 deg) + if (x > TAN15DEG) { + x = (x - TAN30DEG) / (1.0F + TAN30DEG * x); + ixmapped = 1; + } + + // call the atan estimator to obtain -15 deg <= angle <= 15 deg + fangledeg = fatan_15deg(x); + + // undo the distortions applied earlier to obtain -90 deg <= angle <= 90 deg + if (ixmapped) + fangledeg += 30.0F; + if (ixexceeds1) + fangledeg = 90.0F - fangledeg; + if (ixisnegative) + fangledeg = -fangledeg; + + return (fangledeg); +} + +// function returns approximate atan2 angle in range -180 to 180 deg +// maximum error is 14.58E-6 deg +static float fatan2_deg(float y, float x) { + // check for zero x to avoid division by zero + if (x == 0.0F) { + // return 90 deg for positive y + if (y > 0.0F) + return 90.0F; + // return -90 deg for negative y + if (y < 0.0F) + return -90.0F; + // otherwise y= 0.0 and return 0 deg (invalid arguments) + return 0.0F; + } + + // from here onwards, x is guaranteed to be non-zero + // compute atan2 for quadrant 1 (0 to 90 deg) and quadrant 4 (-90 to 0 deg) + if (x > 0.0F) + return (fatan_deg(y / x)); + // compute atan2 for quadrant 2 (90 to 180 deg) + if ((x < 0.0F) && (y > 0.0F)) + return (180.0F + fatan_deg(y / x)); + // compute atan2 for quadrant 3 (-180 to -90 deg) + return (-180.0F + fatan_deg(y / x)); +} + +// approximation to inverse tan function (deg) for x in range +// -tan(15 deg) to tan(15 deg) giving an output -15 deg <= angle <= 15 deg +// using modified Pade[3/2] approximation +static float fatan_15deg(float x) { + float x2; // x^2 + +#define PADE_A \ + 96.644395816F // theoretical Pade[3/2] value is 5/3*180/PI=95.49296 +#define PADE_B \ + 25.086941612F // theoretical Pade[3/2] value is 4/9*180/PI=25.46479 +#define PADE_C 1.6867633134F // theoretical Pade[3/2] value is 5/3=1.66667 + + // compute the approximation to the inverse tangent + // the function is anti-symmetric as required for positive and negative + // arguments + x2 = x * x; + return (x * (PADE_A + x2 * PADE_B) / (PADE_C + x2)); +} diff --git a/src/Adafruit_AHRS_NXPFusion.h b/src/Adafruit_AHRS_NXPFusion.h new file mode 100644 index 0000000..743f774 --- /dev/null +++ b/src/Adafruit_AHRS_NXPFusion.h @@ -0,0 +1,114 @@ +#include + +// This is a modification of +// https://github.com/memsindustrygroup/Open-Source-Sensor-Fusion/blob/master/Sources/tasks.h +// by PJRC / Paul Stoffregen https://github.com/PaulStoffregen/NXPMotionSense + +// Copyright (c) 2014, Freescale Semiconductor, Inc. +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Freescale Semiconductor, Inc. nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL FREESCALE SEMICONDUCTOR, INC. BE LIABLE FOR +// ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +// OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// + +// changed class name to avoid collision +class Adafruit_NXPSensorFusion { +public: + void begin(float sampleRate = 100.0f); + void update(float gx, float gy, float gz, float ax, float ay, float az, + float mx, float my, float mz); + + float getRoll() { return PhiPl; } + float getPitch() { return ThePl; } + float getYaw() { return PsiPl; } + + typedef struct { + float q0; // w + float q1; // x + float q2; // y + float q3; // z + } Quaternion_t; + + // These are Madgwick & Mahony - extrinsic rotation reference (wrong!) + // float getPitch() {return atan2f(2.0f * qPl.q2 * qPl.q3 - 2.0f * qPl.q0 * + // qPl.q1, 2.0f * qPl.q0 * qPl.q0 + 2.0f * qPl.q3 * qPl.q3 - 1.0f);}; float + // getRoll() {return -1.0f * asinf(2.0f * qPl.q1 * qPl.q3 + 2.0f * qPl.q0 * + // qPl.q2);}; float getYaw() {return atan2f(2.0f * qPl.q1 * qPl.q2 - 2.0f * + // qPl.q0 * qPl.q3, 2.0f * qPl.q0 * qPl.q0 + 2.0f * qPl.q1 * qPl.q1 - 1.0f);}; + +private: + float PhiPl; // roll (deg) + float ThePl; // pitch (deg) + float PsiPl; // yaw (deg) + float RhoPl; // compass (deg) + float ChiPl; // tilt from vertical (deg) + // orientation matrix, quaternion and rotation vector + float RPl[3][3]; // a posteriori orientation matrix + Quaternion_t qPl; // a posteriori orientation quaternion + float RVecPl[3]; // rotation vector + // angular velocity + float Omega[3]; // angular velocity (deg/s) + // systick timer for benchmarking + int32_t systick; // systick timer; + // end: elements common to all motion state vectors + + // elements transmitted over bluetooth in kalman packet + float bPl[3]; // gyro offset (deg/s) + float ThErrPl[3]; // orientation error (deg) + float bErrPl[3]; // gyro offset error (deg/s) + // end elements transmitted in kalman packet + + float dErrGlPl[3]; // magnetic disturbance error (uT, global frame) + float dErrSePl[3]; // magnetic disturbance error (uT, sensor frame) + float aErrSePl[3]; // linear acceleration error (g, sensor frame) + float aSeMi[3]; // linear acceleration (g, sensor frame) + float DeltaPl; // inclination angle (deg) + float aSePl[3]; // linear acceleration (g, sensor frame) + float aGlPl[3]; // linear acceleration (g, global frame) + float gErrSeMi[3]; // difference (g, sensor frame) of gravity vector (accel) + // and gravity vector (gyro) + float mErrSeMi[3]; // difference (uT, sensor frame) of geomagnetic vector + // (magnetometer) and geomagnetic vector (gyro) + float gSeGyMi[3]; // gravity vector (g, sensor frame) measurement from gyro + float + mSeGyMi[3]; // geomagnetic vector (uT, sensor frame) measurement from gyro + float mGl[3]; // geomagnetic vector (uT, global frame) + float QvAA; // accelerometer terms of Qv + float QvMM; // magnetometer terms of Qv + float PPlus12x12[12][12]; // covariance matrix P+ + float K12x6[12][6]; // kalman filter gain matrix K + float Qw12x12[12][12]; // covariance matrix Qw + float C6x12[6][12]; // measurement matrix C + float RMi[3][3]; // a priori orientation matrix + Quaternion_t Deltaq; // delta quaternion + Quaternion_t qMi; // a priori orientation quaternion + float casq; // FCA * FCA; + float cdsq; // FCD * FCD; + float Fastdeltat; // sensor sampling interval (s) = 1 / SENSORFS + float deltat; // kalman filter sampling interval (s) = OVERSAMPLE_RATIO / + // SENSORFS + float deltatsq; // fdeltat * fdeltat + float QwbplusQvG; // FQWB + FQVG + int8_t + FirstOrientationLock; // denotes that 9DOF orientation has locked to 6DOF + int8_t resetflag; // flag to request re-initialization on next pass +}; diff --git a/src/Adafruit_AHRS_NXPmatrix.c b/src/Adafruit_AHRS_NXPmatrix.c new file mode 100644 index 0000000..a825794 --- /dev/null +++ b/src/Adafruit_AHRS_NXPmatrix.c @@ -0,0 +1,467 @@ +// Copyright (c) 2014, Freescale Semiconductor, Inc. +// All rights reserved. +// vim: set ts=4: +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Freescale Semiconductor, Inc. nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL FREESCALE SEMICONDUCTOR, INC. BE LIABLE FOR +// ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +// OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// This file contains matrix manipulation functions. +// + +#include +#include + +// compile time constants that are private to this file +#define CORRUPTMATRIX 0.001F // column vector modulus limit for rotation matrix + +// vector components +#define X 0 +#define Y 1 +#define Z 2 + +// function sets the 3x3 matrix A to the identity matrix +void f3x3matrixAeqI(float A[][3]) { + float *pAij; // pointer to A[i][j] + int8_t i, j; // loop counters + + for (i = 0; i < 3; i++) { + // set pAij to &A[i][j=0] + pAij = A[i]; + for (j = 0; j < 3; j++) { + *(pAij++) = 0.0F; + } + A[i][i] = 1.0F; + } +} + +// function sets the matrix A to the identity matrix +void fmatrixAeqI(float *A[], int16_t rc) { + // rc = rows and columns in A + + float *pAij; // pointer to A[i][j] + int8_t i, j; // loop counters + + for (i = 0; i < rc; i++) { + // set pAij to &A[i][j=0] + pAij = A[i]; + for (j = 0; j < rc; j++) { + *(pAij++) = 0.0F; + } + A[i][i] = 1.0F; + } +} + +// function sets every entry in the 3x3 matrix A to a constant scalar +void f3x3matrixAeqScalar(float A[][3], float Scalar) { + float *pAij; // pointer to A[i][j] + int8_t i, j; // counters + + for (i = 0; i < 3; i++) { + // set pAij to &A[i][j=0] + pAij = A[i]; + for (j = 0; j < 3; j++) { + *(pAij++) = Scalar; + } + } +} + +// function multiplies all elements of 3x3 matrix A by the specified scalar +void f3x3matrixAeqAxScalar(float A[][3], float Scalar) { + float *pAij; // pointer to A[i][j] + int8_t i, j; // loop counters + + for (i = 0; i < 3; i++) { + // set pAij to &A[i][j=0] + pAij = A[i]; + for (j = 0; j < 3; j++) { + *(pAij++) *= Scalar; + } + } +} + +// function negates all elements of 3x3 matrix A +void f3x3matrixAeqMinusA(float A[][3]) { + float *pAij; // pointer to A[i][j] + int8_t i, j; // loop counters + + for (i = 0; i < 3; i++) { + // set pAij to &A[i][j=0] + pAij = A[i]; + for (j = 0; j < 3; j++) { + *pAij = -*pAij; + pAij++; + } + } +} + +// function directly calculates the symmetric inverse of a symmetric 3x3 matrix +// only the on and above diagonal terms in B are used and need to be specified +void f3x3matrixAeqInvSymB(float A[][3], float B[][3]) { + float fB11B22mB12B12; // B[1][1] * B[2][2] - B[1][2] * B[1][2] + float fB12B02mB01B22; // B[1][2] * B[0][2] - B[0][1] * B[2][2] + float fB01B12mB11B02; // B[0][1] * B[1][2] - B[1][1] * B[0][2] + float ftmp; // determinant and then reciprocal + + // calculate useful products + fB11B22mB12B12 = B[1][1] * B[2][2] - B[1][2] * B[1][2]; + fB12B02mB01B22 = B[1][2] * B[0][2] - B[0][1] * B[2][2]; + fB01B12mB11B02 = B[0][1] * B[1][2] - B[1][1] * B[0][2]; + + // set ftmp to the determinant of the input matrix B + ftmp = B[0][0] * fB11B22mB12B12 + B[0][1] * fB12B02mB01B22 + + B[0][2] * fB01B12mB11B02; + + // set A to the inverse of B for any determinant except zero + if (ftmp != 0.0F) { + ftmp = 1.0F / ftmp; + A[0][0] = fB11B22mB12B12 * ftmp; + A[1][0] = A[0][1] = fB12B02mB01B22 * ftmp; + A[2][0] = A[0][2] = fB01B12mB11B02 * ftmp; + A[1][1] = (B[0][0] * B[2][2] - B[0][2] * B[0][2]) * ftmp; + A[2][1] = A[1][2] = (B[0][2] * B[0][1] - B[0][0] * B[1][2]) * ftmp; + A[2][2] = (B[0][0] * B[1][1] - B[0][1] * B[0][1]) * ftmp; + } else { + // provide the identity matrix if the determinant is zero + f3x3matrixAeqI(A); + } +} + +// function calculates the determinant of a 3x3 matrix +float f3x3matrixDetA(float A[][3]) { + return (A[X][X] * (A[Y][Y] * A[Z][Z] - A[Y][Z] * A[Z][Y]) + + A[X][Y] * (A[Y][Z] * A[Z][X] - A[Y][X] * A[Z][Z]) + + A[X][Z] * (A[Y][X] * A[Z][Y] - A[Y][Y] * A[Z][X])); +} + +// function computes all eigenvalues and eigenvectors of a real symmetric matrix +// A[0..n-1][0..n-1] stored in the top left of a 10x10 array A[10][10] A[][] is +// changed on output. eigval[0..n-1] returns the eigenvalues of A[][]. +// eigvec[0..n-1][0..n-1] returns the normalized eigenvectors of A[][] +// the eigenvectors are not sorted by value +void eigencompute(float A[][10], float eigval[], float eigvec[][10], int8_t n) { + // maximum number of iterations to achieve convergence: in practice 6 is + // typical +#define NITERATIONS 15 + + // various trig functions of the jacobi rotation angle phi + float cot2phi, tanhalfphi, tanphi, sinphi, cosphi; + // scratch variable to prevent over-writing during rotations + float ftmp; + // residue from remaining non-zero above diagonal terms + float residue; + // matrix row and column indices + int8_t ir, ic; + // general loop counter + int8_t j; + // timeout ctr for number of passes of the algorithm + int8_t ctr; + + // initialize eigenvectors matrix and eigenvalues array + for (ir = 0; ir < n; ir++) { + // loop over all columns + for (ic = 0; ic < n; ic++) { + // set on diagonal and off-diagonal elements to zero + eigvec[ir][ic] = 0.0F; + } + + // correct the diagonal elements to 1.0 + eigvec[ir][ir] = 1.0F; + + // initialize the array of eigenvalues to the diagonal elements of m + eigval[ir] = A[ir][ir]; + } + + // initialize the counter and loop until converged or NITERATIONS reached + ctr = 0; + do { + // compute the absolute value of the above diagonal elements as exit + // criterion + residue = 0.0F; + // loop over rows excluding last row + for (ir = 0; ir < n - 1; ir++) { + // loop over above diagonal columns + for (ic = ir + 1; ic < n; ic++) { + // accumulate the residual off diagonal terms which are being driven to + // zero + residue += fabsf(A[ir][ic]); + } + } + + // check if we still have work to do + if (residue > 0.0F) { + // loop over all rows with the exception of the last row (since only + // rotating above diagonal elements) + for (ir = 0; ir < n - 1; ir++) { + // loop over columns ic (where ic is always greater than ir since above + // diagonal) + for (ic = ir + 1; ic < n; ic++) { + // only continue with this element if the element is non-zero + if (fabsf(A[ir][ic]) > 0.0F) { + // calculate cot(2*phi) where phi is the Jacobi rotation angle + cot2phi = 0.5F * (eigval[ic] - eigval[ir]) / (A[ir][ic]); + + // calculate tan(phi) correcting sign to ensure the smaller solution + // is used + tanphi = 1.0F / (fabsf(cot2phi) + sqrtf(1.0F + cot2phi * cot2phi)); + if (cot2phi < 0.0F) { + tanphi = -tanphi; + } + + // calculate the sine and cosine of the Jacobi rotation angle phi + cosphi = 1.0F / sqrtf(1.0F + tanphi * tanphi); + sinphi = tanphi * cosphi; + + // calculate tan(phi/2) + tanhalfphi = sinphi / (1.0F + cosphi); + + // set tmp = tan(phi) times current matrix element used in update of + // leading diagonal elements + ftmp = tanphi * A[ir][ic]; + + // apply the jacobi rotation to diagonal elements [ir][ir] and + // [ic][ic] stored in the eigenvalue array eigval[ir] = eigval[ir] - + // tan(phi) * A[ir][ic] + eigval[ir] -= ftmp; + // eigval[ic] = eigval[ic] + tan(phi) * A[ir][ic] + eigval[ic] += ftmp; + + // by definition, applying the jacobi rotation on element ir, ic + // results in 0.0 + A[ir][ic] = 0.0F; + + // apply the jacobi rotation to all elements of the eigenvector + // matrix + for (j = 0; j < n; j++) { + // store eigvec[j][ir] + ftmp = eigvec[j][ir]; + // eigvec[j][ir] = eigvec[j][ir] - sin(phi) * (eigvec[j][ic] + + // tan(phi/2) * eigvec[j][ir]) + eigvec[j][ir] = + ftmp - sinphi * (eigvec[j][ic] + tanhalfphi * ftmp); + // eigvec[j][ic] = eigvec[j][ic] + sin(phi) * (eigvec[j][ir] - + // tan(phi/2) * eigvec[j][ic]) + eigvec[j][ic] = + eigvec[j][ic] + sinphi * (ftmp - tanhalfphi * eigvec[j][ic]); + } + + // apply the jacobi rotation only to those elements of matrix m that + // can change + for (j = 0; j <= ir - 1; j++) { + // store A[j][ir] + ftmp = A[j][ir]; + // A[j][ir] = A[j][ir] - sin(phi) * (A[j][ic] + tan(phi/2) * + // A[j][ir]) + A[j][ir] = ftmp - sinphi * (A[j][ic] + tanhalfphi * ftmp); + // A[j][ic] = A[j][ic] + sin(phi) * (A[j][ir] - tan(phi/2) * + // A[j][ic]) + A[j][ic] = A[j][ic] + sinphi * (ftmp - tanhalfphi * A[j][ic]); + } + for (j = ir + 1; j <= ic - 1; j++) { + // store A[ir][j] + ftmp = A[ir][j]; + // A[ir][j] = A[ir][j] - sin(phi) * (A[j][ic] + tan(phi/2) * + // A[ir][j]) + A[ir][j] = ftmp - sinphi * (A[j][ic] + tanhalfphi * ftmp); + // A[j][ic] = A[j][ic] + sin(phi) * (A[ir][j] - tan(phi/2) * + // A[j][ic]) + A[j][ic] = A[j][ic] + sinphi * (ftmp - tanhalfphi * A[j][ic]); + } + for (j = ic + 1; j < n; j++) { + // store A[ir][j] + ftmp = A[ir][j]; + // A[ir][j] = A[ir][j] - sin(phi) * (A[ic][j] + tan(phi/2) * + // A[ir][j]) + A[ir][j] = ftmp - sinphi * (A[ic][j] + tanhalfphi * ftmp); + // A[ic][j] = A[ic][j] + sin(phi) * (A[ir][j] - tan(phi/2) * + // A[ic][j]) + A[ic][j] = A[ic][j] + sinphi * (ftmp - tanhalfphi * A[ic][j]); + } + } // end of test for matrix element already zero + } // end of loop over columns + } // end of loop over rows + } // end of test for non-zero residue + } while ((residue > 0.0F) && (ctr++ < NITERATIONS)); // end of main loop +} + +// function uses Gauss-Jordan elimination to compute the inverse of matrix A in +// situ on exit, A is replaced with its inverse +void fmatrixAeqInvA(float *A[], int8_t iColInd[], int8_t iRowInd[], + int8_t iPivot[], int8_t isize) { + float largest; // largest element used for pivoting + float scaling; // scaling factor in pivoting + float recippiv; // reciprocal of pivot element + float ftmp; // temporary variable used in swaps + int8_t i, j, k, l, m; // index counters + int8_t iPivotRow, iPivotCol; // row and column of pivot element + + // to avoid compiler warnings + iPivotRow = iPivotCol = 0; + + // initialize the pivot array to 0 + for (j = 0; j < isize; j++) { + iPivot[j] = 0; + } + + // main loop i over the dimensions of the square matrix A + for (i = 0; i < isize; i++) { + // zero the largest element found for pivoting + largest = 0.0F; + // loop over candidate rows j + for (j = 0; j < isize; j++) { + // check if row j has been previously pivoted + if (iPivot[j] != 1) { + // loop over candidate columns k + for (k = 0; k < isize; k++) { + // check if column k has previously been pivoted + if (iPivot[k] == 0) { + // check if the pivot element is the largest found so far + if (fabsf(A[j][k]) >= largest) { + // and store this location as the current best candidate for + // pivoting + iPivotRow = j; + iPivotCol = k; + largest = (float)fabsf(A[iPivotRow][iPivotCol]); + } + } else if (iPivot[k] > 1) { + // zero determinant situation: exit with identity matrix + fmatrixAeqI(A, isize); + return; + } + } + } + } + // increment the entry in iPivot to denote it has been selected for pivoting + iPivot[iPivotCol]++; + + // check the pivot rows iPivotRow and iPivotCol are not the same before + // swapping + if (iPivotRow != iPivotCol) { + // loop over columns l + for (l = 0; l < isize; l++) { + // and swap all elements of rows iPivotRow and iPivotCol + ftmp = A[iPivotRow][l]; + A[iPivotRow][l] = A[iPivotCol][l]; + A[iPivotCol][l] = ftmp; + } + } + + // record that on the i-th iteration rows iPivotRow and iPivotCol were + // swapped + iRowInd[i] = iPivotRow; + iColInd[i] = iPivotCol; + + // check for zero on-diagonal element (singular matrix) and return with + // identity matrix if detected + if (A[iPivotCol][iPivotCol] == 0.0F) { + // zero determinant situation: exit with identity matrix + fmatrixAeqI(A, isize); + return; + } + + // calculate the reciprocal of the pivot element knowing it's non-zero + recippiv = 1.0F / A[iPivotCol][iPivotCol]; + // by definition, the diagonal element normalizes to 1 + A[iPivotCol][iPivotCol] = 1.0F; + // multiply all of row iPivotCol by the reciprocal of the pivot element + // including the diagonal element the diagonal element + // A[iPivotCol][iPivotCol] now has value equal to the reciprocal of its + // previous value + for (l = 0; l < isize; l++) { + A[iPivotCol][l] *= recippiv; + } + // loop over all rows m of A + for (m = 0; m < isize; m++) { + if (m != iPivotCol) { + // scaling factor for this row m is in column iPivotCol + scaling = A[m][iPivotCol]; + // zero this element + A[m][iPivotCol] = 0.0F; + // loop over all columns l of A and perform elimination + for (l = 0; l < isize; l++) { + A[m][l] -= A[iPivotCol][l] * scaling; + } + } + } + } // end of loop i over the matrix dimensions + + // finally, loop in inverse order to apply the missing column swaps + for (l = isize - 1; l >= 0; l--) { + // set i and j to the two columns to be swapped + i = iRowInd[l]; + j = iColInd[l]; + + // check that the two columns i and j to be swapped are not the same + if (i != j) { + // loop over all rows k to swap columns i and j of A + for (k = 0; k < isize; k++) { + ftmp = A[k][i]; + A[k][i] = A[k][j]; + A[k][j] = ftmp; + } + } + } +} + +// function re-orthonormalizes a 3x3 rotation matrix +void fmatrixAeqRenormRotA(float A[][3]) { + float ftmp; // scratch variable + + // normalize the X column of the low pass filtered orientation matrix + ftmp = sqrtf(A[X][X] * A[X][X] + A[Y][X] * A[Y][X] + A[Z][X] * A[Z][X]); + if (ftmp > CORRUPTMATRIX) { + // normalize the x column vector + ftmp = 1.0F / ftmp; + A[X][X] *= ftmp; + A[Y][X] *= ftmp; + A[Z][X] *= ftmp; + } else { + // set x column vector to {1, 0, 0} + A[X][X] = 1.0F; + A[Y][X] = A[Z][X] = 0.0F; + } + + // force the y column vector to be orthogonal to x using y = y-(x.y)x + ftmp = A[X][X] * A[X][Y] + A[Y][X] * A[Y][Y] + A[Z][X] * A[Z][Y]; + A[X][Y] -= ftmp * A[X][X]; + A[Y][Y] -= ftmp * A[Y][X]; + A[Z][Y] -= ftmp * A[Z][X]; + + // normalize the y column vector + ftmp = sqrtf(A[X][Y] * A[X][Y] + A[Y][Y] * A[Y][Y] + A[Z][Y] * A[Z][Y]); + if (ftmp > CORRUPTMATRIX) { + // normalize the y column vector + ftmp = 1.0F / ftmp; + A[X][Y] *= ftmp; + A[Y][Y] *= ftmp; + A[Z][Y] *= ftmp; + } else { + // set y column vector to {0, 1, 0} + A[Y][Y] = 1.0F; + A[X][Y] = A[Z][Y] = 0.0F; + } + + // finally set the z column vector to x vector cross y vector (automatically + // normalized) + A[X][Z] = A[Y][X] * A[Z][Y] - A[Z][X] * A[Y][Y]; + A[Y][Z] = A[Z][X] * A[X][Y] - A[X][X] * A[Z][Y]; + A[Z][Z] = A[X][X] * A[Y][Y] - A[Y][X] * A[X][Y]; +} diff --git a/Adafruit_Sensor_Set.h b/src/Adafruit_Sensor_Set.h similarity index 72% rename from Adafruit_Sensor_Set.h rename to src/Adafruit_Sensor_Set.h index 39f2266..f41ed2b 100644 --- a/Adafruit_Sensor_Set.h +++ b/src/Adafruit_Sensor_Set.h @@ -4,11 +4,10 @@ #include // Interface for a device that has multiple sensors that can be queried by type. -class Adafruit_Sensor_Set -{ +class Adafruit_Sensor_Set { public: virtual ~Adafruit_Sensor_Set() {} - virtual Adafruit_Sensor* getSensor(sensors_type_t type) { return NULL; } + virtual Adafruit_Sensor *getSensor(sensors_type_t type) { return NULL; } }; #endif diff --git a/src/Adafruit_Simple_AHRS.cpp b/src/Adafruit_Simple_AHRS.cpp new file mode 100644 index 0000000..0ae9b45 --- /dev/null +++ b/src/Adafruit_Simple_AHRS.cpp @@ -0,0 +1,85 @@ +#include "Adafruit_Simple_AHRS.h" + +// Create a simple AHRS from an explicit accelerometer and magnetometer sensor. +Adafruit_Simple_AHRS::Adafruit_Simple_AHRS(Adafruit_Sensor *accelerometer, + Adafruit_Sensor *magnetometer) + : _accel(accelerometer), _mag(magnetometer) {} + +// Create a simple AHRS from a device with multiple sensors. +Adafruit_Simple_AHRS::Adafruit_Simple_AHRS(Adafruit_Sensor_Set &sensors) + : _accel(sensors.getSensor(SENSOR_TYPE_ACCELEROMETER)), + _mag(sensors.getSensor(SENSOR_TYPE_MAGNETIC_FIELD)) {} + +// Compute orientation based on accelerometer and magnetometer data. +bool Adafruit_Simple_AHRS::getOrientation(sensors_vec_t *orientation) { + // Validate input and available sensors. + if (orientation == NULL || _accel == NULL || _mag == NULL) + return false; + + // Grab an acceleromter and magnetometer reading. + sensors_event_t accel_event; + _accel->getEvent(&accel_event); + sensors_event_t mag_event; + _mag->getEvent(&mag_event); + + float const PI_F = 3.14159265F; + + // roll: Rotation around the X-axis. -180 <= roll <= 180 + // a positive roll angle is defined to be a clockwise rotation about the + // positive X-axis + // + // y + // roll = atan2(---) + // z + // + // where: y, z are returned value from accelerometer sensor + orientation->roll = + (float)atan2(accel_event.acceleration.y, accel_event.acceleration.z); + + // pitch: Rotation around the Y-axis. -180 <= roll <= 180 + // a positive pitch angle is defined to be a clockwise rotation about the + // positive Y-axis + // + // -x + // pitch = atan(-------------------------------) + // y * sin(roll) + z * cos(roll) + // + // where: x, y, z are returned value from accelerometer sensor + if (accel_event.acceleration.y * sin(orientation->roll) + + accel_event.acceleration.z * cos(orientation->roll) == + 0) + orientation->pitch = + accel_event.acceleration.x > 0 ? (PI_F / 2) : (-PI_F / 2); + else + orientation->pitch = + (float)atan(-accel_event.acceleration.x / + (accel_event.acceleration.y * sin(orientation->roll) + + accel_event.acceleration.z * cos(orientation->roll))); + + // heading: Rotation around the Z-axis. -180 <= roll <= 180 + // a positive heading angle is defined to be a clockwise rotation about the + // positive Z-axis + // + // z * sin(roll) - y * cos(roll) + // heading = + // atan2(--------------------------------------------------------------------------) + // x * cos(pitch) + y * sin(pitch) * sin(roll) + z * + // sin(pitch) * cos(roll)) + // + // where: x, y, z are returned value from magnetometer sensor + orientation->heading = + (float)atan2(mag_event.magnetic.z * sin(orientation->roll) - + mag_event.magnetic.y * cos(orientation->roll), + mag_event.magnetic.x * cos(orientation->pitch) + + mag_event.magnetic.y * sin(orientation->pitch) * + sin(orientation->roll) + + mag_event.magnetic.z * sin(orientation->pitch) * + cos(orientation->roll)); + + // Convert angular data to degree + orientation->roll = orientation->roll * 180 / PI_F; + orientation->pitch = orientation->pitch * 180 / PI_F; + orientation->heading = orientation->heading * 180 / PI_F; + + return true; +} \ No newline at end of file diff --git a/src/Adafruit_Simple_AHRS.h b/src/Adafruit_Simple_AHRS.h new file mode 100644 index 0000000..1b92504 --- /dev/null +++ b/src/Adafruit_Simple_AHRS.h @@ -0,0 +1,20 @@ +#ifndef __ADAFRUIT_SIMPLE_AHRS_H__ +#define __ADAFRUIT_SIMPLE_AHRS_H__ + +#include "Adafruit_Sensor_Set.h" +#include + +// Simple sensor fusion AHRS using an accelerometer and magnetometer. +class Adafruit_Simple_AHRS { +public: + Adafruit_Simple_AHRS(Adafruit_Sensor *accelerometer, + Adafruit_Sensor *magnetometer); + Adafruit_Simple_AHRS(Adafruit_Sensor_Set &sensors); + bool getOrientation(sensors_vec_t *orientation); + +private: + Adafruit_Sensor *_accel; + Adafruit_Sensor *_mag; +}; + +#endif

S>y33(kz_10RQB&ye{`Y(PuQaoZ2 z2Y!v{l@X#WEt1%JJKc;3GbHKC?y%XIxTC{I3%q8xf~D)oQ5{7ZtRQE?MQ)kK888AFY;$OaD-zYj=XUT3dF|Q z?O`~dng7&{Q(z6jQ*C7bioGbesxv-1q>ZJp6G3Td?tfD(Fw2qJ&3=++7AvTHSoRJJjX(2S(=^p!+s*UiZef{72r(ytm2Mrqt>xM@^wO9imEqrx zmFg$&J`-Np1FM#bdFHWjpS}ixOJ(rTF8=b%Z^H1>wi-fu4h{rK<=Y_X4HMh#LKMV& zF2eJMD|*+S;ik0?4)Jo@a58X=ahP&TQ#GoVgU@!mfwZaclZ{W)4n5Ifeg%FIbgBvN z;^o9&V#jN${0LT$Rt1XhtaS+mt)#I@FiU{4e1mce{F2k9SuC=4vqy_A6f}qM;mSL2 z{&pD42(t!Cd?Yy}rW#$0K1zy<{JOEE5fbGNr=B#_ny4{Zv2AK=oJ}zwXhu|&(D)*92#LG@V<)boFBc>Jp@pgoxK3j{m_pA103-m0ouP{J zUPzH>B4@xrEPm>#cc6WOY5KT?rUc$0V8Zr}6%)SayKk{sF~Ekox_KHYn1&W~u*c3Z z5Qg28hfZ3d{+qTcG~QuWvbqy9RD}jv#PZe}NmR_oFVGWfn&Lh8#5j))Cait-eyz9@ zV#MJLJq7OT7MzK~{3;fcecRCL&+ZVczj>VKHxQZkjGz@cP6+efZr|x&7Z?)X2G7OI zSwfIKngS+A8bYgxJ;+>sh_S{l450o=ZN!3VlSZ@Y@@n!<{E$=S8PTivaNn|+TWO{S zd`{FQ=tccP7qV%^>UYBMnu1;s6rPd_5*o%bGRC|Zp%W-4In{+VB#lS&PEr0HOyE6_ zUr7cGsvBuFv&~`1&*3T0nGbFcf_oj9Bhn&!oi!W;24L-kI8ODDTD;8RRLku;`?lcv z*%b%!z`u@heL_u!f*p~3X)-z4$aarn!ZH{xXp(i7aFwzCbTPgfEuCiw{{=LNQ&pp~ zuoz3kM&Hr-5_$c-?39ocD8dwe0M$$zSXV zo6f$|^JP~M5<)zCWzj7vqG0uM{wpv+!fvBfxoJyv_(gKH9(KH!mHXL6pMJ=ByLB_s z=yusG^{2Douw%8dSK)1@taErXAR&A7&kvhMz_1jfyFj@QnW{&_R(g1XE3PBK2HGKuzJ>*EDq(?L%&Hc99sR=zQJgM=AzPs=QWsA!T9R zqzKL1f3l)E@SD{&glEd}8n@l6af4FC@ zE#<|&#-masotNJ9T8-&`MyHCW&*V9!v=l#Nt7l!5m6gk8lfnlzW`N;}^V3%mbN+Gi3mst?X9@NkMC{$y7Ph|yuqNYa6($9eGB2wt4HNOgm}7sKlpuJ^eXwWY zgwV-R_QE(lB7XS~mQL*(P#*CA7TyNKFJZNZU6+6R`?1m?pN-_Utl)p>D=?9tdIJB8 znQwCheKEe;AT^68`Gic2tk6jV8H`~137?8Jj1*aMoYua{GOpX~$tB{bH&`NwEes=W zCzK6j8jzr+ry#`UtGUcXSoY9IV7qH<)e!2?yB$1ADxI>8+<1q==~Y_ci?t!wQ=lV>|+<8D~#iQZ`t+HI_RYAGJI|v|Olt}3m0wX4(kqyAzhAcrRyi3qO;E;I*D?}cnEiN2Yaw*ahn30%P z z{6Gb7do5K9NRwd8vLwKwg~f)bw4F=Fv%ZaHUVlnp2mT+TBM6C04%v6P9lFfDMg1RQ zX+-cRBi=R{SYlXvG&(7qFrFZj5Qwnr(B`E2SfHLlu@wzewkteqE2%2$JXBCfXZqJ& zWUe74%}zI#E^{U>yMv-}3L`N3d%$NXT=A?2z&yYe;Oxq!o>KHf8MR1Ki%!i$*P0)h zm_%BVUD*=kvzZ0gKTm|L41@!TuFiOZZofou=sJ#O-ewo~5qO`x(Hy^mhd|lR#$yY z;@c$i`ccOl&a~Hv7b`d@S`#F4qc^&q1DeifmsT$}{)=`mQ2aq$)9PGXy+5@nOJS^L zpD@a{%6SAzfGOdRMO`lWc{PG6%x?esrW zGfNT(K^oRPQcMr2flvLs{qXI;D8~sLGr$0yBrzmFHqg;W{u!YBTnsP(sQCKRe2ir>`U z=!@~FCV%>uI`AXAgYH&~&}ho;sE;U4?vvMUBB z!|kzTGMJL^sn!###0qqMfW7w605Rd@Aa7--+6(lG8uq)h@%1A=~Fz- zEA~26Z&o)7Jm#)*_PaP%i;Cn&M43knd>KlzJ*(6w5V230%Kf#~Thf(s^K( zSSEM6fbGWqc50JmJnNuTiRj!&T8qDLO;!6N-SdvC({GSQ9K8&~!CEiB<{1Bl$x3r^ zsxUvp$%~a<>$e<>5=kf=*VRie=xInul(yik(33~<|M2ef=rAIZ93)Q#` zAk98gjC&$jMXLY+W+5gLA7rRn)80K4%uZj$S>ad@>8iZ%^X?6|r{Jeiq@5>IW!Q%Wn%vbA1du)uZ}p46?KjBD@Y%*OnB6+0N4(F|_Yo7np^YpXZc4^dlxFqSJ&HG93C zyRxB>&T0(YKy^FiOrQIdw^5`oXKbWV@QgutjU0s<9XrDpAsL}mZCy<;$+Idi^8Qx` z;7&jMQDx!4j}C}34ny%tlH;{LC$E)!Xcr@Z;jkE#2i~?a-`fv93t2L+HJ)p7>KJL2 zNyeB;%KQtguF%zs4CdN%?&x+=yOXFSEDt|75?P^6t7!ytpi@?*{Y-Q% z_94(7q1Rb*7~S~V-W4yhz<+|o1LNL(qRM)p zy$-$&!Ik|}Tmxh)_Z06!5pO^!`r`Rph6ngD(I~Pho{{kf!-p9PQmC!)v@7Ej!AGCx zpg2()LS2#fLBT6QJrSS`!|FYyvkp&HfQ`5yr^ko!ZX11LZuJu=TE1n8!HY_4Be=?b zOEdU-f4~ymhNwg4LsV9FVBcz3oc1$sQx%9T8ybH`i&FAhtET~wz8^cFc4ZJB_wiqf4n8ImYvy}Zd6;FY~PR(%zh`JVU-d5q(#WAV759MD-K zx0QS|iqO~RS33kBc4j;UrGG~zPD<^OMM>PwH@$sw>)N$_2=$W$d(#yQh|Visd#Z)v~pi*k(Xce67)IXRqlA2ks<{;Beh)pVn}|u zw(m(rY)19;#IL#}2oadg9+wUVxpJ!2!gg2I%!JV6a)ymmHORFZFvXg>t>cNm<(sLV z*xJucJmY?5%#j#bqHVFw4^Qd(JbCPXsaVc7qo8J~8(G5EwpPj6=>8+z;my`#itT1~ zN5OO zI4Pg$f(p&9Y$(x6$K30MCLvS9x<)jkbvaiIQ8g$V0vf#H< zo8$lF^qAOBaqLHu>>-KfS54X!_@YKso{~m29=bb538v_#@ob@xUx~!y%NXS8d*cy9 zTAo|4&AxCDg+FxG@X=8*Ki44R6)eqpiB!$Jnf6~heS~&8%J%OH3I1w_kJ2W5QlYgt z$PcB;q+#}-e?u>57^)EmC&NQ!3VUgf@gXWm>BqZBi|8$`I%qkTONl|ol!oJb#IHo$T1AQv$ zZwV|Jo&!05N4r3tCF~K58VrRPGf|6S>E(u;hL19T3MX)|JA>Q)9%rrbYuRW-@b{?- zQEcqg_~ky;K`iYw=G62EJ}lSDGKL|~89K%(H+x+RxhD6biimZp8r>D4E~0_VyI(wZ z4mI1c1@I;^7m4Lr{MzNs<`eds61M}~uSPW5Tk5lkWrd6kuYA%@gB50!1~CFJkY85} zD4zN2|NNHGNllOofAhnJ1*N)t?wn)`7ox*w>3Amx$yv6d64{A$K{Tj&S#guQY*No$EGN<{ezrCXhP~9 zWF7M94&kcaBGLv`hx)ILEu!+QPI)!zWCREY+y zWy1BX+y6Bq`(f3AfWtoj4qV=PFvOQybyc~MY1;P=ql!+vMD1M zWvlPWaL^>EXqY6XR`)Y64G9+FQq-x>rPw~=A5!j55=gj|v)9^-+2F%)y_Qu1`!0(D zw)M~H3aiyAri3^5gisj4=`9m=$R_=~Bf3Q4pOxZx?`@9x@!D&AR7x(YTE;C7LO6;% zM}h-UJa>!PA>Zjcz36{7G@rBjVBL|fl*B}}o`fbYuA>7`?a!Y=W-}}X}z(Ju%co3fito+r2Gl% zcqX{UJnbV*Waf(OKm#uhs_~YU#pVMnA98bc7az$q#Z(>O6dU!38JpI#>~+TbAScEF zrdYVnX_4RSP*K0v>V=yxH(Vy`EakkOB@#2szW8$u#z|K+D&lk`e}>V9>_OB!kN8BU z;6*<|CL`<0>F1yw&Gb_d1I?*tqo$1i^ajy(45X(o($-nXPyaoa`nJiRnW-_$9;GfA zMoDKl9-^7|J+JB8RE<>F-5EAMR96_N#e(5|)+<^gb}22tSxQS_Hc?VyAz91Cw#VOu zbQ>WNsgT5%;othSE({MjI(MMlz*C8!0BfqJyt4=<;4o3Ez@-g|?~h1^&Aq|#^H0!- z_+_WrNPWY(wr3lK;w|P#0_}6tohlwgCtp?@)4Hzd%ZIcteEwH3?WLU7;@kt(xeA@p z-;DfFkCX~Maabj2;y?yZ$|FEvRO{k-_J)7_hff@FvK~9C0RcJW1>|ii}ou^_lzWUn4p` zirP|A=?lB9mNG2%^Ho2Y@47~3_eacRB{x?Pej2xrPZRroD%$2{P&F+H6ybWRWB7U+ zUgTmDgVTlF`Rg(9#uYPjOYO1w$tiD1D9AQkd{!$Tq$_*POIV00gm6F1j{MI7=_=7lQl|IW82?A;&t`D6--=lEz@tTvKNvx!>F zV1KyB8A91MzUahKqRayT*5Zk>wvXkiOtA!?F>Xz2QQ|Vsa+gm`4L7XpGFEi;EH1)y z_p$enTW}#E6Udy%IEP#M{=>9CiTyOA2FMKDaSgwxxQx2e?X@t1J)XFE0{nFDQQ>!880t^Hnp$lto*N|+Meko$l@Jfa{KbRv0@K30qlzvi3rJtKif?`Q zZkwX#N8hhlP4$DsrE|XBq1(MaS+iwuAqt*+kap&EusVV1x{U@@7b%962lx*;x0gQv zxKCkh5HbVzdslu0DQhK_le*^`|BtSBjIN~Zx`n%w9ou#~c6V&6W7{@+r(@ghSRLDT zcFc}#+y2t`dq2-P;~nQ4qkhz{`cc=aRco!e=A4nRF05-FwG1>mDm_qOyOOi_QZ^2X zg&iqi-(jw{P|Ojb^JRd86bJ-X;591CH}K`Mz6ZL*AA4?hscV;k5K7iJJMiu{s!{aK zW^KEp%a*CVkWK1Id_zgRtbpgZ2*7Mryb7IkihWE`%PcNr%sTE_d;$Gre0~yx-y6*BbK?BSF+rf(=pTp5< zS6Kk^@_KQBOpZ8B-b4P|pvrW{PIMAUd@4FD=#dY=>+_)!-G1n@_8LqmO=OyWLclOx zquTyN9f(rbB6YKvQ$fM9UW?UEEn3}k=`jW2_$DS&HVbQ5jZnOlfmC7W8uoO=D*YK}lN%-4I$ zgN_T<%b;x65%x>(YuFUSx~Jqy_C?JE8V}~^MTE4;oqo1U#Wu=S?ZFIiTFs^-_=Y_A z!A|EDr|GT9flm4EIi=h7aG#xrP@hF+x`}Bjc%*MbXZPw$l=w63U-RfqWew40%~FQ9 za0@!0q?=psVqBA4|1{qX4b5FmOP``2L!YkOf%qT$P^i799yb+3m@4!LOGu|hTq1YQ ze~jaRasN0g`?0v+do4UWtY%MyYA}Ia5wDzZoGCe7qAZxr#j_JzRT&Iw_)KA4v9=u5_t0Xxk{^qbR$t&tGmG&Vk0eZ} zLa$1~+rwc~N>jUor;sru9HFQa9CCbZ`bRlTz`+}qkW_b9uF#{Y zfj(xK#faFd2HRoEEX6kU)9a`v_Lq+vv9NZuE?_tWx&m=V5mN9ScH#vjZNQdA-<_xx(U-ds8@CMH?_e<-_`QJc&G|r-TzI4)uRM-*bHIvr5bH~?);2>T z#G{xej-5_}O|7dYQDNZSWiC)F>_=a7j9!tgo^p3azO4zi4pwM{T_DuFn9*E#A!m9A ze@s}5<2(kELqHZfA!tW5?%{4ZiHa;o=r&sqhh5t!;&x7vQadG+EJQ&6ssQI^5;*w7$;Vt zoQ0Bguj;LAlqZF)r?S`y`RyRBEy-KoW7wxm?Eeg|Klo3W^L-CoO)h=kohshIIeuW81RwD$>{<+QnsFG8 z66VU>ChRBPu@tyKw%KorC$isWeIuU8ra8CTN1(RSZX=vitNU2b7quW}EG{#&NWJlK z?yUP=&#BJyqZW1hWegn?8tb=}fUmwpS{sse_{&dS1&i0G=3-m`8j(L9>47y&Wg%=Y zEDo4OUv80B{a7+XTqfLO5)&j;TQT5g@WeC!3Hk`Yf))Rt@=ZGfT_imU<6SU?Em$m-@Cx4eya*AmPq5d5%UqEvJm|B>+ zn3`NiHjd7Pgo8GyaRS+#ix$0K)y%smscOK_!3TYxL&;K0=t0oBFlWcOosW?n`^%I! zLA=hxIJ=vx6zkT?yu>ySKf}o^KjgmJA{j}`qOPi@ofUAQQ92;Eui)_pZ7>?z3Ejlh zJ|l$@!1_R|(|YQ*XtsQB5!lD1es3(W;5s8QY3Dfte{^cU(MQm;8nfoY|uG>2KvZ`#m( z&_;xYFg691#wouW7xwwj2ZhJk8<+@*Ih*)?NRdeT(LV#1vIBAorctRq;U7P|=g6_# zj^`&%vfikL9Isrc|3i`aOPdQoF3RhS4IcaV&(2^BSX0~vevP^eHWQ?!7Q-2?OAClL zK@_4}vG>>Ay_V(QA@QRG3&J)A7xI7?hqr^jpZmfx`_L1F`BRjsMnfEYyNzNf>GDog zbR!bj7N~C}MU-yD)hEN%<=yXz0O1(ico2-#%611$I_Ds5)kPh6>&nonz0S9G;Miro zU+yUkk;j4jTL1zCSI<~7982;*2QXGfPNug~+89E$YeDi9Bl=(`UtI_YbY{gs32Bv2 zB$gGkQr1UrG=CBl;ula{q2|@9k;JZggWMr7im&$X?&O2TBWS67%C{Qfz*pVH-^Wwx zLO`uPm-@Yo7*Zp%ZKHSL= z-f!q(m=ec!+4b3q+d~4chKI%wVitQRWY7qX^v)6bT|q*yu8El!3wwS?dpo z1ipTL)|ZM zs$-5d-%28ogs7{c^qT@~=vRRqbv+9+0-|Kcj^cpo?{CPWe+vBn#1bz}o5fJ%lAjt< z&l9_d5O*qy?B$;<7=Y^Kepa~YApC92QGLT|{2QLTn2)C#)r`~GM}ocy7L42_E(D*t zYgA%~TL4#teC7ib(40djYEp@jdC*wnkDe_5p|*a=E+~=upy=j<>BeqRccodP*BE7u zpMvby+7|hy=amtUQ!H>|NU^PA2>4a7!5#(q&ZT}-C0e~B#*#I?p$#;bPmfKP^eCrv z!=8{Mz_$`34!p=rvttx8_@NAGc}t|{d029=&brm&t9Zirk9NhBg`X%IFZug6D`m0< zdp$~Xm$4Fe0ovB$=E&a**m$%+uGaD|BMH>xpLWEdZBAp5hLwrFNo~1-UPNsQGwXaC zCJ`HMzTo0R?JrIz?}syGSQXSI)BKTv1pJ0VM!q={h-eJgE&{ei7QG{fjtkbL6?Rr&~9v=7I)4(u2CMY->VR`k%o@{ zG3gphc0;*utD^m}pl%x4wJF0!?O7Cwed$EImCIvSu+mVbYomq87NloziuZU|d0xNX zfdigm>aTUWtjW69O>bp$%I0-zmDGein?9P=-i2~ONR9=BdfxjVdUXpaGLS}_F^>)i zj*#Xh^b{+B2=5fdJn6^2fIWk4?t3xtE{*L9>*KRg&UMJ7FX#P4BV?bds`x zze7YLgh;REp|OREM&6xvMVEVi-+M+>L}iphGDH}=)IKp7@-POAt>C08 zIAqH0DV`>o>7}7B!=FT`eUj9-{5rkRSjyc*sYA-DF4~|50g)-F{K9o4X^WXQY&WWh zbcq(JQ__NpjX_{ehf0Azn0ix#71>;dRX{OAf?HZ$0lHA73Qz~HkuXw1aPD+7oZBT< zJaG^AOOr_0J$msF(T8`6{^pC{af1F)O@$OE<8ex{B(x{Cc4_faq21y0eSUAj-?&Hd zz2empfgZ2PopvvYJ>1uFXOl@a6nBLEfQ`Jm$D`_`Pi<_PIaOo#0<;oK=AZ1}pN80) zJqi+kU*4eTX@a_`ykNceYJEO+HvgY$Kpx>UeAy~&Adk$){ z3V1zWcIB3~PN!skk(5h&h1q%_1l>&`E(K4|CFgTa_jBo~>=lnE(;y@H6G?{`rES0)jvwW*cXA?0pEDZ*?0wiht3ivGppPN$*Vz5Z6NQK@SPFUyaCmRwg2AbSpw zot)6GlY!-5&)rRP5xQ)v5XKz`1=**5fhYXdWlpP9<3 zgFcgcriMDdZNXG7-QaqE0)BVaESG+49gCrPl#MPE1@YX-NzHnyJ?8@-Y164k?@mv( z{aVvpOQ@hdwjHT!u>Eb@)A&DTsqcPsAZL7c}1b zmTF)nEkvNu=4{$ju3Wa_XetZ8SxCn8!?XAsni)gA=b3l}(7*v(uD;o+_cZIn-00fL zI+r#tdMsiC1I})@)9`m>W?tJ~}x3$fl1sI4|~LB|DUHMK9j;+2`JNk2=r zO5$KeI6<@W_#IF#)pR5oC3J`uuQMFtDMAnL7pSy1qW{&eTO*OL<_3wau#R-Z$D4_Y zx;0eI;NvlS23FKwCOx;(&9aZoVenX6wA|$F{{Qg3qCK=?8V1kwXmWFN7czAf&A+OC zU?V^y54m1IoAr;9|UOKl@q>beH8yRt_g)X<@%R7UBJ{}+|+hpua@+I!k6tCdeV z?TW4FBW?LX$9H$_{)n{t1w#4V-~1ipgqa-jJOeXqCc1I$^2(OW*Is5sbkFS=!JJXq z2)kbxm*UhQ7fSpTY3a31B%LUh<7`Y+9qL9M)#z*bn4?9PSX>`fzm!(ZB1JT~>0qhb z8swDcjfbmhq|InIk8oAv+Dfro1<>O#&A>`a)7$Nyy6Wxyun9i`5Bk3WlKhhu>tlPZ zs9h|&29lxw&F5ot>jPJ%ONk;_v|Ww@jEV=IdeW=ilMp1^RePtffH2EwQTN=~Oy8aE z6dgj8VU`GcfQc9`?K7~4m7krQr9H>bCXjATT<3&Uv&pM38ESpEy^K3Yq@e6+fxxye zpwoSc(E3s}W#>+J1F|lsU;jaQFQEHGed=lKH}^A82XF_t#g>>44J<0g=gCz{W5p4Nd&mZ!m@v2Q4s_vYHT8zb>04W%?X(Bxz(x7iEL`FA_C9r$-;VoMfj3+GbNd^}+BkHkPma2kV-Y7bv`7`!HbV zwjcg8O?B(B|4V5WSOgi7nRyShRdE$2XtFlMrNER z2CMAW`Tn4~%zSTE{DExS2Ln!TwT5)ED`RC{Om}wLlESTB%q`ik>+Y7gnA_$smjUalho);-?HY&R)%dw} zMdQkkwdEwLtp=4=Lar1Oq}Q@aPn!q(=j0P_S2t=V(oj#)$1%KzP z#sJ6up_*2)JD2Qg*Pd42)`-w|`>M?D^1OZJUZatQ5padh2SmF*kD& zd-gqh)BC#SU+yFYB`tSiSRA@TP?(iBQYO=$yZ!tMhx-@25&ThUm;O)tVvY}Bs?tq( zQ)toBIE#Cee6IfjWvK*5IKo7+SOYwwF2~qvBYoS|b0#%5H3T>j`uQ~8yI^E0C>0>X z@vw1%D+gKB3H*W&K{U_z)FgIV%}i*BHw1_meL3p7iC|;#&HEkXQNqD487o8`UHDvZ zE{!B|_}p_W>}hb|FC2W*yA3)eBM^>2PVOMJu?g@(jIfY*Q+Qg34X314J~uox7xlSu zAP?Lf~8IWV^Xq3kr_^3sf?e-f{jJ)+%S89@AHuny4t3yO2H$QEZ?bYs!I_QAxu z-UoEMGLF;s{=txcf%%$~wJ=`?-*jag)1u8ITDJ6vvpn#>_7a_>@JT;~!n?q4Z@dtm z&Wn062rHdurK5y>KKiYv?{Ou7Q*R1Y2n4*t?c*vC)2_uELaPnqC*&OolO8 z<++)7L*Q5G0|T`v_O!bTR9a5pLPPm$;%YM9(`k{aw*6EXSkuYTlxLmRanG}v5vAoRKo7uX|wv5mW2hX->`0kz*nt`gSX^~}@bmL(*{E!h zb`@l}KE6fc6!`&Ksy&Kge*MyM)rQkZ$wYsNuy0S$A0OYZ_z6%h{ojwMOxm&(e_=+1 zS9+<4$7Q{1NAjOQ7ts$p*(10Gp+3A5`tC)3vNGMFTd+(e3ktxEViz#YV8m#Wk*wMw10F!iPaJvAy+rKd3G3&>IO|z;{ILmFTnXkO?a5LW%S@%t* zCNXkzWZYGyZ)A5gSS7XoMrxAE}aF+a~R1g9We1FsxKxz5FEL zTUuIe*V#C}0Xj_3wPR+L?+dZ^y^DfessY`=^3CODi!-5qFBh+Ip3WBxIbD`g7N|H5 zDHF(G&?b9RCxRLiyA!3)Xv;FsezIeMykF2f@BHCB-fZ^0aBOdLkfbyo%O128Tu#X z4-Mk;q>6Yi?h=N1YNCrnnp2AY?1AGzC|-CgbTEV98+L_5=LP*71U(f7HOXTBd`$Ad zYum1E!F>`)u$oXWtJM$}A97SpMEXcw3cUBMC_kBunF)QfUl|Ktsygo55I9y~nV{ z&i7Wn?wbZO|1cLXd9*t5#h=ZekQbVr%-Xda_;~o0OWS_8CLDLf4U&>Z(qU*84r*Eu zpxNTe(pZm#=`HRddYi=8%|Us&J3YhK{z(V>SafZb8x!)PG^rqOxn$rMtl%T34k-mOF zLPry`@J4f6r#`E6e?H~5B-8yGx_In%y+Ary(h_03RJ?%4@xlquy7UahwU+_8=?e+^ zxc`5uxvyU+;0z6)|5six`whA*x%wUhC*Ws*Lthuv5{0xs6m1U)!-J@ou%?!yh=NWg z_7D)2X*D-v*pjxl9wHMLiQl^L=7PSK&rn_o@e)_swOHp*Dpz(47WP$LdEoB>?fgI$ zE!#C~n571N1i0DgJ1_DA2JZZ+8p(YUSRl(H<8Exm%Y(wcT2@OZrA{eu>dL7AC(kDc zdk&c!8JPzrw$(knRBlPreRgBXYF6+lhhEFMCqn_=6H{{+u}Bf?M{d-6rUGB5@~?N= zK#naL=vOh`uJE@&Dn%PoJ5y+Gs#OLXSQLb<0a{N%4a(W^IUr?0!C^czo=$9{dpCs2 zlQ{p^H6)3gdJC+_24Y6foTA<1%H!6NtM_@KwhdX%qL0~$8RX|`EIRuo^f>uQXUVEH za3wmWOq8!PyRA8uJqr&SNolU8jsZ`xdN!87Vp2Q?fV0Q0rhp@9(ph$bP97MCkSLK3 zI!s~9aD|BcSwG7(HJcA*7TsBzO>hP(fTh!`t~|nBghV=9WL#Clm*PBMTs~jkRtStx{u?Hewoh58Y74?XOj7%z&|R`WGEH1u@3)e?g2?( zvUE35&}YID3ujIp2frk5t(R53%Y}W8N`|tLDT`w)948mdkVJyGD!zJBw!6^0JGcA5 znL3o*>lY(%Ox^E_SPIieC{HblURsBnbyA%Zrum+nlM}cAuaHv$?|u-s0Hg~AnG>j6 z^U}Bsg#)<(jO_ydZ<4ns`4&v{KW}SPNkfakU3R7UXSV+cuDwNZ-z`~r z-Wz1KXI@v-LoHU3uW1;Q5`(?^`T*kI>=S3jP>?_WRh9r|{6r)%fQp&=bb?&tf9f*W z&LeSD@0MZVst?soP0A!i_Sud%hq#9d;3`JlBad(3+=F)^@eF>{M}n^Bb4^cQCilg| zG(z^AYsWyhp}Rd0K(MM-H4Gg^PSL%{;2Na?B~}kKM4nlIF%5pC2j-UxG|$8^0p2Y8 z5MBH75KJER2IUNP6oJM%FAHy0CI(SNy0LW~tjNTJ z0H`NsT7yT*CyWYj^YWhp{d3g4A-s6|z`{^7_3eG0H+Hrh$o0a+Suf7JCIVtV^Oq)f zEe3{xM@K&l?_N3Lo%9R}#|p%54Sp@+zh1*Po%mUkPGH{Gt$CK+1+Sb>l)MZEH-h6mc3r485`f=twg}2jx zEang}ZYAvNyYGefc7HKr5dkSF?rXF;(L+7{Lc|fd|0QoC+qUd0zY;nhVLx-KIz?|M zv>9)^1ff^QBPS&zEIC~-nmE;y{6g-5u#wh!AXZi%>$U^S-?;mG`J$n1d=2;x5cznQ z0)TN%utJ(BAc9e$7hXCF!b^Q-hNkPqB1r*L_c-;;eU~><7NC$fDvGv03P8u0-_@lC zX0(b(;7G8c!Ju}}Pd5>sE}<{dkD-=b7*+A4Wv78aN>tJ71y<~}zBO}SP)!o{4aibz2)C&0 z?);qm5tr$> zii>MrjealeFncY}w9P<95}8RBRMCr8#sA6&OPTa^yQ9+l=qhcR+1COi}VHY6=4_$rldmTsi6o!6sf_0 zJv|rIlX2+@adBnnH^&6}QgvYlRQVxFB zQP6fv1uC0q>GJJtku1fiErnhYj%pt zykS`m@6#-(O5gV{>Aj9M)gQj&MyM#&_T7JX`>wNENyt4K@}PSp<-2my)^0!*R?aF(4RGTkn`lF4j7LI+k`jy(isUAh+#s$KOW>o zYcJ9r`-c1+?Y@h=7}*To@D8SmFWVhiJvL?>VB1@AjXXVO5LN@!1RQ z#r6+Bob+B^$Y!or+aM9VC@$FNU^|SkSw4K!Sr&Wvz^@I_qYG!g5>8V@_(FkJ0`Ab` z2Z&(=FKrHQ=(<|x9J)qf|wQ1>r%Sg(uhJ(*B4QZIl-8tRMp-&QopjHX(fXfq)0l#A1LHv-buO9k@w6C z@%evp-@%6!@Ar$uo|BE*YguNW@$vJlZk)&}sudIyC~wB}=X;V zO)dBcbfkm>AdP`$7lAHq)2>^KiKyRIgvPr?O=BaLt1HP=fUKSg<- z&BsmL20WY{MQ1~VNR7I!wuglv+t3Tp!(ICg?2U4lGunS=0U~gpD@5EDPziSXo#xmD z*YY{Pu?>Ei!MPR4^o~%#bj_Ib3N}(Boxk5S9u5hkc);Yy^KE+JU2&I22*kZJ;R{e| zx^y^8-s}}d13d}1f6{%9XN8p_7uxhYEi{4@?`;(rJL~*dceu?SOcR3aNBQ-Gf$*L= z9Yo;U%5_=JuT&TmWJ3~)Wb!%t!_>N8zb;XdWmZL48b zsvm{kqe+uHB;E zeZb(#0H1PvJNpLv2LIA{K^c3t__NGC!^`zW3;9b`Va2$s;K_wZXma}~iZox?TrVfN zpC9zRp8tHe)g~_l2KnvqLyFv#uZgXn65R&dh}q)tMqQ^k<+CFlV<1vD*Lv=?PMK2$ z+ME8q=(na|p9?RnAs^4o0(V-4BqZX<=svsNM~P+Z>K(4*fjdQLO}KqGq-!2ZgLkaQ z#;zHA_#FiH@4I?cZBVj7bXg-w!q8Ijyctb=Z@tl}%aI!((%UAE_89 zxFPRnz0HMO<5RhesxHegtZCVq2V4S(b?;Ia()*WZ=ac03fppuExmhh&OTW{y7s}RB zs{T1v+xp)v^>fbNN%Y4&W`Q>N2{yAXw@LAsEm#3s`sX$kRW%4?))q#2iHx{bPG&0x zy+lQ#IJ>Sc8ouTE`jb=Ea+T(FFJV8eY|0xw((LXPy9A#6HJoftaviO#g%NNJz^Aj zm-2Q}tvR0SIE}V9<|0Br};uU7r(;Tuu{BUYq}DH1mUXQ zANMou&Ah!8(n1>6+RZb+2xC#V{9YXF!Fl-KN+jDGbpe?qsE@P@kzW+THHMmlyr*5l zhd@1=B8Ca93valV!0n+a;;iaez4EZ1^P{+O+r0`F4MRgm#765DZ>4yE+pJ*(J?V3B z?|VR0_Jfv1Q)&TL72xA7liN+v*TokcT%<-kM&hq3C!G!Ao}JNk+|}po7l#+^_L*6? z8^RD-o*J;p=pj6KJ{YnITvg(3Yj1Q{Zya7;~XjKv+kD09+P1uHX8P_wNg?#kNdT0F{4QLHL|Mc`hr2ce}wR8`&-iqKxt%XMd6 zKg$LxF_U!$>vE~x&xU=+rr}i8@?VZrk)d6%*rin?Wt@<=VU_uu#^F%(Wh*^G|N86E z*y@#AV{lh>?x-WC+VW1Ub)U6p*b_+YzLfhwS?p^iUlga#wcqhWzfmFdiV|I<0 z2@3_4e-?%lZ|93gI`at}gM`UPzxbA+bABTfg?%&}(v-nEtMsscc_ zk*=={9>{Kwd?YpbGuKDOOxksBn+hG`^Uoy!4~D;W!FA{01uZ607F@giZuOw~FpN#$ z6^4^|p|ZJ61iDi0LrEXT8S%s%-~3WG19u@_eHuzODzfPlopMs8=M!pTCWLPgOo$rd z9uF57M~05y#(wg$Lz&aK41W@)r%wnA&wC0>-q(xf@IsryzfG(D&X*p&;elT1r)EUd zkHLNtP|1miH*cBh1t#1UTv|!Fg}=)~fKTX;2pI_`;?^`4y9Ir(5MmDFZUt<{A{|(Z z#Iqp+MDj{31Nb%as0P**HP`}~Cw`nSo1J$&SDcD^sHmX%EuZd$+y2wUw zxh4#pYkl8sU*IQB5SwZl;SzcRpe@ZU+r+b+q&9-F8QuU}t(Da(T>h|6`hk6YX5`ye2n!4Mdgq5SK z0su*^ASopZjqa~@8a*LXY)J?l$j-TLB6HgnhyvB0Ma+V%_2;WW1~VCEYL^cFi!p*a zCi;=}Yp;YNlyo!k5A>Kd59DtrBxt@2A9I2hb#s}2d)pIw=MB7{&ReCEskea8AATx`GY_!^1HVNG87J!mUQ~@`Zdu-u&?#dz9lI%B$5`*t;@qt=_+&IA%d>c^xvWa zkKN{vSmr3vn91do*;@OOh7Cv26fNDs&YRBr?cQZFO=Mc6 z;>Z5Fn8CGniZ#_>8*0YdtDrNRyF1H8Z|L-$_oFv(F?x)D<|PMu0Iz7od*HXn+D+5z z`bH1y?;@Z?OqmdS?x&03%B`^;hl9Iql5x?%*7*}f^aaFs?T2*r(|Be_KOsPW1Q}Jh zA0!#i8}xlH`ilfn2nl6}PHXl+;FSOE z?-U2-^lPg=gs$yp47H70R{lQqTOKNK;6@*<+hgfyC?St+*QIxu2hRl6gP=8%DAfbR zyiV|Bw2W+o!D`$_^#@Sv1p}&X_xNMdHzdH(AI82Jv3D4*;L(h@du8rAKhULt+{;r%v_48i7mhAw5 zwnt0vEVX?S)23tjcRqS^&$JWfLe1rYJyEFRc*u+adPq2~QCxIoxa2+ou`xOfFj^vo zV+3>bm!XnUHflC2j(JSDRo7%1>gW%}t5qm#M}xdES`FiC7G3-MngyHNy1My(-H=D0ikW(5<1Wp| zc&lypYky_G+-Zm?%FxFBxoPJssL1pA?s5)iW(ma=9}DFT?`xiGNEfHr1~kQ|?>m)E zh5Ch0??!Z#gbATtoC5mbT88M?w%KdlW9KJB8LO!J39_6uN5b|uuUus zqSZ%HEQ<)1?1xFUv>+!BLa17q7rlpx3&yU>fN1~dAf?f++Gd2OQ8R1epvpc2mKm~( zXnS2)vWTBRG%qa?UMjAYh`Q3v;)|DyClz&F#KLT5uuLBkW-Jdv)`wtkCigoHVGs5{ zp}l80nWQ}rAuQF47FP0aKgo%{*K$vk1qk5uASb zFp)MiLRfCfHBZ1Hx&albC;U2M=NrI;M7q$y3&%?p_(~OXkz!$*5H71?30^@c)IdECa#F+@%56*O{iOPn^?xV0T(g|>}Un9?V z+cN5_&@I2)1rj;|-mN&1h7Z})vN-ArYY*6H_1dPlI^Y>LLBQ4TbZ&bIu4%$ z#9(3Y!JM`&4w~KoyWd6KBFwSDK#S={Q)3L>b8I{9ZPEKXG1snq{cOev??#WmD*3L4Lyv0*Ps2Ss3LyqFP>buniFH0Bldd+bI36pUF*3liJ&#r>1^aXM%k5@jw~kFsI}VJZ>R z<X6Z{J(>1eO1R96rY6I$#m9+3NNrTrCd5#9G>5ZhnkOM<=lCn7-g*x2`CfLJEFqWJO z2+f4D&;p2LPXM^GCZ4qY5YhjI5S$Xa-UWhhZU1BtT;5k_2H?CS2yO)71qf4i&oJmGOdRhwAgGy{N- z6jXIbaV-zXas|SOdCDUia^;h-S0C1dY{%|InDB+v*!Iln^;~b1+gHLjgcH1xK%bi8 z24Y>A1oY_wzrKj#zZZnm;1u+>p(|{~=!Wa@R+^Y|oJe25TvXd9jXintZmC<}Es2p) zE>F0&s6kzyazvQyi`1u(1@<6OdPm}`2IS9}#tOkK#s_~GOUmZ@{l!MO!8!uS@#aQ~ zVy`PMEn}cPdH@gU#2m#Yk7zB>iDeF}(Y9XU;uu-f5!w*q{_8KlSfoNr ze7~MS1lMP3F^`C-Cij_<6lNfvaMWTiQXXj$Oi&(h-~}B~Hn^H>oRgC(4yXVhk-7P` z@dsjND#1PGgAubxNT(3aN%|F@YHLgqgfV?v@>8qb_EP=+w z@dlAXk-jt&H>PBjhkMdFR&&4tk;icwN$+Z zYZufBvA$$9bi?1J=i?rvPQacYxQw370SFl%G5{|xzhml)H7-Mfao+(Ce|Fg?U&w>T zViit8cg9!4_f9ZG*EO*aCb`v58>PM&{Ck=|{-QN&Xe~%tj!NLFY8oc=@bSm~5O;M8 z<37(~2fb5S<0PIXPTBn>B}dxdHVc)kGE@LR#fh)n@_vX@CI8!Mrc(mmATqY>a_Fh; z!^m~jzmO48f#vs5_Ppct^lT5d!g+mZSZpSOk@F`K(zJ^JgXxE1I1HBGLqRNFtcN?# z@LY*v`_|MfhrQW_$Rip&Lm!hZ!JhA5*=@2j>iUp&G5;}1qx$uN`D~~`xFp5!t)|6C zSedE#lop7F*dJ+QFK2(5WS%(NMIDvE>{=3kDn-Wv@KCe2;2z`1PjkgPS^qa%Ww zg-N2=WtK)$!D&QU8GodS+nqK#cZVp?=lkXEB+TP3ZR+!FdhW9p{j9%}csdef>nfg* zl!9Y7P*`1dA{K>~r9E%cnCa+Hy;-j%wx4GNdNbz8roCMXlxjvb+WY4_5RtgL{s4au4t2LISDuRcI4I?Z@uV*} zoB6F}cyF5VLzoU9cg@#{ml#>?H@qsI)wyH?!k5VSGf_=)rYBMa76qmF_ApMK3Q>0| z7N)BpZ4QypM?GI|g8(oXUc(BEhRBG*9!~aQyiFTjq?&B~J{FIx*Rn-|A1SZPog||G z2MT>w%)@rphI?0S$}pxKxv9V@Qei7ge5*`ufq)L^IDel+v|MN52GkN z%YDoG{V%liy_y5!o)KU;`bJ+-SKEo5{W$|0o+y`8;m2+ix=#HOByg?#A#dKg{)<-_ z;jb4O`ODRemznhRH8<2#BiSWBIv77}d0w`{vn4Pr(lFxUZuIv06zN0zuF;4y!`*h{{j3^k+7 z=z-2-X6yBad!golfWm_wR@1e( z>m?F`@kK{96*m-aA`%O_ycoLB>w0vj>Br>K>$U>YMqSbiH?9UH#N58I&&zu`+6Dc8 z?7d}JRnHqXDjm`w-60^|9g-?iBHb;q36b7(cY{btiPGI&n+9pvG;B8A4Z_)|zki+g zI-k#n_qzBnYt7osnl&@e%-qlY+#}FI!q(-?&U{sF(>0rVxI+4S3=+b(swB$GX1CNQ z#9Q_4+(_Hm25&2<&LH1*xN6kzk_>3t<_E3blzVwf-GNC5^e1t^35Jc6gquXJ z$yC}5B@ykZv}5OpZr?_}ete`jJhB{E>5fvi9I$0Gh+nrKaLVEcJb?0EXV2WpVXPZ5 zX41YvUx1JajO?}E4k;dx(1g<)KO9GP*<5}8#h(t3+Jk4`AkzFx$*lolu;fVR>Pyx4 zE~U5-=Y3m*967A_?`Lm6D+H~f$>PiTaefT^NdmOkyuigUbS&eH4nh2QyPw@}6{loc z{Z_e&7>#Eovi3)SJxaigAjeRG@_fW#vNnFLHh&ov)PK9=7*o_t$&ViQUPv%kwzr)m ziW|wB00IyV<8};vG%S(0U*Y47Php$DZTzy}k@1QiN{)GBSq7x~ZJ7JtI7wCwAp0hp z&*VO5zNQZROWOy4IXm?q{sM!4`3qEJP_({!gzaY>0TA1#z?J@N$+r)`re#ZNY~AJ! zC^GENnTn3DZ*9E~T=ld=;6;i}UbiUvR4;wm8DImv_G2pxq4qniJ6u{laON7F`A@(f zBr|imzr;OIRl#aBI+SKwd*!~dY+Y1&304~w(A^n21ScSETbw3q|LUq@&0d!VtLht* zp_uDB>$gDi7`n|WAXe#oG|ON5K1_YmJ%7)4ko$9VqD5onw&g7gNkv~F85ux-#DPWU zoiV}>>)d_a;}RGHwP#7A3~tI_MB4jAj!wOd zcdG0|aJOr#I**rDK`MdfJMoWKqT9KjWYH{!dXZ)MS+N8yY|?&3E!5?!-u&Cfw$I7? zW|+!F9sT@b7$`qW(|Y!2w`T zM%$*ttU%9)VhOo`xSK}GY@7tHl5BjyX*9J&%P$tQ*Y*=8!;PyQXCb}R=QncW>PH+M zjO}H9;BSg{c#Eo96c`}&kJ5QqS%}zJH4R9h{C4JUJw(^GK$F*W+CcQZmIS5*&?7fu z1jEmzFEv#t$RdWd5_yXO(57o##B*2$evU0bB!{ag)(J8HU%AI}O-#Ye~-tC4RlsVh#33ieMn*YUAZ7m zvjZVHiN7~KzPX9j$L=fADw4}gwd0D!klhG#IR?G+p8JFbn0zoz=qH|oercK*$fDuy zh7LZ998R3*U#=ZP+?4=|jF=CRpH`~M_NANQg>UUjFOF*_Y-J9MT47AFM{O${!SmeC2U9A=Vv7 znh5$3#!?=W0|ylodh$RYwFciqKJ84G?wsF7xa5tbAQ!h6l7N<>N(~?upS-`nb@{L^ zC*qH$8elZcj`2$P+wvM`#;A`teXLA%SjjC$x=FGnfgIjy92=vq>temA-(uJahZJS< zU|c)=yEq(@d~>5;!G?qGmxpiyod2vX>!pdvkcI($j{uB>CR$ACl^yU`2B=(=FVl; zU!#cqA(^3eO7~?i{h)ykG}>WVb1|A?r`1qz+)*oX@FtE=BL$q-&F@)A-Sw_AWsQ>J zRy3m^lx#0J6)TijW5=%Z?xW0m)Wd6p&dyhP;+-DfZWk9Ds=nK?Y==b)OaPBFeLG8H zeMk66+f2=Ak6z=&N}jwPpKf@ZL15zr9sV$vkU)gV`sk;CZ}bC*nB8PJmW7bLIv4e& zc=)GqTHuwbfy?HyU!6&5R7;uwxFbVkF`dRU6&dP4JgV^(e#mNLO{+Gd56_n8zOi@8%-7RN&Jf%@k)xoOu`D7cA$5YL?E1=z|A0}s&sc{ zw95x6E5>WjA{Iq^RsJ0jAHrO}%S-yX5M%CJ@vHU=I;xq| zWU{Q{4)UH_tLKiYjJT&g&2vu)x7eMNUnc{5U3*QB2iE$Sl9hFQPYQGLVOv*M_>kzU zz0EeZiptx=%A6he+lVkUmu@w5VD6q1$>*vcV*RCA{KIx%2<$l$Tg*a`uWcuvX|A7Z zOVkWlEbSv`Xh*v95}qhM6~O`c&jeh^z0QRIJxhm2zF4fUyAz?KE!aU2eM~Yq%8MvF zPsr2KQcNdGsqFXPcg5HMG&Hn6)QHOz4*e=kV(ly6S>_F)&yK;;TJP}66rF5ITrdC5 z!cyx~a;~j0qL*ga_~a!&nXUbiAoTc+T&iZkp>m3*P{o>&Q_!zw_>XvYDaj6Di@qN+ zmRm-efMW*B<#2_eu13}7p#`_<{%<_7PotXQap}x29OgW1MCw6>kC?lPsoRTGRNy;A z+MrhDopj-tzpHFuAtIC8UPx8KNGPI9q6p{P?ij2)92sFm8h>CU?|pPnGXd`vD@aKQ zDM{wj5i^k7@3g{`K+i=43yT^TtP>b2lPeLUnK?r+#Te!$CyNA zs^lF+GZppe-;fU;4M*O$WEW@Ofr6KBHgdYwUSmrK_@eliH@A5wh?zL z&nL)YVi)q;*sp^l4irMcSPGS1=K>~f);Izzz}xAgh`rpTWA|a{GaEQ>y4*qaVxWhv z(<;NB6ZfbFaZa>%6Mb>nXhu{%D$56 z4SoI?OIE-5Z-0ISi!u+s3zu>p)-E4-S236(41Pffs2$REu+PpPt*B{hrery<|AF=C zb%u`~NW9;oSl=kY@~x}@#T<{@rQ#=Tpf_vRFV92bOtJAhu8|Z@)~P?JbTYMPqxp(n z_B(0$OV$ts)UpQeSaS=dk7X|f2D?AeYae(*{u2~V(Vr+uU#~zla7q%3O|^+@m|5y_4VcbRuXP-tNH*x)foi?Ps;}2QCceGN5lVIj5eyaj|9tydfB_*+ zq`6FP9l~{atj@pPQL1J%d<$2Zn!{5LATg;&``k&THf$b-1x1VRgsPA;(gQbz&k zukQO~57s@o{s9%95QU1{XDEm#^v+*gIQB!osNP=eum58ERIsiX2#>;}KZ~wyz@y ziX7W_WceGSP$5}DvnT-KOI&Z(T#p9I+mA1qZheeA@qmcaDEi(F+IH;RG&2eut8gM` zMG&g;hn*uXtthJpZ1YIal9^!cJ2xely%6l)8S+3lbe!Fl3EBYyy;Y2A@IsFj3U!w{X}YAqSuu>M3_QKpIMZz%RUgK9~^Jj zO^Wm!!=8I#`2*m{_${<7dDS#NdSXOEw#7~VD6KMWCU7S6Eq=bCT6(9 zw_HC+0I!b7Cj(<7fZZ!Z+*At9=A-8yz`!AsM(7fMir7pGFT2&x+Lp6Eh8e3R$Lx}^ zg3)-<7f2IqW6+N0Gbm105nS#$!DC%x<_&oGwk|_9Sf)Du0=l68YH|)g94lP zqXLwhExV<0t>S264L zI3dC~@y5PaylOharisLm+rW~=nn!UEcW=RJ!-90H;;f1?XlvIK*ORib&Ens~B_wQi zUUik49@OSMWN+1Aw^AKI%rl4~Jj7jvdp`>Hwl4M$cpQnho0V+JIiUD!!4r=wN+myE ziR35#p+O0|O}CuxTg>n2d#{0vx=e|Qfd)m)i@Rixje{w}F^b>vHl1jHCm?vDrPI#l zGXo>P&h+Fb1rQMx!c)shDFY5a1KP?9Af*JTk(YOPqYZMSV%G;m?}U8!aL7i*AL0lf9k82BE0X_DL|HJYZx* zA}A^22!C$BuN}rvCt})=Asw_}lz3-*jWmBMn|Hh*Ufe{(Tr9Hr@RfKnyn2HY@bZL& zOPSu-llfJ7D=+tovXW~@zi&FTIHp_+Q)a9fxZ7*$$ewz!&9zLw+>YY?voZ4~Bi4W! z0P$wPHLAN?X3LS|kyfv;V%PDI0LF;$ar(w7$=gWQG^_sXXr(Bu<&0FuzDi2r8b3+T zaC2#OZ8wy(Y$%W&Y53_xMMqWJA%S42DgMe4-pRIHuQ%%*hGemSgq(4tHEUW(^j(%I zqffV)5Yap0qfP3Ug1k`@g@C}B_6LrOx(VmJ9&tAg=HGgb zfR@sMze+%%1zN{c>o_pbqG+I@70V?10DxmW{!ky05apX^yX7OW(aJuHkNJ4iiC^1G{Ahz6+vq>v& z{U1L4N&?-A!mCQ-aMJ4y-`%&1Fh<~Zur%3UAT`W)#?MlwkDWI?i2nykDE&@J8BgVCHRX=@Dg+02mS0YrbAX=ex}g~jyuL#4R7(O~raGoPh8AnI z1;x7yZ6}!*AD}Jt#()DF02ud7!5D%k$B*taa&mkqcgRRmyjg9Cy(OG%LL=*s5G1n2+pw1o@z7e(jlrBAjNC zQ9>5=@*(?HOI88BF;#h0)tb+m4lGZ5(6kgzZ~31)=i%RsZhk4WgHplW8$Cv`{AC>@ z_+@2RJrLd@lZ#L)aRtU-=hfj_%3&{tUjO}MhW`cD(P80<-pF#z2`C%yIp<& z$PW%In3WM=U3ATL6gV=467h9H&z`DqG=Ga~N>>FMEr}*N3nddE=!vr~Hd79X7(J;= zSLHm4bl0ck$W9rApIn_eGTSI{SU;!IS}Hn1zjFGH-4m*=bbuj?Qe%G8MXQ$)PDl?q#GZZOM_G8^zt_QPh!+;9#;KJnCcci2TYQ(!6Tv0qlrm z@4=R79DwF%an`tt*&_InG5@qpd*tI&+e%M+?E`OWK^E)z3Q*y|j4s)f^PIbKyQhZG zAz2}E_#eVn`!>Bwc=SUQlLJP&;WzzvG9T&(Q1ggaqjPmZ}X^!3beutq6Nskdlw5QFE1 zDrKvAXjkSe)F=-%hzjc=8`xD%cvZE0_igS3f_jNMkJL9R%4oVI ztSkos_HhCNh}k+`p<|)UVcB=s_}58ethn$1@$ck~9ep!yu~!JVqk&g6&xuGZF9r>R zlUId-fnI7AN{&J94WdI{x403VXhv04*%m4zsA!Bshq6gWe#X3Yo>o<=>_|Au#Et}R zrIc|m$d~Yjncm;winz4TDapAM2XOQrk1l<}C%vZ&+>exh(?_g2LA36^MPN=JeHQdJ z8rP5KHMLPv#3`GQ(471ITA{=Hj+aHO`)@c5w2AOSuOrsP)`v|A7|pPHU-ug;bj;J9q4X6xRQuR**d z(BhWAABNYDv+Jgbde2+NTs?HH#hhx~f6b!b;?Jg@Ol7C`@j}W5HRM%wB9X4kYUfz% zwt{Ch%`_j}X2!0_Zt5e8ybG{3(pEH_*gV6r-x&RLhBvS@S9ANQG9TSm?4rkJA#H_q z*0yKPz1G1v6I@rlO09(dGZQtqrFCSnRI#>U^z|c0-mKxv(C1iNb6q!mlSz>`86Lc{ zY0xKdX!Ou_*>}(W%#H5T!=)i<$g0nld$j|EaLoKRl-PbogAuiBQv^ld z?Q5oc(Ic|5Y*@x#V%oaTZzgtwPp@QsZ1xjseWuEaNd&&LDMP_`fj}E;K+U}R1Yk;S zs$SyX-0HW6o=uBc=QGp3cN8J;8u~5WatjTUFf4c9iNVRXmnXNR_DBBQ-Mc@lgkzpGC%kxVdq;(;X-Sv?E# zYC`w?p?J1SA-v))CHLeH#)A5kj%S;AVT?>j(;Z;sj z$|~5pA*@Mtlf9U+QybJp-a4^hi@-$yMZKtM&Nw+nq4nIdT;ChTRlP8pi&>!m z!Io<$d7^i#?Gd*4Y2p)$E@vC1a5{&2t;S>KhmL%rxq1@l9%nGoPm~0h-ArvljFa-*wCO@{Pvvhd(d5` zXRVE{zf%CL?vemcH+@M)w2yqv^C>(*G0uuwOL&77J97z(zdSyUm`)4wd_dy@lUG~1 z8CyKlQoOdF+@NzUGpsO9TSTDG1eE>4)R?ffR19h;0$G>34Z{m*uDM(mO=P@Xz*J4)dNH(}M}!T9f(^dD*}cA|DE zwHeDWbux7k30{7*)90Ad`0MIsX7Py)BXqIKyqT|BIy^% z$<7X>muf~GboGPF{`msHkX_c0pD!ec1;>^^0XLpZJ{+~FZFRkOky^(&I!p2-@|QFa z7y!O^48px|>}$FB+=(e9$HVR7+!eq76}1|_^)>)|kK(F{DM4zK|LXbUCSc``cC5B_ z^0_&|tZoRt?b+36BNngjR)E9!ycS^jOJXQ$2z**%duCkq)r<$FuR{>A_ zLZHRo*Ms$zHRLK$?=EL;_`s}LKrc4x2aTJppZp%YWrM_NHP%TsQt5L%HoDo+UalLVgjxR@ZUbkIKz5NU@h{~`2ps}%G@y3ln!SiK-p?q z{n_ep4PO7oMB8tj*8&HdrGk#U!>KdZ%S|Jt5M=Stkv^f*Mmc=rYcE=rWeSjU47z1% zl-V>j_%_v<6=*Mi)`!K)EO|#ca&s}=XF-$>u>1sSTIl6yL!qum#4R}y&(R>JANe%R z_C=LEXH3dCI0tjLfWfXHAe1=TY1c+SQrPm`L4VS7!z467(IFx&Z!)pzN}8qubC9qjc+!KY{{xux}_0@u$K-oSLi z?JBR5iHdX19RhLi2KLEPH%Ho<3z1T4x^$+?YUOQ{y|^$t6}xLNh?Z)OF0wN#Bp5@E z^$h?hG&;wPw>(|>`LBQ*T4ua0MM*oZ0O5UKi3r3pwP!<5z^ zel72#21hx}f@tW~s%McNEbBcP_JfR55!asVGm*F9yUgP=T`E^N^Q4;_KCv9Rj1%8L zgnzON2@?>7atczFxr@q%f;`C|@M`TP8wfbq{dhW&B*=wdhDf2&_UIF!4Sq&!!;1#J z74bK{niZ~>cYn2G0gSZuKdnkLcR+ za0vuD>zQMlS2{I&;ZCxG-sC0K1)X`Vtpo1M<;&w8oJ0}cArhY zg$m8_ci1U5Y|o=GupcE- zW&5uF!0FBOyrL=NKMZIQY6RMF%$CIxwe;=6_uoY)8=Dxq#WP7-?oyPSM#p)a0G+)^ z#NXmgpAIVQ9TYRie)_OoYc$2}nib=sl!D}AqK|)?uk*Txwu$GI5EZ}r6N`2eMwhf{ zHHjOrifBG(*cF_36!cmiaisFNKDwD+`dZPiv0$X~Bz`!VkDC@Gw{XGUKRWIJ^eAg{~K#=Qu>NCxWcHH`3%HjL^*<43hCYFoVYu!3Xe z>+GrQe{hwwv{2yh@HD+e9N~bMAA?hPYc`X2=u-F~(F;@D{0zG-0dFWBLeXZ`AjBbO z+7B{vnZFhUaj>~8fLEJVe0+(h+dTIVk~B@y`$UL2PHNL~5u4IK9NDlk*Q<~>z>i28 zi%vN6BnzzwN=cbnpfiYO(jv+dhcm`q&|mmaq7@75UZ*%rr!`zbglP8!OoWg!;Vs=k zK-~)_BJD;Js4__mf$$-6*Q(o@vv~#nIC5DKhxkjOzP0Ww8m$wzGh;mxI9AQ`H7&D* zFv&LBa#K*Wc-^I~oA;KsJ5fGLb}rPbf{wVH&JnG5TeJ~F+8q96gp;&pG@YqVv}BPFNi~~>L~-7G){~9Y1JU!o5+EVd%@`c6UlB`R1#LJq5aEQ zq{T^il7+tHf2xq!*@NQXveW|N7hmBPUISd!twd%XIoidOi>gh|te^8JhZvNQEy+8s zRXMoaX(Rg}Ip8wlX843Z7oic140~nDKVS8VDgr_*C>!}kFjua0FYc0ZV^H=cWhGK2 zdsZ^{RmD?rVcG}L4cRDtO699eKhvn*^d*i>dJJ4h#^}U1loKC!N_=BQHs_^qMR%Ni!tmGRt_=o zWU;-DJrB&6B>=+O%Erl-KfQqHJo;mL{D>WV!Ns;v6ZqTwU$mi}ghnMoNi3I+3Fr_C z@)lgLxiT8eVt|F2%gmuZyhv9iY1NOV<_Ac9=QUyMl(uEcb0EeVT#dy=$GsDRNG0xf zquz&y8X{iHk&_}N8X6gH0LfS?hWqg4%2kezT4y;rJ;*LFBXFoKr~%~ZadZaa#f@9I za-Dlp_X=IG1M|{Mo}N~CBb1L$g_UtzkQosOPt$l=cMB~l!ni@0j?-pdr{ zY5bS)SRB@Coj1)dPvyehE}T%Y?=s>$(PW7aVtA)*$WHX4O??6(pKR3vx9@`D zopMyZf9+!TOQAIsuT2d(uH?Mk8gU&HMF;Eh6~M zsy>5C?@l7)Zc!oX5!gR`DAZy8+lvcQo`~E(b3iALB>WNFhOvy?hCafC*XSAWR3`ct zxDE{0ymRp++E}JXg=fS?q=1D9m_d!9Z)GZGx36W|4 zcU<&mtn2W3#wKimE}y(wc<=({aD#pf?FM3R_SgV3=%VCOH~8I!TDz!VAYpuL?Agfj`0MOfy&`B^~mGX25EZzcw~H1;J~k&Tg2;aBikG7=L|eFeMi+M31t&P>XMelgOQE zkCQuCl@@_((vmtDRsZOA8H^+td=8WH+5HX0`c)-K8YxFm5OeqTc7IOUur0YP&@99H zmllg#zN7lScN#aK@*2U@7V1aCZ--%iJz?fodZKLlqu|HK7vI|Owr;|HwBe~V{X^2j z!1?NSgbb5tK~2~!ck+5lei9PFe+}0i+M-q9M5_kqk6{%4kwf>yBTnx47}hiA2v~R|Mj6imY&SJYp}j4z+l0e<-<;AqnTvlI_XMAItcj zXd8j6lGAQ|0Rc)>K&J*pFB7%H@X%D2512_w(_@=vzw96&Q5g}L75wL4QR9_~>y=<5 z>oKB40+q9{8`jh4xCF_Ok15#S1jOtR$Yg$1fy*7^BtHn@36hdsYdREG4Ol~w#X-j- z(0tPgayY;Xe@+~^9^8o$OuYu(4KNH2F&d1$Ux!c!j<_rXi)b z`{h9-D|H;`zE!Ouc&aLF{2uKR8zzdFTues?leBse(xWQ=O;=hersEW}D#kSVo>4r5 zh{w}A|Kto0|Bo&R&@U1R`HGD$Y}us1;vdxz^37e1`yWY#xw0!~xGISK+onI_|2jFp zlEH=3xB2me=MlET-IJ5Y%fS2y>Wq30-!Z*dfS$7rO1S<%86$<=;SNaX-ZNFI0JD#d zDIfdj-E;XjZ}!$_4C}BR4LD8$JJDr7XX4TTh{K(p#L?fzrI>S$vN(`3WAP9BW#q$2A(>OROTlWEv0DcY!e@Sew4ZJ1etN{MGmdBvPU?NY}qzNcj=UOcpqgv zTRnYAxvXXyaoROhsQ`G|W;XWiWKEPsPit>JsfFM;&d*|Fx1Yht2Hn1nmR$9>M8}oJ zu7)=?a+=C@PlN)S$ig&xrfAz+L?sRw@L7;j@aCV03R6@Srnx6RxcA)YYtng+5_J5; z%?oO=D=ri;{S0$lkSg^YR>9UW7LW*d3DbdU3KgA;Kr?2}t7MK zQEbDcyh0|J$L>tKg$z1`C#+Yd9KvbI*QDd1O|zhjM=G++%3EC2+UEb2pfFKr7sf&= zZZrwIE|9QRRCKOof}OvtrN~^@^`b4sih+($+u1a?WRS#8R^f&1if<+##yrpRaAo`` zTjhN3^CF8@`GK*i!}5QC$2~MmgdbjwW88MFy?Dan)f7|DY8_Q-)n}%3m2~{o2^DK{ zu5R^6Y9N<$cMCsiD}_*_Hm%as@a#tgYUZcs837N4h9vO-OY^uzb+g*q+Mi#nHMO7Y zyBB{O7IsMnzu&7bYbM-TKD60y8foQuC9}kdBOP9;jQWU3o=!1P-|VV>rsXV zFW=0&QBmL5 zrx=pm4+m5z1T?kgdb2eQ^eq*f#*59nCN6fifJOFznqFu>L}VK0ZF#D!!oDYy3+2w8 zgNt?DiL1sv{w&5vTT+|BeUtKj!~QH3H{_(if3yIE_rwz0HjvuH^p?$>Aq=&7D{w`Y zAM#*p>L+lB%D-L9zh@Y60DKJ&nIL_Lv54DuIZdq&HT|YB{-FG; zZ2cxlrN4y1f;e2^WW}37Nn1E|LaVOu!8gW{)FV1Zu8L%q-o=aQYEM)VSVB*!_sC#@lJeL)l<0t?kcFm^W37B8*fh-!FQYu${(B6LQQevY1}zu~4%HxPnU9t2r$D z7e-7s6V2w??Dr}{(sVHj>ijeKYCRYZ*7xaf)-G9wh~iE0(R#GU_`3xQmWcvNTt7hZ z;^?ZeI7gW(7RW#iXq{E9Xq+*k_9DWS3vQ$SA+1*Uprf>>(oS}4?WsB0N(FKuCk9iDtnj%p6f!jk+i@J34S z%dVjOiNg8$)mm4$F1t*;mCk z53!n6+$1FC-KB+%D?I#Wz?#LZUMV)V?!ptoWaC^=WUub3{J#-3K@Q6gB)jP#b8t)O zmah2p2Eyf%o5lo{>aX+sI&HZQ9v9+$QVAE<3zrT|f$h)S(&u}PcCB!}4afQg*+-x0 zJDvIa@UCrqVWR~HWn(TtIC`MWcHb2I516r}Ny(Z@DKcwoLb=fyg_ z=1Z4C>xp|;{D6{<`~0^YpkNy6ULl9T;B_rzc%;$>1Ztx3FZG_}bHm@YYE^Y{Mn3Qw zly*uYw=FHtqIZd{;c6Tp=ipg&ex^T3LJHK4G%svw^*O`L} z0FX;srB5I_S+nZ3f#mcZYqaM^OA3)*yg}Jq)4F!58fvnI=Z*CnBT8n~i8d83UN@>L zVg6pOt*LL(%Eg=AWiXM~sTl1Z zLM0N)Qqx{Ve!~96{jV*mJPN! zSRIoH{$;DW`hjc@r#G-rcsg8J?!f^fKyC4l1Syof(TWp8?`I`wCR-TQ@uT~_T+DWc z9wW53kReAqFPhEudJ!A+JaU~zHmw>~DHVsXWMPpTp^$u8%RwQD#yJ)HP|P)Ti$#;& z6GpHeqY{ltzDsfu9i8yJF!q~D5*wn~4HC6QoUdmXM~Cz&W&*5VOj8?3YAe1kXqcI5 z*56IeJ?+@EOZy_eoRlbzvY(z2e(oDVy!~Q%AL|#|K_w_09dP5!1K?f?r^EM~cuCFs z_3Da2c5s4c7#v+|reoGvx6ek>GwzgOmFbjKH^P7b`W-t@jzLueJ4R#aovDteXH!ql zd8lkesxEBxyFlXrJD64B?OV}&^sL_;$KsR3!mj~;*ZDA_SbTdlg^1EgXz89M?1WNH zfRqh|8(YKmuMBBxkAs+6if%4Pu9)reV7{2SUFkLxq0gYeDo(bynI^9x=lrg;(4VOP ziJz2Q*;!G1&RR#!gNLmTtD}wDqm82DOeaz$uoQRPB}0&o?>6OIqzTLOCup7~@z04_ zIl3i`;3{k_Kr_%lh$=dr$JepO)lL^dfWzpQEeqzmKjq5ixsoY}FAxzym0@v){RJtK z|9~l$i>Gv>lZxeA+G;FIN*v*n{E4F4B}Q5{1)H&zv54 zY1b%{!$kjCK|k-;?I}iG!S0=}i2RmhUwwkie0c91&6zJiAW!Nb{pgSVFsXPlCJ9zF-YX>*rDy+yKL3~babSnVIela|;G5F^yN&p-GFGY|vvnK` zIscC@<`mcdu)K8LKC7OAa<7nT6z?}5_gZlWK1j;6;9GH;6fcgBlu46dk*_XesPoQ; z3Ux(D5`}XiPLnkW!Lt-51LNu?t!EZ$0_^6FHtBW?=U+*6P~`aN6MMjp;k%P6j1}P% zZW%Nf82y=tEtkVUr_F`igS5+~Ay0d6`NqRr&k-@G>*1_;)?t&hUmisnsZ;P1MCvDS zsFF|MaeV(Kzh)yc#qts`2E6=_n}3sI(XhPgb#>E`e?9*1hjsV8Bt}c7>ozeaI3>IX5aqAx+Kz4By(zIel)BU#w zo^t$$v(MAaqsZMHi&#^^?viqCr;%qRo^tFy$6xghrv-qvZN>Y$DH#DA{o|y`i_WV_ zmB!aE8aBh-`Od6kCVw7^F_L-K^~2&5C{53?eOh&HTtaPiZ{mS>g&+Ag46($h$!?d} zLNwV1^=G&Ggs#26)0oxVU3~`%d?F{I7~T;dzE{1zA@VdoHTpE4S;GD4bn2vvN{7LQ zy|M5;If;0!JRye!EdmE1MK%n6{D{SeahLx>9w8{J{~m$h)pOMjxIew+dlanu&AY{6 z!Y+-H@raWOD96_NOx%y!v-+xDRNz%<@ zW6-#&3AlSvu@=hie2|lLBL8d9e5)rR$9|ev>{qkxagGC2XFz{ypztx?#QJL3^#>#_HFYl2R5 zxl(AzL`B2EE7f-1iPuTaUKvxp!JZ$mOmZOBVz1G6+6D2n%CSEYtF*esHd zR&QrgKJNpUyx;H?{9}~HaA9`wQ@6Pp?qi#LQ83y_B4XIHfh15hSdWJ#FP+CW>v_0# zhVFsg(rm%50efP1#pLr3U(>-Ass~F>#p6&+67sE-8bg9P&#m&kBkS3gmY6q1)?6Gdkt??}l+}>OSJ#;+G zVy;rqc8w0&FE(h8obShXSfW7UN(B16cJ1OAm3AK≪khHt4!C>F{WF@AMsRO4)B}#ikLV~ zHR8Eq<~9Z0dVSrsYnMQ=sB3oEo{b09_o{onyuRKOg7(z*^G`Mf%@C8hR;WTx>;wln zI^AWz-!H%Ac7tn;&tKAoNoU!Tv4a?6gJTZj(mF}m=PK2(Fe%Y(>SbNQ%u3=yvT5iy%(ExNSXAyRVc}GV*%OS zY^9vs&8&zVT&q;ta2Ym`erCyc$LoEY0*Pz6g-o-!zh_vNTKPTC`eD(<-aUk1>Cz4Q zJx;cM!f27vnNR6hQxrDU@8?m|j`mx!;w(348@}rbC`UjpC6-yJmYt-;35!pcJQS81 zH=Z{*CG`=>4}jZG2nYx7+nSs1rhJP$%#C)PDuJg0kiA8PjRh8(^>=Y~h7NwL%?+9c z-tJzr#lv@oYKswe$(XB(EDxtguN#gp1|ej(otsX>>7K|;yx zMgKwWa-3p*+0jOKnKKK9^8Vd%Esb^!KvHATEvT8V@zwnxomVAvB;cdTRjJkOmx1fm zrKQ@N#v_Kj<66OHfsGY?%|!Biu=xn^8iKv0V5QurKEvMc9=0EQR@!U@{Q4CzN7dR| zRsC`KY(J^QW{<@lW;*(>gJZjW=&b8bcLKm>NS!G zG2Gs7x#n@)X^<{!yvHbUOgFriaHrzfR==@U8f^kCW7s%TvXrVV-RE!u5_qxCs+aS9Z#ez3xvX}lha%V+7tXY!JV6t|8(Uto{WjCznuS5b|(IoyiN zmN$$w{x!_+e#~bopzoIRP46psrcUqToCG6j5VF5yTX`?X^u%t~i-~}1N&QQFs{q8` z{j^K_9BR@W)uO3Ukl|j@De}qyH4EmeTO!or{79i&b5*i^_kpHHi1LZZt0h%R>UpUiI# zoU>>S444mYoWzx%>H=%@$nOj8GgZj7Pgi`?-L4@=h_PAQHKpH-_=q9wUsbhm;z8-23%dw`VTjn1G2fdszYU|^f|bzbt!MCeDDTj zb~mPN21F(%R*M9@n%Lvzkqt3+F>NU4sanZZVdu>r>S;GxS71>7Kh1q-R8!d(uOf~G z#SSV8jv`2j5fCCRU_q(`2?C)-sX{1Hr3J)>f)Hxx1f>~i6GB1Z~^-|Fz!N$0ruK+gw|va z;B7#A+p5o*kwl8~pSd-Z)wBkVr4)+xNkPo=Xn$Sw`TlOdbXT>Z@5giy%B4kA#Bu-i zBOMPGQQtz%P!~b`0Uwm5ie`n({ck+y<<;_*S0|K!Jezke%%r(=txsLS#C_yXdG1x` zvGK>L~!8df=e^hRla!3MYEJvU3lB4V8W9xyj1zg^NQCv~QC< zlL73Hzzd46P*ESh!U|lrNfcP(I6>}e4 z<=qW=PT-f&@*5wd!-icmvig| zqqJug5NCT2Oh?@+&W$z||GNgYGCG&NW6b_OPd?}F-M_9I28{4aJPUu&T3UVP+j^dK zSLL<*-LU8PO&?exZT7FY4Y>8recj%z=Ue@v=i|4HuCvV43V41_uB*AR)oX9>&QRBm zS$ytVUz%fVxpn`-q_~~QdBt5&#k|?h7MtqZ@_v$K{iIYT5%QFOA;i%F9Xd5oh~!50o9hRlD;2G>UGUwdw)@FjJDyY63vLVU46gRjFEiwB0UG~W2!3$wev$b#TXqYjyJz-HMb$Fvvr)1Q8}){^h|ec~Mz<^y3?-2A|3--ejn~cK`SsnsMGFu92bZshdHL$dM5L zgCos=SwN`8qedf)PMZV6X#+rE{Bf zl%jdJ*}v5Pp54W;JOAq46sc@SXYbm-wePZhccTOF|F*1AyZL{g6>u<{b$ns_Ug5r7 z|KkIoLsId?x?_-Q+vbs%bicMUVRZuqr=n)70)ouegG@&u&ehP>V%k$@AI?WnOdT$O zQD8IjPGBVZp=312DsVVCGFwPRxX>fB&)dhZvQXBga`O2I?fp8*+4|- z=yiz(9mPnP&#hJKanDGU%gWPSMCs*WNXDyrLiQgcU8wEU<0)wsf4U*4!8V^C%eTJt zF9}?$xf%R({6&J>Q_t8}qCULZoK55IAULc~Lb*6E+Nr?oOq|(V$fAoGsMFEc?756> zbdrj%8M&{>B(?l*P;ys=E_TM-*D)sDZw9LfnTdVaj3N$cQwq4mP@7>G}KW82XoYIaEo>C`zsex52Rwz4+G%OA^jK3DMHb) zNxL!vzlRojIP-w2Ckz%k6%#OZrL!pq5yhsueeT3hf!*QBQiIW)B;l&A{zCfeIGeEH0D7G+qHG1qDaB1-BjGT&?~U(PDgC?O z{!Ede6TLNscnV6yb!Jyjz;mO%(~~l*RQ6#G ztbKL#K6`gQSx@*1=s;hqXz1!vz4`Q=(|b_(!hwBS%0}xt_$z>OQ;BZh9;P!2Q1{dQpG(CNgXL2$U1x|sR*mKfNvAO$>MeP`jA%0`LUOsU+?t)$FhI=>P zsd7IRWAO`~u0NJ^kZ1hIlC~^xEBNC2?ROsDdlvMa`HB0_Z9!O(OKVa7bZo4&al**L zM#Fi85JAnFPK_%UJROBe^}TZwTyf*#6@ohUx%xh@{TnvRiA_wmkv_$d%1+6s(&?pQ zJ-YAyx)LRJ$OO~6E$HJy(8KR~8|)oP8MEX`>w&L(5ahqwmX|-&U3r45SZ=*L-gez* zx=6{x?gGZq`-Zc{-Gr3d?81NMh{az#;*T1e?|(J+Z`xE zg-5FF!#<0naUZYU{OIy_kISJ_Cz7MzEYXb}wqp45Mnlsqb|=qupV7v)!Xa`1q8O!m z5n7^&T{@uQov-@bcV(2LJ{!e(dC#;Xw%kHxaxOfq+W+>{2w=zF13i(Ro3b}I$V`bTc$)p(ccyOj&X?>FZPddT zi|avs@wqXce+YfsASC@7F7b(K?@VVeLG{`_Yp*puf)>!pRM^wVh#FQTe@{{LS$yu~6WZCK7zFElwonW4(wtoY*F{F#aZ%eAJ~e+A_xoV!;!_P(ev|iP zS#mjT%0#r#YTCqSZCvaG)K6cqoLy{f=de%lkz@$WY6epQ9*GP<%Q47j7Z+$ zkL&Q#q1`{wF5ZT_$9Z;O50a2z!#>{d3;?{AeOx@F#3z`#$%p-75(RCA8l_I&bB}V7 zCL0Co?t=$lQBRA*o)2msF=4H>!JK%IIS9$}U8^Gtt%Gt*8`ccyn^E=B(=c~$8wOT= zB(aY_IYzhrtPrgeAduydCLy7S!1cV?!W9woJaSFz_quxsLm%o*yLm>GO*L>|%9ja~ z?vldnioUtlj$H?Ur%zaGaBwG&aPHTOaTdzVTZuL<3yjF-q0LE%9sC7&Sdlq07g2lk z6O;(oM-RA=HPIpGJ7{(RZSaK(tyImX+vW$>G4>UBe^yNnD!e#5EOe zo~uouLH-E+#pD0lo3cK5zrCtFb7>~e@XY7CNLv5fP&n&`@V}1u=hsU&)2x<;^YqT( zvn>r^gM^%yTt9~KA33Ai&ppwd-q}_>^Kx<39Bh++C5~?S-BB=O2o6NPkP7)<1Lmt=fCO&k5VM?bxcn zg2WD8DBJ}u!{J)FPj=%06r(*d3WY@RTm4JD{WFS7396(@AJX#3q3muM^PN$)kLm_H9TSO&UW*xkLIp}1-263qy-faNOgr&zp z?^Uck)I0J#2Y4HHatX}QC`Hf6$VhBVU1jCav#57P8uvZ9R(2%~H1tdj5m%x!K^3Drh4wSCeqdBiwiI1A@J3St_wmwc0%SY_rpEOHFCKW$zar8okTH z9xhxUuF-CS_ARe5so*eHhpEd;LEk4WXIk>P7YQZIX2k-Ju1a&NiQ~Qi=)`LcaLFThubHfNCad)CjC#W(nP|t;u~vfVaY1k${vXv) zwtHMqk;D#1({%MOSKqfFF^`2n-l^(aw<6>TgS`Z2vR2#rwWe%+2~!u|0|#&mdw$BK zUtZ`JkhI@SD=ZF>SuD)f@YvS-WcBZMyMO`;2Wy44Do-37nlBkZMi0E@(!3=Kil6#6 z!hmL7&&dn6D2hy1$3Xdo|A$Qq56+<%(9}#*XYD#ev4{(j2O2+q zUZBX&AJ63aY*f8M6NTZR$|KQVex>!lgLC1gD!V<9WfbUn!P+$FlR^))V!Wz<#mC;t zd+^ox*s&{o4BQTnICFcOkHE?sS6p`4X$3NaaQW_l3%_~hF%6Gb#zx3U zQH{$~wLk17uu5vGdJ@}5IXpH>g2N|+)S58%$uj}U$T>G*=V9P(=0}55e!U*iRk+UKk{-k@ zE3f--3hgb2vrQU%CyLLFLXdsP^&W$s+it>8$!IXVti3~{S|e?)7@X%XT=$g=E%l&`8O`V0k3I$S#pkv13KhGX zKP5<1jL2z3Ijz$3i(1`l^trvFJu_0^&Pht>G* zun6Di`%Gl^7gt)r7^IrO=-A`Kbi$#oE zhd4Hd(z`!_R4j5+8irh}dR!a*Ckj|CNmrAUL2uSc`1be}QcYR24D>Q=H38{liiz{$ zWpb24@nC1DO8C7knJ{^%u6MZG5v{8Q!Nn2sy(Z>%9xPZjW7*aCTVS0hFX4SUD)ON& zl;Ijzfpf5x`H6Z7{WF9;a&GSVJas3j6dks72d(3J5<@L>U|ZFtH|vdKnawnntCnPX zj-U|zz-vPMN|AlOTr6G2G}8r(g5q5MUs+(0IG91Nt>JY^a&BG0>j2Mxd7JP4mswlo z4|J*ub9`1SVRGinOU9%5=gO!Lq>-%Jx%FERJSQus=p)_MOBT;Rz^~rkVf*YLm{#Db z9K1qG$SX_Lw(@#Q^$1OXIkibRwCav7`~PD9pB%mkTlZDC$fAof81#T#e}gfsd!h}U zqovrm)Vg?uGNojXnvPMVki?_-BF-mrsy4bur`EUL5ZUMd{mSz#(l<|C zl^sGeNgj4;`{8rEB+-XHc|<4X_@5b2(*8ZSc&i+mPdTdrKyGP-T& zBz+(Q02fzM-od+Rl6=}>z42oG{vxc$ruS~32Mo=Vj;TBHZkD@+!(fb4Ky1&Nu?>vV zwl=^&spd8W-IA%7+_^nw5qUN8K-+pF%Mb5cFIWA!Wck}VLaJ$AYSOBeoX-mUbd6*ex^`9})`wg{kn=P<4loMed(4n?hR1JrDS(N09NIP}s0x=U zl*T1#SZBQ4>2o=wHH9l*e-}tW3Fq#v(%SdwOU-IC=y3bsa3|l?qQ~mk_9{N2t7Y#R zqLm&MMQ^J@fWTOq`Z|0XB4=B<(H=jk(hc_89uws{CN#XXsTE58KoIL)^ zcTU}|mP76%n8lL$VrjgmDQ-H{XlPcMtYUVz#_v94T!)Js$jV_t+n5;`eCoq-Xy;It zAH%Z&ZXYn4qt?knR87zl=_WGD*pm?4XvcX0^D}rm>41B#k?$=hjFho_Mkgi-dHfwA z=dXfBlc?It!N+tB3cSXRu~xu{a1%X6$agjzcqCIr^NP<0LhSnva>bdN-*? z0w7hK)Lmk@TM8c#nvg2$lv{$~+;ISyJKK>})5OMDZHat~FSjEm5kkB|=@m0a(_sv{ z_UDqhdt|Kw6q0DAESsNCU2QVNH&G1OO_WBVvG{6xH(&td_?-|2Od-9`@nN4b$f>@MSYSBjG=FB%^(NufE)c;4%{r{HXBh~D~e<|l6aqLVF z=B7FuJB|Mk%(h1oZ`p=ryR)TSC}lkzMX(=>wx1=NuKFhQC4@tlNicbOwWTU+RcV%8 zHky@Tp&{YnjW0df=31e$WM5HtsI|7kkuwmNO_3tyF^qrhDF5H}ji z3N#hKO~_j-AA%Voc?I2sB5!Ov3DG!7hcniXxkt_UxVBgl0_(lf_X;Zz+HI>|4D!WJ z%<|KjI-Mm9LOajf8cbIKxpvVXKlGyMx((@EhEAQ7;`vH&2aRky1`*gwMVjxIa^@#0 zR5F1Kp~1-lS6-sYdxc7T<234Bl-G z>UjRe3^(k=oUCd65G=<^n9f`x4!uZ0+Dt)^*nQ@;dxf)-+MykViw1rE;%Jpw^(}?A zBz)Je(|bv*nq5=YZBbj+;}Z<_GH64aQC>~AmwJZzj1@x@vq9vB0s9q4!=M}d$6RKb z__a;nahh~Bo93H(H%t6m?itIPBP_2aGkl*!Uga2{5{}}k7 zW|6yoMy58{>GiCf#x_vudGza#lZh_m&$&_yYve3RJQ^*dh{d0p%`tT`4EhAq;XlT| z%iqisXLWGs6mi`cn*(i=rFvAps5*0)|N3Pk_o8YHKIP%lxu+%FKKfQY9%h4<<@X!M zUT+~jzk`3RJ2;SCB^%@d0d2b4)Ew=){ZlWZObFI#Nk+zT3NuC>DoiAz;7+glyz_P* zPSSIL7Z73wVej2^93-{b>lOJN*HEy~+geFouuO=J9>uI;x=DN*wF-QC z9?~?qbtq+0!5cX30#34YZ+oHa|2@W522NnxJO8~WLg==`TEta@tgIj+UVSZ;5 zw}2=>oxMQPcaCdvLQ*OD*rvaG#gwUbgy)|DkL(eNNb(O&C{l~h(@$byrrkW&WM&|O zCps5DAg+F@z<+o_ANLmVK9>X<3I=SM?0znCF-Rfl zib{iAwdQH0ClOu-h+LumbEpP!f8+dm2YH2Xx{a(r!_YwZYJyYiigyA()92YDFqom} z32UYt3ts|iSxGpJ$(zrOr?PfNmKa<5U;(Pj9GeTKCpr0Q*>c(oZc$#C*7J|u-I7;h zhcu?0nEp`PAJD#`7c$V?nsZETD8OgfK_`hNW;%?UprU9)KIoj>Dj!`gXu#H+0tZu=sYb6Socmp%3u=V+`PxB=3O8AXdJ(;%_I2Yxs5Cef;2l%2%E zO9|$o?PiKG5sbD!r$f3*E1cY=ko8N1ECw7DG5)4dZrZi6*P>W0fts;mWsctPKk0IV z$Q=KXgZRe6yMaq~?V0RupB&O(Z*mDOK1F2pO)$wT3yER)^`VdKQ08UZO;I3D z0<>W?!D6o=)IXf zcJugk_X&IW3=$S3?D9e3&+5|6WJgM}P66;UoRC^b8%qkyTwgO=aGN^SLFw(Gu4VZp zY!U&9;k|_j9z8lVw>lt+qiO=0gW-9a>OX*N8XHEeON!2(I@w02XmkVRA!ds9EVezS z@$Qz+y-zjUnF;MuI!5@W73=QN+%=d$8^2;vFx$`E3X2M0;@fSR(uk$-RiYy^=hf=U zafRQVkjKUC{U}?~6|9Y4HN%3BCQIc_iDp=2tpOSDV}p8=CxyyNx?Ei!L!~6W0m}3Z z&qC5h7kTF$=4#0VfOBoy;g5v^B&RLO;dWMZMvwY%j}9MAJLOFPy&-Dj6heM^i#tXG zt<$($0HnzF4_VL|u97zV^9)*xQiE)-HVw@z_1VZ(8nn~$1?+y3@t3d)x@mr=(*j*v zvkCCep{CfuvF>;}lgy9{2ULL&iB!|NYN>3K14{~nlS9zDnJ_}+=f?oOnoC@{wQbwp zM$H>n4gRs9o2(mTdr)KgUQUW=4s7a2xBy82#MXh}nUXlW8V}H59wNWTqSzaodmbWx z6OeTyX|h*5x0f*>c=KB@&9GJfCb3pW$p)5}78@#|WvzL-&5{7b+OCN$BebRCWeeWk zj{#PgJ{{v+b+&cvldt3CTDx6v@hu2rHIb@aV4A;@RVnN6Bo(47P6x`3nk^OThrr~2 zCDxMS<1C7q?_j2~<;iz8Ub&<9o&LQJZH0m=&R#v$P*@4H8xlf%ka=YmveUz>39wA^ z6*`)bPnMg6lSKmPH6pgQ#$kPFV`0ZA3qa$b9iNmMMf0Z($pwg0EjL3Ctf1+yBQ1aL zOuu(L6H)vHR#Q=s=sX{j98z#!sL~lb$%>)o6EGYoA6vSaMfl)*4l?dzm1#+!_5ww- zGa)rf49C)}(T6s`K083eP(;^;4(r}Ekzs%4x!?2RuGitW z-7vjo%Ar=iqjN}1vB3`Qs6)&a7O1>R6#yR#-Ly*?7h4uhtU;wdV{-&!uq7&7HYs|m zlz#L`G@_V+vGO5f5-c#u4oGv;zRp$0X{?o(cs4-OcW45Yw+rMf#06I?oXRxKBN$EC z4Kp>*rZ!u52>>|}8}s|NR_psKK?Z-TrUTN2_Quqin1L%u`M7G(Nw>0r_1F<|p->BB zm)hr*J@NRG%_H(P%}W@hdIRKaLz`??Q!|2Gt3q5GK4I_lZoM`A+veujf3h?|Bto3) zXad}@I%aV79Rpv&3DHUkG|a~w`w=MwStQUf6gCq%Y+w6F1#l7XsRkm*RzJ?p7u(pN zSyKUqVXPcXiKX!=QEG1b>vO+HRMqbAg+d0k{^j~WepWWHVSxX1iy8%J9=LfD3v3!a zZ4f@1_=Le9iwhVB8G!#6_oL5o~$LBR+5KFHD={2>)|Iw#B zvS;KNmp-9uY}#beAfKZ%p#%4=x64@|04y5Lxm9ZwA6Q?QkhJ7rl|4iNQ{1OeK9IaKIMrPE@lPcLg_D3>Tly*=HsDq zHkI81Oo!p@A(}sQ#`D=-vgT}3h#*_D8v$jRGMQ3ai}j3Nj4J7kDv$^ZjzT$V?9wtm z7dr;oR*1?(=-9l&U|LTaSL)Fmc39dhVn<0m>>S zWfWdb^44MUN3s?{(op#=9i5ZFzSfk{WKsyFN~!$5Bp4=U6xtj6g4sB06L|`UjE0&g z&7U3n48)j_$Fl?l&Uv#-;W>F($!2!hjcu8tqcv4s&55SsUepXL4V_H6`tO%5EpMgQQ@k4eTs20VmyNw!W(eaM;>pSj`m^dq%=@ZZ;8U0 z7D+DB(S3z(sCl5DH-93o{WzZtLYU$MMNG~$YJpY<1| z2KC=v;x=xFKlO^dBjVzYX>;Jv6qkD3LU+%CB{o_%9|JMNeGc>g;yyNNQ*(0E=qti1 z^WsfVDSl&%$=(J$bmoG|gBB^K8__as!AP+h>E0oa*8Rvz7-;Eq+oOffFK3ZF_@JC7$0RjpYXqdbDXpEgTG`s~di37o z@LSSXJz?O>kEz!qrO*Lwi-vvUFdJR9)uT=DucQ&WdD_je=!d+PTQZ)*ee#aZTbtxJ zrE1KzJBeCCgVnEnbDRgV6$(sNXi<}|VI-W;j{gySM=m%>wY{|fYgRpgUt(HaHgI7z z1t>FR6?}OYHbaGF-Y4Y3bKxH(_jNabb>%<&y* zC#7zFVRgoK<|nP*Y%Y(qqIpV<@7uCP9eA&(>=Gu3UaM z(%s{C-}FfJ5Z7t*gD@?e63M1OErJ6951J diff --git a/examples/ahrs_lsm9ds0/ahrs_lsm9ds0.ino b/examples/ahrs_lsm9ds0/ahrs_lsm9ds0.ino deleted file mode 100644 index 6a01436..0000000 --- a/examples/ahrs_lsm9ds0/ahrs_lsm9ds0.ino +++ /dev/null @@ -1,72 +0,0 @@ -#include -#include -#include -#include -#include - -// Create LSM9DS0 board instance. -Adafruit_LSM9DS0 lsm(1000); // Use I2C, ID #1000 - -// Create simple AHRS algorithm using the LSM9DS0 instance's accelerometer and magnetometer. -Adafruit_Simple_AHRS ahrs(&lsm.getAccel(), &lsm.getMag()); - -// Function to configure the sensors on the LSM9DS0 board. -// You don't need to change anything here, but have the option to select different -// range and gain values. -void configureLSM9DS0(void) -{ - // 1.) Set the accelerometer range - lsm.setupAccel(lsm.LSM9DS0_ACCELRANGE_2G); - //lsm.setupAccel(lsm.LSM9DS0_ACCELRANGE_4G); - //lsm.setupAccel(lsm.LSM9DS0_ACCELRANGE_6G); - //lsm.setupAccel(lsm.LSM9DS0_ACCELRANGE_8G); - //lsm.setupAccel(lsm.LSM9DS0_ACCELRANGE_16G); - - // 2.) Set the magnetometer sensitivity - lsm.setupMag(lsm.LSM9DS0_MAGGAIN_2GAUSS); - //lsm.setupMag(lsm.LSM9DS0_MAGGAIN_4GAUSS); - //lsm.setupMag(lsm.LSM9DS0_MAGGAIN_8GAUSS); - //lsm.setupMag(lsm.LSM9DS0_MAGGAIN_12GAUSS); - - // 3.) Setup the gyroscope - lsm.setupGyro(lsm.LSM9DS0_GYROSCALE_245DPS); - //lsm.setupGyro(lsm.LSM9DS0_GYROSCALE_500DPS); - //lsm.setupGyro(lsm.LSM9DS0_GYROSCALE_2000DPS); -} - -void setup(void) -{ - Serial.begin(115200); - Serial.println(F("Adafruit LSM9DS0 9 DOF Board AHRS Example")); Serial.println(""); - - // Initialise the LSM9DS0 board. - if(!lsm.begin()) - { - // There was a problem detecting the LSM9DS0 ... check your connections - Serial.print(F("Ooops, no LSM9DS0 detected ... Check your wiring or I2C ADDR!")); - while(1); - } - - // Setup the sensor gain and integration time. - configureLSM9DS0(); -} - -void loop(void) -{ - sensors_vec_t orientation; - - // Use the simple AHRS function to get the current orientation. - if (ahrs.getOrientation(&orientation)) - { - /* 'orientation' should have valid .roll and .pitch fields */ - Serial.print(F("Orientation: ")); - Serial.print(orientation.roll); - Serial.print(F(" ")); - Serial.print(orientation.pitch); - Serial.print(F(" ")); - Serial.print(orientation.heading); - Serial.println(F("")); - } - - delay(100); -} diff --git a/examples/ahrs_mahony/ahrs_mahony.ino b/examples/ahrs_mahony/ahrs_mahony.ino deleted file mode 100755 index a0eec21..0000000 --- a/examples/ahrs_mahony/ahrs_mahony.ino +++ /dev/null @@ -1,120 +0,0 @@ -#include -#include -#include -#include -#include -#include - -// Note: This sketch requires the MahonyAHRS sketch from -// https://github.com/PaulStoffregen/MahonyAHRS, or the -// MagdwickAHRS sketch from https://github.com/PaulStoffregen/MadgwickAHRS - -// Note: This sketch is a WORK IN PROGRESS - -// Create sensor instances. -Adafruit_L3GD20_Unified gyro(20); -Adafruit_LSM303_Accel_Unified accel(30301); -Adafruit_LSM303_Mag_Unified mag(30302); - -// Mag calibration values are calculated via ahrs_calibration. -// These values must be determined for each baord/environment. -// See the image in this sketch folder for the values used -// below. - -// Offsets applied to raw x/y/z values -float mag_offsets[3] = { -2.20F, -5.53F, -26.34F }; - -// Soft iron error compensation matrix -float mag_softiron_matrix[3][3] = { { 0.934, 0.005, 0.013 }, - { 0.005, 0.948, 0.012 }, - { 0.013, 0.012, 1.129 } }; - -float mag_field_strength = 48.41F; - -// Mahony is lighter weight as a filter and should be used -// on slower systems -Mahony filter; -//Madgwick filter; - -void setup() -{ - Serial.begin(115200); - - // Wait for the Serial Monitor to open (comment out to run without Serial Monitor) - // while(!Serial); - - Serial.println(F("Adafruit 10 DOF Board AHRS Calibration Example")); Serial.println(""); - - // Initialize the sensors. - if(!gyro.begin()) - { - /* There was a problem detecting the L3GD20 ... check your connections */ - Serial.println("Ooops, no L3GD20 detected ... Check your wiring!"); - while(1); - } - - if(!accel.begin()) - { - /* There was a problem detecting the LSM303DLHC ... check your connections */ - Serial.println("Ooops, no L3M303DLHC accel detected ... Check your wiring!"); - while(1); - } - - if(!mag.begin()) - { - /* There was a problem detecting the LSM303DLHC ... check your connections */ - Serial.println("Ooops, no L3M303DLHC mag detected ... Check your wiring!"); - while(1); - } - - // Filter expects 50 samples per second - filter.begin(50); -} - -void loop(void) -{ - sensors_event_t gyro_event; - sensors_event_t accel_event; - sensors_event_t mag_event; - - // Get new data samples - gyro.getEvent(&gyro_event); - accel.getEvent(&accel_event); - mag.getEvent(&mag_event); - - // Apply mag offset compensation (base values in uTesla) - float x = mag_event.magnetic.x - mag_offsets[0]; - float y = mag_event.magnetic.y - mag_offsets[1]; - float z = mag_event.magnetic.z - mag_offsets[2]; - - // Apply mag soft iron error compensation - float mx = x * mag_softiron_matrix[0][0] + y * mag_softiron_matrix[0][1] + z * mag_softiron_matrix[0][2]; - float my = x * mag_softiron_matrix[1][0] + y * mag_softiron_matrix[1][1] + z * mag_softiron_matrix[1][2]; - float mz = x * mag_softiron_matrix[2][0] + y * mag_softiron_matrix[2][1] + z * mag_softiron_matrix[2][2]; - - // The filter library expects gyro data in degrees/s, but adafruit sensor - // uses rad/s so we need to convert them first (or adapt the filter lib - // where they are being converted) - float gx = gyro_event.gyro.x * 57.2958F; - float gy = gyro_event.gyro.y * 57.2958F; - float gz = gyro_event.gyro.z * 57.2958F; - - // Update the filter - filter.update(gx, gy, gz, - accel_event.acceleration.x, accel_event.acceleration.y, accel_event.acceleration.z, - mx, my, mz); - - // Print the orientation filter output - float roll = filter.getRoll(); - float pitch = filter.getPitch(); - float heading = filter.getYaw(); - Serial.print(millis()); - Serial.print(" - Orientation: "); - Serial.print(heading); - Serial.print(" "); - Serial.print(pitch); - Serial.print(" "); - Serial.println(roll); - - delay(10); -} diff --git a/examples/ahrs_mahony/sample_config_data.png b/examples/ahrs_mahony/sample_config_data.png deleted file mode 100755 index 02c3c49efce9ca460c5152b651c9cd3b18843e34..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 219474 zcmdpdgwvNszVj!B~XwEkf5NTP^2WqK0`slN+qJ4!7euIIK%C#{Q@v%((ycI z>jW7~!-p!ew5iqzv3eEF8Y_iK@paE~58v5{R1roj3*qn!Tq@;Tj?K;7S9z6>t9wT- zU+C@_<&m_Xd7t#9QbBQ!P$C=TV;j=Ex9Fs>P{?Z`)a+39c4Vto4YF_8R?v-f5#OM1 zAR?vZc8emV<#$U-r{o2qhulI%585HK|cdCu+7Kh9r1%kxaY-KFY zS`B1roHVRVJGA-0p%HrQyk6iCQ}hnCc;v0F>IhmWaojvr3@ugE*+DJ!dKho_rRepx zOhPsNjStb4n?Aem=Pf+np}2xie%nqS*@pU?kkDAH0q4#T(=J5)TchlnepUAF5Li|D zcQtkIl(I`$At3 zMKY58kSqxrpBveDp5a>+o zX_}zYgd^DTu0;J(5YPs*S^0jADDUHn3c_LjZ~%UmhNZ@43rR@vuU3>&p=F5M7XjyE z7SpI4blwEq_B0sTYT&wJTf=olSAJI}iO`H$e-{$Zg_j-y-*4ED((lyI1!dC48`h5W z0jc*BrYNeuxOum7xP*Bq&luKj#T#4&C~WgAtMK-W9Dzmj$BGjH{4%9yT>Eyfjth1J z>f>*&C`%m|hifELi_jveFcK{EDreXdZ+`R)PXzK0zfOL|*kqmdh4B>Dm+W=F0DgrA zrX&JKymcI!`8&c9m~c^gIt1$a~@H#h*dOS9^x$= zZ$z5d7-jn)a~>(a*prx04xY5Qi<0s*e0qpyuIzgxxetZ8yt_W0?{jp zo(Tu}s_&EzLp-Pe9Kb68bp`xvh;>(bzi!v%<~Mu&Q|vax6^xT`^Yy7y-kbTG&)#o+ z`Jd3A-aHZbLOmynknQ%|T~ml*P9io3HU}mIjs~^|Vg>4Tf9!r2Bl(_!5A!k9L5xdD zoQWDhbxcD-t4D*1z8d#la)(O&GY@?L6$LZ7YK&_vFoq?LBu;#~Zn_NY4c?e;vif9I z3T`N_FV+1_s7RY<)K_9BKVU^hF*oPUUv9__dg|-C~#9az%igflr zSTWZJd8XWbR+gL6iYw;*SgTPheeq?7dK98%rNyO1u4PjWr&X^NTo157v7V~at=p`- zs8_c-nHH*i6bmjg&c!O|0n<-d{^ZTSi2gQFWIs%P`tkYk6xcFs+xl)I&Mq8UHXr&O`V%4-g^wE$ ztu_o|4cKS%y7E9KbJHX5yH#vjCVs{5IdS;ZlGWCD0CL& zi(|=CpHi3#W|C#1VBW%U!CA(kOl(LTN|a%`)>^6k+<4wF+)z@tUqwJ*CnRL{(010^ zzuKTyd)2U`ZC7<%=WA|k9cNX$Q~=%yEzf2KHO#pt9qICi>1Hi6wR*OeUcq|V-3#20 zUJ0TW1q8#aX3wn0Qtt2W(b+E@&hftz?lS*s@!>I$P~L>LKskGgrO?;h2Vw!C9xESX zr3GdtvpF2~j)m&uk-Q-{Cfo#u13@N9)GS9Vel2`Wjyl%5l`Tq3-OD&F_08>$ZqATq zJBQ9a(Tk8XjpK>+v-v5I^2Yoj?=I&Gy3dH+Vs7nah2YBOsdig8i z_W1g-XMBit+^%pnPO2f!J+48{bJuQf{HpTe1UU=A1pWd0C$0s?AZi(!H@eB&UX%rr zU&)r^Bc{h@9dFEFWxk@pbt0dkq>wsNU?WGqW=1|jokEmBEk$f41>k33bufCO;olP1__yzae~3U1m6!iJ)X9vl(vd`i@p~jOrTE0?q1=&H**|mNp7v4sm__3 z;Xxk=)5djUUE%Uod#F@?t-Mh?}}lj1PT)5TZNWg@6z@l z=6K`iV?2DyPBdOS{<7X?Ry$)O3Wq$df?hn~3H9{WAz0n>KRo(THq;yuJf7N+RyJ*( z55o>=d7pR>9N};M9~hpTL_@N~PZ_w`-K>vW+nU;lJ#xEM)>phg`FDS+`l2U2?$|!NXe7 zi8+bcYQEO`+Me1c>qEi(3y%wEkNXb?KuR15tEhcqT_4#;jiKs^&Ax$Pg%AY+;S{HH z!+{YXf8nIOuAtzy^L0uQ2W0G9rXYCeP{4QWc`4?i1A?Z1+VRtK;=)KKNn$p8Rlt{j z`e=UHap>T)c9epG*Gb-raS{w`W*esG_Mz$wIDFQq@={Ns!}p@Uj?jm@nLBd{bH&r8 z_4H~m{gd078|c__xwOU3vGYm)>Um)iGVfL=T-SLZx)H#S#*3Eu$ny9&B{D=goLe%m z6P23LB*e>(Cp35Ayg%h{zF|%|E~9VJIrnSwc)LsZ>(efQG$DaIwFl=NWO!D*(yh(G zZ;Fjb*!$V`X)(sl^dxeH+xPV8=Pldi=4Q-%W=Lj<@S-2!8S`@c*y3roD4E%iu@V~3 z#=?~g%J2BgNw71Nh2W{Qlxn+Dd|=Uvsx<5qV(AK-^jGdAKKB#3pzFyZQ>f`*Fb0cn zjvAoQ6<(1IA!Gpns|$EiwaYrH4TD{$R*rtozv@w-dR?Hr^*H$WJ`3~RHNS%Q!u^6p z0bYC!#k(Y?*bnsp^GIkUudvEsRX+v=^(wuGrrGa;(s@Pxf7(YaCWxmV`X)7b7OJiV6k&FXJzB%xVwSe10H>ERgxKEkatZv|;2*F4Z^-{> zs`-CSxjEkdXUqS1^LI-D);}cp4~hO#*Pl;c^d*EO!1{093n6iCOR7Rai9kt-iK@82 zI&4QaQ0cpUdKQ89?;RwDeoY52$6(QnL=i@Z8-r9wXT(%QCKnFJpcZ6BXxj;`#-R8Z z@B|waHr(e(-w&NY5kiKmBpQIJQt<)qt??J?#^?KtWvQ`@w07!LdoOrb^PP0Jm6Y4G z+IfzXu@snh(NKv0e_UymuqA1gFv4=1G$&KA8KbfPBiIj3>8xF*qifAsTlu*jVH15e&1Hmpg!mwnuK%O z(|maqj8xD6it$2?{>neh(MlzL`Smw7E^sXv1AWw2VoGfu2yGqnKk9qA{jo=jE(Z~R zZ>x%wQaj3v9{D8R^X+j>Y%yb*YwCBsv-n%^Q|B165^!}B`!)X>OC0j?xYNvNL27Kf z1i5_CNP(67^1oM(SXSFu*!eW8!ZIC-a8nA0&$)iaQ$jvKb03yg7D0wih>7+eihLa< z@`(q3*r=AtW#lzTd3LTSx`~1adScf?^Zu<=yQK4xF@v>WD@uXXKgN^H%0Y|=<750u zwaNTK6hf4Cl`OW~?;eDOgg?e=9=ZX9SSi>30!uz)zhU}zLq#yR+ z8PU`V3_d0Vmtu{HA{Ca~A1Vg_gM+mtDs<*xQ6AS1d$51dOVFq^Kkk0Yv982T__dc& zBr)mxZn-8tAs>k4`HoOtcjx!o3p_A+U4UD}6s%(r`Mv*Ge8T zT#*NU3VTCg&rs`Lk!-+JqWb0VAg+p1X;n8=i z2d3g0!<527Fc&n}d%JAXwbj>894g{UWHs^|uUQC7;erG^=@!RtI@ab8wuR^wb&|m9 z;J>LccQ8LCK1%Pj1G9(UEQqQyTcKRxY$`k5V@VkeR3?$qa{*&~ZZ{kKj$5Wty)m}6 zwM9~I1-`RPU{H-6{uG(;8>3qzqES>)ao(M)HYPPQH?KTiZoMw0l~21-`sO9Aw=Yo5 z&vg_63(L6u>UjD7+2wHVOv)j4>ou}VY_e2+=v$?% zx?0%_g2Ow#(AJUol)3T@dPem!MkaalDt<0m;SWP~OS^MZTB|Ix)qU-kGuoE8y3P}J z0wieX7Z-a(O44us>0PMM1HZ5^{p771%Xg74cd}NREoXGDu+8)$WW2g<7A)TuU)>d_ zsGTkTS$90Dq|}A-rJcFav5-k)MQg(GuLI zlu`tFZ0A73X%(*#Lj5s|lmXlFnpJJ|9MuiRlUEv3Y#T&UNao`)InO=;-IoVSr%!6w zW+ydwdYsK~jVb_9CAzIS(mn8rOiPX3SO`ka7H~*UjW|KVho=jzRh&iydch1*?Mn4# zarSbWp1}gaRd>6K?k9`aRUF))*nFzIjqfe9SrYApG1vn>=9JLVrhm96o=8}v3jw+! z90Z>-f{%5GTU~Lu0Zmq(M`~yO12r4?wQzqrF@KJLFJtBTw4R0E#_C6xwE1xd$#eMn z*^Csd(-l3qi4*1nroOe8$y##a9ia~wXur&MsfFF|8Us0&KE>vx>s`q5-#;RK1k>!EQxPsS`A)+rHIjjP`n)brr$jggQ$SHFEdOeso#euat2 zA_6AxOie5k<=Ybl97o*)6Ltj$k9;SYn1m2!1*70@eb}zPneo)EdkCCGVc|WGXuKC_dDVFj zGLP*b9BtE2S0XX)BLbxbWEw*JH$#{&IT8hQ**fSeTG~P{r*t*pjm=dP@5(;@xhmTG zVp&Y)Nrj=`WVVfnm-oNQF_2xrUj%i_m1e*jgHjnENlMzBBgtYv>$i(K_t4kyGc5gD z9$q#XYjGuxL&dR9xny9P*3N}S(B=J1HWrgtd7Z2EnNkV6L#S7^Pt&mr4wp=R7&TOW zq|)!LBXwxKqgWcHRCQ*KmTtAWhGSdFOoW8d2WYE@Q~DPo!+m3N_1N8E3>TnHWi_FT zRj42*#0yDbG|;Mu{&CUQrZN9wt*;Xz9s48rJM|wk{v`(U_P)K6araS|kaai1`_7Z- z>D}Rqs^@t@1}~5tmKS)l=6Z3p9<(agZ;B=ybUfPDg5o=gp=52L6QeEw| zlRI+%e1WOE)eE*C?nBUXadKpC~6&-Z&vexC5rSp&#Lh+UhFhXQ@3x40Zh4-u$6@L9=_F(7 z^1bu6Zt^4pJ<~u;>MMT6M#tg5oh2Ep|3-7eM+Nf|tsR`w68b6UthIton%Y@3RlqDt z3a}x7N+V#w!Q6iM&?AnkdWLgPv3jB$bN`B|(8K1n&;V7(qg|f1VawRQ4HuKI+ygdhA3yZQsSw^={PnF&DQhok*bU8;gNv z+das*LSa+2_y2VQGfq3h%=3|8b?<$bz@Mw6NH1&{x^k}M!$fM;?S*gCC9R7L(;(Gt z`!+(Ea37nh>cE2%i_)2lYPr=O_N@^aPC0;xf#uDmTX4~VIh{%YdS1Jv0#>x3) zmEEYb?20{g2El53uTtJ7!zNu`NrpR4Df@Q=&c7VdMe3I^t5I(qDGRMm-4A_$7T1&l zPCWjVwCiO#Gu9|AzVE1*M=zg4Z6|*Ig2vXU-g*+?K&B~)AT_aLJ7dc^!*;3rKK@O& zTUsARcH@dSZOf-eJ7#)Uskg))vn}QQTD&>n%RXj~ z{nN2SdySfl2EL0?mvZlsqkMw6ab>%PquNJZ+Dxh7FD(OZ+5+4k{X-Sc1{8ojIgBSi zrmkH+%m`=p56FEpv@lyfvohuFpU*p%BmFwr>fIx_A2u4B^6yO(r>NI%^7-{z zSJ#H~KDvK|x+LYs=bl%u-SUYZw*?i)VQ~;uD!DzQNUi`{KSpcx0m*WsVB~^j7fF8-R@MFq#W?W z?xY1SiJGLm*Vxhp?5PYv4Kq>#^ZAOCY^7l&P-a#Rl=}G*uMmT^)^R(Vv6ht&v=dNh zBk}*9p;>QWosVtx0N_hxanQ06*e!A1^!to~a~tnTYwAcm0wV{XVc&#vbRalOK?=bD z?W#>GRpU~2ff<#mb}JiDJ%OTG%4K)h8gj17lpGH4VzKLxkU-VK8d~pR9m3htLT(Li zxok65cIr=*es5bYjUgO*DD&A}lFJUoP=VVd(r)^v`mA-soXqD>zVH|I+4r%B4}2gk z@xv)2u|Iveq8W71AirMVf!_+Q^@>KILdWsftH@qM^0=e&XD$DJ;uZ?S3(vIJ&h?<% z=N{qb)AuuV`=R%w$6vn-`+oBn7m5n@B?>JT?j)Lxy5n8(xk7O!bro*Wn|{p}bUQfj z26cb1rRi7e_Uy%wF%Ii{c7WjUX<2!$%77r_si*PgQQt4rO!eZl$KUO2j2_45Z3(_JB zk7%2d$iVd@DURqfT@0GXE6+W35}{`cUf;5~Z^5Jop~jiz0}-)64omsyv&KX-@G+9NUc2xysSoA;Oy%*l?l$kkTcOyK z0eyYFaRt=>~OFP+KS(;CDSUH*!U?Ki0nJk|FyF{Lfx9yP;8dwJT;I{vaN9r zdnf&ef0T36dHC11urO4Ep`7qD>-ECRol$rEs0R&VWrWu2qrm~0(}!5Mv+#S;E`Zyh|N&2%*x%GZPNyYF8d_n3oIdOX#9%^jC+uIj~A?<7u-Kdngw%wyowmv`@C}V z9kBb(55-a7mR)|W7lXb+ovN|4HwPe%CYw6*5<{x>Nf~0=Jk*CflSZQ^+nb|-DomIF z1lFg%XboLKoThSlV1&x0XF;5F--|cS)=nM*#7Hb{Z*=*fo`O0ewYX5f+e{A-7CAyIec1T9qIFG&U(GQko*@jd+-)T@Z1(#4RSv z9)=T+DFh!Tyrp%dHoFvCDJ#X`+^)|DUxsoiE~8(ulzQ-X@Ho6~Aup|mgt#Eh1G28_ z9rl|LN(hJbqAO}c{$w^Q`AdZWI<1rv#e&O8fXCEx0E~~;`T)v>;`AL!ofTdb%4fi1 zjXpM|gRV+x4kKP0yw!9Ca}BG*(gM#kcj)-+Tgn!sK5OkG+#SefU@yx4Aj2nRUK-TP zNLx+8tZg>-nClt1l0NXKi5RRwET8%v(vs}k1nxCGk8Ka&=Ab`Qo8Tj9@|8ES0B=D) zXTj(Njp2oWS2@?6DLo_dx#Dya{+1ceDi5Z;l(7SpCL_njgzMn)+{M0(`$i0R*)TDn z1*`Gbao`R5W~bu7hWYGDLtZIeXOzQMus0RB+Nblj`0d6)l$znWjNPr&;(M%blWvu9 zy{T6f(dfg&QyX+%e)B*%?{*xD6((Tj2Mu`!iB$oKnkxINi@A;VxPe(c!YxM1&FJEI z<2~C2I~xWh&#^6|)dm>J<0V-&SSdedEH;ak7EaW*7Bu0jw%(|OM!1f+zaT{sG1y3ft(xRoo2n)IZg#I*{^r+>^~{u&b0voLI0gq*JuQ2EY1F;yvf@=8;orO1 z?AL>NdMYpFLyC{Fz$OyAb>ULA^*R2Ulf5PohW0OJdC6u@kA$I`vPzK-PW#K2e(=i?v#$*i? zq!%kb#S^+2Zw;|@f~l|~ikjQ!jB%FY|Mj?CICqYw$);qVQm;QC*E#%ynci$_>Vvxg zT#=e?y69vq4_sM8Sw_gnjO&Lf#+a*n^LJuItOFhMLF$EV5gwtDY&oVOXGt~I_^iI+ z<*Q3Aku*+INliKGAfx8v(HhGx8J^?^r#DSGPS6|RUn z6t9I@JLEbW+x=|_XZrooGZhA8TfM}N#JlNb3&iXj8c{9$soYBSY!jF9Y;JYiRi|EG zb6`?j^qwVvk(Z_BEA1(-GE7o~-B&+fZ>Yi+&P(2(NY&4^ME6lnm)Lz3Jc>_Y_d1ldUTLfA zkh<^N$zfO2alZufOm1Lq5%ceGX4gm3>uZ5jBwS$T+0MV-ac@{8lty0%%wb7{m`c+h z$Q*^r{_$3>UF6KAzG6W2mi|WRzVH%Ej+tA{%B;z(ObkXb33goV%RkwO78neGK#lvK zj`>61wrUaT9`Ao;PDz;qH=!+XCPa#DzodJAJ{RddW7e@O1exP>1O%)?*0h_qw=$*u4g9DEK`<-lF<@mVE<+y`iM-dG+o zSVgK`T5Gi=X5<5aDQXE|6198rf`$@uNRO(!<+s0Q z%G69})#lpuhQ>3Fc7AysBMndVwu{4GB_E_ntO-9*bT!S3V)1IMj!#n-{!nmiE)I`FVMHQc}b1(98`(NkBOS zdiMz~OpkZlc-kRO1v8(D=@u>-)Y>`;S0Ua}l?@f$OU$2kr#gb%a`if$=+QZbVKNm= zK5_{lxTB`6LcWZAa8cX8!gP>qo^S|PHT$~2-Ic*rBT~Jmo^>959;PF@K@`Ga$A>Eo zV4bZSO0CoGXex6bs<9l!pN-2OZhU%kpTzPppj}^6q4Xtk<=nO99Pk_I;~r%d&)&rj zt*~3Jo|2a8@TA<*b>_Z0@j|>*@U;;v7w0wsXElPicAi2gn=o%jj}uGx#cNhe>;xO~ zmF~(#ZD8IM3&U3WUN8tCc)>Cd4gWE#g?vD}1yTC1pj#S)E`CwVq!poE zPE_wwxl)|JEtt<|fpQ{NRWxUMf;RlEn)O%m&6AJyq0eXvwwgAYR!bh}B<=N)CtSg> zbp+1DD_XxOGH&dlp3V(uRg#1^S0cHMf10gjzAHL~YZKUh_HMTb_Iim*zN<`W^C6Y{ zh);6^o;q-Gq_*AXceU@=XHR%^?o$yQHZBX#&Zn8Fsmt%z+yWM)^h>0*qolQKPdAkD z`)pCXsw&GQqZ6nc`O!?q&oNuM;BzJ*9j}rvpY{5UpU>3fI*w6)DHJnqO8h*7B-Ln7 za>iLr8@?0A1$Y0N)el6=#-=t_ymNO>9CbjB3G}t(-bnHA8%PY&a;AjWnZ@JxCal#` z*gea4QC8+aeMM*KK`@q&aH`U8yt1=^^5aHZ*(K||Q*0JgLr_8BOxggdPHWPQGBy6S zN2$hgc*?F_N#GOUA($n|UboZRHBf3}DNOw{~OM&lPvzq<~ndldSnTv#;;kZbsurwE=T za2C5I#xhGAYGm(x_g^_idr!oz?IAt#nqF3Uz-Y*OY-!zjENnJ#iDoz|Wx3t# zIKKllNp-Llr-P{6nE}t&2I>x6O~lVFBiZ|d!&5#2MvYdSDo*&u9{qNl@sKXWYJIXd zo2*5e-vf9A&S5`m;^B9I1MPOnHdTCUNFzY+KB{rsCgf+5M=oN2ZJ->B7Fagr5(lbo z73P+|rTH6q&k7WgmX_up+IuXiDK6MPRFnw5pr#Q1FJ%cf@#-ILznbbFLRTag6V1Al zZ~jx4jT)w|9$9TMsdJ9eCZ?vgC~WXJe}@78onH(ji~jz7K~LoauVh3(_c4zW2;f2K z7JkHTzQA0`j#A)b$MW_1e96c-4F}^rq>!MfBZg2SxY*=;%(1miMe8KS__qKz9rvsI zH2!3^^pMo%*8P;w=9m;m%Erad#4o8AT8);GOVBgy7#+u}^k70-DJt>9G4yit zaciw3f|Nx53x?8D#R*hQVwI{jwF>surLFYp1(#vj6{0EzeV@yO{kI5wvSCW^ME_n) z|1**B3Q?svN7<&+Ak)c<6dIy#V;a$u>ns(D)r;4_|4BuETRvs^C1KSH=-sp6mmDEm z<}(_WwQ-i!Gme{KH(%LJo!cc4oNaP4_Yfe3`A4Sdi93QrkH$Ln(q2uY^S7Alc>%p|cr*r%_^#?^CcHiLJxfu3&)O{_ zww*b7!P3s@dV@h4c}b`Dfz2_sRuh)cjQrAsu=tGUP**uztNpqBwHp35bzdSBw) zamGC3AIZ{}#4(v8^jLG#@>d^#-B$mZ;rW=x0UmK4MYD=>ORQ-`!*kc*z!-c% za~o&X@w{|C8d4x|f>~Kd2^Ew3wfIhi+(6{g)(d(Q`fJ-P_;=}4GXKHXJdn+T1|K0i z1#6EyAX<6li)0JzUGXX2DjQ*r(SeJ+v^=8-Ud6gz%^a1ct}nH1|H6p=J3&6I@Pl`i zE9ws1+yuWlce*1DiCiLCB&M?($Y?xJb?4JUg@x&vU$@^X!IB&Yj8~XX`WxMg)-Hxf z-?_`9IywS#$rxrBRtBHYxHsZH4&+Y$JbNTH+N2H6F$x#|?+Jw{=IY}^bbn1$UD0R1T7(u?-`59M5(8)G>8LH5 zyuj~ zGO)atk^n%zljOjzvn@i9H>?`#c%aMM?h<6DALTZ)3cO+0GOl+@`jUag%A~P*@|w2> zu{KFk6rh)1(RAl}p%LK&F`)i&_3W+kA;9MA-*aJ%9NM(Kqv9LQ5UvK%;cP*5s9dxL zM?sqRL+9er705CfEVZUXZjfo6S_d4>8zoxWIx>}q7w6V#R%YG5omwZW{`l_aAv#j0sciudQeUj=Gx|-iPxmnct{xYW}?=LsN_)`KNrxk;l$&x9Ul+%k? zNRxZf{Dg(+x%b}sCSyA;y4t41ci)CE{O%L{B?|*=3Q?A*R>~Zf@HH31;U~gJ+`{0v9M!r zp|6@7ILeLdK(Z?l%X$TtUR6o>&B_CVj7&nrsIeje4lqW}aw$6~R9-g2N7X=Pt4&6p zV$da^&op!a4r_nyD&oyAD~za*2L+o?o!}p3+ojc>w?xyvu1xHSCm4OuM2qz}G7U35 zQ>E(0V_0(U4Bh$mAIx}HJgiZ*SZ|S6;)g!_)8cA3b^tveGa9za^=<^ebuOcWRy`0d zGAtrH-{_mli71e)1|RCII-*wlm<*_G?PHg%QK14Jxf|3@fT{ShnuT77DVaP}jY(%;yF0@*%8YUrtv)~Gv;CYdrbQ&k3jExdEIi=}+y z{-LcSo39@%E6-JT`6opT2g_byQD=d4bZp3St;o_3#1ow@cH zx=W~q2*y0{(R36a6Q4A9l-)jRFlR<>*8;jpg9XFJ74I(AANhY0g{y(2OB>DBLBgm# zgc};ad}(HkB$mdjw#rp^GY_wW#Sn)73UOahTVj93+1dL>vyDyhYoi43=ZcKV+3#3q znnNe=^z`~>3q)+{H{E^CC7LWJv}Z2e4|uUo&F?R7fXHm-L)tgi&n8U^FBS-?Kk;zW za{Q5vnC#Kub8M?n3O8z9H9&L3eAdB#Fb|TK;j==8)jv53;IcF?D-p-B`dMP`EXOy= zqe8fz1WE%5x>s%M%e-3~;fplCzum{>!sRXuIF2?M(hhleA{SH?W;ZW-@7tcx<~cMzSNBtA-8?bV@& zRL0Q_X-Sr)hTz?Y^%-e%=lFUP?dz`~vzr{wJ))q?>pyt)FY$_y;UYEx)*gSPC7q_E z39Q;a;Xe5+EB>-jMp!YW@*l4qU)2tO<<}0A1cK1A?G-j1gbMMv4ntnYkB?W~1G+vr zX3R9VF^bc0`}=BL`L(I7#GPFRZ)9oLV>G+urw>@r#oom{MU4V2K84h!i#Ch{-{2RkEz8ipZ5*C|aWK!9W{ z-y}2qzoTPnMQ>&uf`L!V;v4=XxJCgl=HmXWtRyMY;o_jHrA~c&-oEm*?)7s$hi~Tc z#@5lc+7$%24Hf_DBIrxVq7ch|OMz;#_}r??cn4kSgM!#kg}&##w9Clr#fL2g=IqK# zuTCUPnP67e(L)GzEhr;KQX99N-EHX;=T_8V5h-w#MbQ+DX@}Fl_b5lMdX7`55-vpF zxQ8m~BXH?eDJ5U|N;yMnl0Kq({r2`*jjrrmn5U+jD;dG;p2GxViAV8cdSHB%tMtW{nZh*ME@1 zhUnOUbK)dW$nQ2(H|}{qk>PT(?1$)I&WH8c*>#opwE<&#DnF%f)C!z>6p$vx z&4gi)Mk}`%fe2O7G&shR!UJxE%FwYG6JiOoeLrLF&sIjo3vsX=R09>|GOhb2!y}a? z3{m2}`HY#Gm{pKvR!-bBx7CoXBE0eQflqxu%>8B@$IzL zk_ag1r7j6_$464!4+&httctd8+C1~U|E_uSzeo@{Jve~2NfCSl^YlQP7FHQ$7I}F; ztz-U8f=RrR6zJ7CaWuQB#c#COc7=k*S3iaT?Z30^+U)qV4c^?wL>xfRyYe-GSLLxr ztFp|6`Q!G>e(I7&vfp{KR~-E2$DrJbW`##9aA@&zd9nalt-ixk@kw2CwHn8AoM`|9 zB(>3%;lgV0^K_jjULPyTwFy-w zf^z~Mq&wb9^jdH5#s;CxZ?HNf*VOpxz0Ld}3scvMdh^)rGE>f-@mN}Z|BjnPAOf6o zUfLR*B>~|oN?|M&8BwVq(w;c<-4lR_F`ee8iP^W-l4)Zjt|Xcr*4-FXlsxe;j1(ITi#Jo6LH z*P>26*WlEL5#tUIq>0hM6X+~xr6uZ9oNY8XlDLVDJ`z@4iTKY}(*k=B(@vNWOl1RP z9EkM>*qaqJgwp3aw^x%XK>`)>YL#YqqGOjPyt8h^3S!#Lh0UAWoYjUy_ophj61l4o zO4Ou=4%B&m;O0g{OJ)?)s_umy5gna_TXE$#v}`gK{>*X&&af%(Di+aN8C2;VsMIELkBw-fI_!IeJlsGsU>?ynl|?Bn-V1xGh?Oy=b4UHF|!S zOX;g`(!5$2>aX%$xxg8MdFNymn?G3wQlu)3?7QSA>EDOI8$G1ao-P^&tO=^do$aP| z<_6s`yMlsL&VrS#7KA_ERbM3Dj$LN-82B8D39PNBG|g#=Y&_pKEnmC+xWA2$y89B$ zc1f|^IhAQg!S6hCp|>QTreUv7%f)Ybeq4vT}NlGv)FdFdFP&An3cq5 z>lWH?e;(}RW|tXU{jf7RyII5aRuE=>r~c&D`-9`*I);6!9ie8-c;Jw=+7ttKwQhkW z$`yNM@BJ~2TipCXJY#u(4+@|~K4l0Y{OARz^V%E6q2#uFLH_wK?&8XsTqSZTC4fvx zJSFSyK${WLIPDWE+Eoe7+ zHJ38ec0rwElp=)?UN8GnF$K?^qCDWL?ORMC?C)T8g9wU2G#l45`-^f>rq$dTGy$Ge z1+!t&^@cc+e|Y{trYyScFjGJ)s`?eDe`u#N|Eu%TCoSnw`j8ko!*n1;A?gK{qU?`t zfzqiw`YTjIAW2-@CuVIupVPzh@bFStxxrfqWEZ)JDRcA`8%E3iajD5-U=R|XiHQ3S z`|pzhB2du&m6h9f?>CUA?GFM=A*+^p_jeZt$8D4bJ9A^aO<$`()8vNdG`3NZzGMSI zGbkzrE|e&S^UC>(uZ#j=@DX6jMzm~te=X!zI zF4#>8T89p|`z+HRws&@NtiUBT`4Vk!adFv2q0RCAySqQk!_cns71keYyTqPeI3%V+ z9kTo_e7rwYCFw9!q^jf^5xHXjc;}+`;^6z4tm@^7^$~4p^M%xv*v}JPP?N5QmW{6U zOS?^dfbD)Dy;Fa|5~q;IIhB#I3&*E0R&AS!fXXiwCG<}yfK#^N^0gLixq z*}>mn?T-|NFSBUoPi#hLQdv2#(+QS*93|`9lD7mZYr`oiuk`|``E!&Bz zfdN!1h08C+=W%ZRWV8*%@ zUJBYaMABVfVA3m3Ei*k=kK#H9AokmN_2>A{xnE$%kf2|Z)@h5|drj4bjoKt$Wq+2A z{4u8e4n~#Vc2 zZ}H;@koIvMu4@McG1aar4*!I6M@-O_a?uiyN8mwD~K$NwM z6+fLdiK+N_8eb(g*7g^0sI>yvDQDR)9EabJ|7(}^pCB-mq7by%ifv{lzi9znt2|lC z1l#sRh@2lqgQ^;WR1?Z4ud4nG{HmeFdt(!th9tJ%!?Lc>W)&~6EOkOk((tnL;ayBY zuI+f`W0-674JQtjF~Y72GQyW)JLmN3DVmG_8vb8A#bDTv)u%h18O+G)76Pl+Eg&QObb$OSnx_7!l1pc z65;zJ+aR0T)=y(=H$IqFtsDG1aQy`qeL<=hXzUvE*eM$eRR;#sEgRd0-_ISmQ|G@N z5un!vk%zuiAQ^HQa4pFPmzooNev~{&Zi)EK34}io+bpJwGkeI%`hG$=1gMp8L^iRL zD=1PZIJ&40By3RulAHVyxynTD{I|MnEHyO`f@(mH|8k4}@ez4e5#wFP zh>P^dJYFiS_YrC~X)EavLiH&P&4$@U%!$qaA06KuAJ@9J-Jp$a+l}osPNT-QZF8D7 zw$s?Qoi?^Pv2F94?z8tfd!O@uf6c5}zcp*E=elk@w**ECipBq^=wbzE9}fzIKeLbw z^lu#VbE!5A`O@zat_DCf>xy`Bl>cmiXjUZTf4c4ad<@Jtk^bGT=84>GsFsWlogbk}`Y4 z;Qi&1L(AI*1bu&KhF9eCc`6asm~JKuag8;Ri=dws0$}gF4^!Y=1a69S0p9)Kn}cOo7OC#Qt7a( z_Z5gX^h@rK67uy`#*QwmyM~7ASzqsnEEN$<->cIv@H*A=g?n~_#yeTClXVz% z*(?~o?KT2TBxqiRE0oH^s2x8iu1OZO)=RbM5p~+2ia+)ZY4lGfIchqU>ek-lJJUtT zU`AYV)L<6>r8pAgx<=Y%t+v93?&T8q|4PZL!(>>PvxM&nQOv$*o(RxFPRce|z&_AM$<|y`cugf$1 z?8GM5M7>|`mE`$EJbIkvp=b;tk{8HH6tB+ zt)_Ce{0pMJ;4AFwf5DG+BAuS+_gIOs!i!#;rE$FZ4)>ai`*r4Ij?o#M z@b5rGIMl`tNG>&cykB;g(4{Mjj)cvuaT$B3J#{D@PR=82ZB(+&&9G4i+*V^Tt5HU& z287#O2OdwaIfK1Mna!qA-#@EKHv9A~kL~%t+-m$;g)0PJ7$a20?N(J&m1 z!Y%ok9Unl99{gnog-uN5w}^Ay!E6%^h(>KFG5H*PFt*VPdgRUM8A{{YCyj&; zLto8s1b4jDfZi&8*Q=d^?RDE0@Svq>xO3aSkXny=A&=PW{q(IFy#XS5#sr$lkfx?% z;d{P_6LT9djD_TGy`6J6cQ83&q1BC1RX(bJB1Srt>a9=4cZ_qOIFps=sEVVk2s5Z(`Udj2H#mNWN`ldg&bxT{Sol=oeK-1O&z$%KpY<06?QRM~4oS}UU7F-Aq>sqh-_9-LtD)xqbHrz{Q@PV4UDI&|_i zQ@lH;MpC&*ug2^vX1Db7#d@5^Q@jXXv(j3cuIfu!L-7`ZHWj#>rAB?&iP9&utn2Bpu&^!%32OKO!CwzCYxQSu5 zqA1ZSO)fKdSaq!Sp0U^8wdAhQ)1O?otJZgEh=0#3w|eDz@yfB#V1+d|N)SX9G*&lO zD)hqOB0vSnGk4qZZ^yz69q`5J>dQ`{50hCyfG7#gfW3ZTuG3O>EyN${mj}lCW>pXX zsAbBsQ6itQ1pGWu@<-UTN8an*-MPwxUx;tU9#-`W{V+B8aOM-zgz3Y)bAeZV)(KZ_ zKZxs{3o+oPA-92-O!dS+B8+?5Sx%2?xHZ9XB4%uopPTV4u;#RkzN~0Pgvp>CT%YL! zHZxajy1xEEn0ycXWUfF57NHr|O)2}>xD~A&y+e}h-|E#M&QB8-A=}qPgOokj@fLcr zv%o-GPd^M(l%$SVTz{CWn$`mN{FTZJZP!8&%3Kg_!m|q+zTeQ>SKZpnv8R{?bwz7N zSi5~r5^pv?FGq`(5=9W@VP8 zKy7xqkfSeRKcwKs5=`&C{;dedE+b}V|I5n+8wnUa4?>?acTZt_rCzXDw`A2ei_JEEq>TaJQEiVpfqNJ@(*!yLg60$`mqPQ5}GJYXC{`PUg zjpqalvmP>-v1dNki}LID1UxfCb}2FSdWn6Ue^e+;v6bbz zuplwd##>>rSuBZ0%0sZ(up);g3Iv)mg9^{nUaCS1e3ob1ps)~j?k!h1Ag~M$;;m4K z&egfSwlgc|4VXL!4-@Zd*ZOl1+L@X}$o$?9hOB|Djy;8LqGolZ3i({Dt}5bP^x=>p zqv~j5TGCH6AKDbVI@E%ts8m{{_s~oyz+$(a)HKz@mMHN(;bq2_fj(Pv(R)kombO{OA@K3E;y@Y2bE-?eQ%oI zM?C4i@}90z24U;z#Hlrefe`t`t!Vzq4vmG0uGS|<0+FGcv34YOA0-DmtN+Y zy-xLJP9%140=n|lOe#1fj`d`&>d)_+PfWJC^d+N6?tPaf^Wu5J9R+mg8buKF$hV@G zS~!Ef3uSfvumO*T&!oLJi=BcmkEr+B^c6?akjAQHFelsC{4bBVN0^mHi*(FJ`CLr+ za+CuR23LJi{k!TKV)3s`1p|PUDpDX%5;y_XbdX|4B5@|Opj{$1^un29w2W0asMdfy zIx0#RKjQk6U$^55)bJnV?%GWbGfmHKl1l9WeQ$y3Q6zM73YUK8-Yr)MqL>Nt&{x45kl zG*~W6A4q<{t+2s&=Dk@t*3D zb4VbdzQlcPTQ!!3u5jyCm%nEtiv&X{aZD`tn`bf`vn<1{rsfnwJ9&vuX~G=m6NQcg zPc@eKtS*3qeww}=fD^{V#Etl#SB$KFJCr;7Mo0!9RFu5#XnTZaYAtf0%CR`P z$-KhFDr{MdT*>1tOQNXZ4iSU<6v9M4N`A62cb-yly2`x5-EdnKbKWSw09A8yzFUd8 zPMXfx*wmmZ_}ga(b58SQYu{F|&W@cD!xa7)@6=!okgs|ND&`F(7t%Y= z&-58i#PQE%y!*hVrht58*Ui&sJF>}S|48aR;ecFr3KQjEvB^xcGg}mNt2QrGscXZu zbohmFF*2{xrQ(Bt9Kde@`Wh!}^j0tvrE1OfmrPt&vwT*|jf5FoZrd;`tG0WE=s6AE|_Mf^>i%8g>LR?ki})+uHuWlm%GM+hF1 z_Tae|7Wv!tso8Jcfrvt(uh~h_m44A51cJSuTyJ29?oZQQ@nNq|bj3@{Tr*Ip$MJQJ zFw^C9H=I{x`)OD`ewSS~52iMiR4!+LW>N&SJ7*Usf-3neI||xjBk{Q}OM1XW*|BQ93O8rsQK3Q@+;zE{Fm#X8LohCzhWL;6HnK^!b{e@5bfTH>XqJIGjP5rF z5F*t%w+O-G-l$hKiq+TM7V76p4?Ck%35~jr3U7u#wq9+O29hB^qft{+3mNA4&?;$C z#gltxMtz~Ley&4~<`?CAzZq|TJe=(_nADC6yDeW@E3-pdw-Sq5vNt7Op&kpg@}9R} zg68Jz)41P^fMQ=MdN1h^UjkHFz#}nmGA6m(1baRwf?51i^a#EAB4mI}bTI zJ~9vqU9TUhXC%Q-bS)mP%J{h)n}7VMNTHpkw04415KYhz_kJ&IRif-^{)7TgSn#Wt zY-e38hGVs8ACKo6q_tMIm+RuMN%k5?N9v_f?H~!Q4m!lQi{9_;lpO%yRA0bkSeV%6 z_1LfSkWBr<%nuvfjPUSSg~I`x&XXJ4M5}=`e*1cg940ic#9o0O#y7z$w_PDA$%&Mu zayVmn;2YkrNAs0_h3_UQx~R4()X=Hx+CeeATTr;2fJD5&;z}_^3TTA#G$^}DubT3q z{0!c<#*n~;I!)>)m*UVg)s{I;R7A~u#BA%lELRA=hRRnZkAW3tq?PR`%c*ZE>g@*X zrm~X4eG|6Hl+qD9TkbU^{pUZq$Zkls=E13_XN@@ z(!6}#CtPgBwB}hXqc7)$_5{EBW0TWt&X-TB;XP7B(n0U~OX_kc7P;jU0Z2Y_s>{nK zek5l(m0K>nna($%UV7T$kjU@rbUq87-`63L$m4LowLR@)cW>ZR?)-T1g&aN5l2nj3YjjLObM$0W7iD2@+>&m!m9$7p#^gP`^VUjNcFGwKA7W z0+muf=Gv{;*?g|)6`M-_vl6g!kXGL4DO;c%pWiqU@)=sxYLx(i$X~C2D2{s?pL_>r z*rKu&WL#`?!faAG45lAdlDS`9je|uz%kM-s%|2j~}`B$$_e_H&xFY;E`)9^s;m_xlxcxzc+Yl*F&?u7^0SeM$}i=^b|#&}^j$0-djfYC+sAZXxY3i&VoNMO zJ)Q`OFC2VHlDAjwLMfd_np9X6d*yxZ3VUhP`3Q1`^kAa zTD<-8=le1Lt5yH6d3;~rj<=`>> zy0?j=$o(f>)y!(@yRGC)gc@0>R`XsV^y3Zrzc~L&rm{lsA4aj}QXRhsO(Nr#>msv_ z2CJdFZu-Pp<+NPS#iOShfBhrmDE7#(1E-a**W@A(D%38Ud2{tgv>555ma$_kT=+uh zj$=EQxrd9&_4gkkqy9eJq}+izo7A6F#V=m9#i`8t=dq`YGs+Wbm@k-*qhC^6;7^TP zWd*=&TJP9kDIBzo>Jn8*olFuW4~QF~Lv#1NG!iPZ-7T|LZeB4nP{PF=zVR${c?s$D_Rz5 zvzh==2}f0KDZb6(bYefq>GGAhXCzS|pm;z%=6%$$*yal_Wz?Rhnk}php7m3}fnNVJ zbJSIEZ8RO-e8>H0(2a>X94&S_Hf(lsW8GC zDut+Ov%`*|610fD%%noXhwzSdSXn^TTLj={Wlo|&{aV&JPSG~1;lNqSSmQVj{_WL4 zhvXJ}G(;l)a2x52S`H;#&Z=}Dj10g0Zy%b($%j?TdI3iHXG+&FW%%q8wx@gq>R#?U+F2HwdE5PCe;f}MJcpU5v8 z%4DCi5vi zW1`XCN&X||0u#DCIiIx}Ogt@}O@#aXTxYFnvs}CLa2=H#KYjW4TpGA8 z3H|(I@w5I1Ee5fi;Xg7$6ly-o`_!*WBy-cvce|kVsxdU4I1k3Bx2nY-FQ3d9XF!gL zf{*?fyj1>o!5-i2i&;OeUB-*+ z^xyBk6JfGzYrLc`E`0)UiCE{J-tVMiwnxD(fTU*g~^c*3WO#2Al+iBcO(jgvA|D7m!Xbs6Jt&t!^ZbJC|31BoK$${TYAP-E1a z>nSgf+&wH!DyWWIn)@R+x1}^96>~WbXJI?WdU=T(-F(`b%ap4#uvI-bvm0S{q&14D zDw{P5jzMz*$M)84ll4{_#3>tmLG2)I9?q2^=`1T=J@F|Lk3SaTEsniI2INgIZL5da ziV)1~<1mimU-Qth(%E5LveNiTM*5XA_#q7C|B*{wA0gJ~7jIWqGc@@=AP`Qp3bzG? z*x%H$HUt~nJ7+@&p)?|npHG{BS;YED*97jd=={7;7pDG@gyd^Q^PLot9bwaG6QqwV zB?OFULf0ZYryGvvx_o%pr3Nw25z>H0SF#TI-?EUPijGjBunxbjz>(DRRf$ZJ{%QE> zz11MR?U>G;+fQjK=nERCMabZLGx*QiPSFcdO@u{Ghx&_9{cQixuF*nGkcN|WE^5n^ zj3C+r98tIm_ZD0Hp#IM$B+y9FdB}ZY?n)#w_ioe3fOKF zd=LH4wwynU@ca=`GyaH||NDZ!zU=V>oE~U65*+Ot?bdWl(sOch6j@+Fj;Bh=y&$>8 zZgy%`jZps@Z9p1c$8`5hrOpew;?Z8V$P|pWF6Y}aL@&yJ&;RVw5b{TirN+E=q$L08;1J~F00ZFo0f+_?H zbL}74gI*}>5_;m3qDR@{6t`Sf))y%AD_?awG4BlIi{Rw%Vsk?%qroK@gC%i49K`M~ zL|v?Tuo)3!iN+ih@d^KfN16v@5 zX`k4#t_{^XK5+bVDpRJ*PK${>zj5SPU@(!Yq%xdY~K4}y$ zk3gjDfz$azuFqt{Oi9$lBk$fD&NvB1?Hs+xIHp6FPCHY9jo)>q2k))Ga{XmsUm}P+ zq@-OK?&i+weAn*6wJqzy>M@s}nh5pXk9uvJ4P5{WI|HhU+t5!?<8H`U-5`*6yf zN36KXhjH%vja)qv<}}(F8Z0mu@AzdSBYXmi)H+X2`&r8H5jM5h`4=hdzdr`8zmP9O zjhkT_oJlo~K4)iH5L?Am+L=N=tc_Mmj6b(aE{9Y7&^a{EBkb$Sj3K_;r|%SC7X zZS}gwM4PmpoVA;-$_!6JG*4xKz-ImD1TgoT0J~7Fu_T}aB|MXf%K5M$W4D{C#kPyz z-Q^Q?hSB^%aL^g}Y08tXgO-dkK0xWxrce&`>8N11M1RR2yJuMby{-oa9e=%_%CfV@ z>?Y8mjK${>p_7^J^xY)OU-I4cAWNLhzI(P3*4~h`!X2Cbz~vc%xi^qADtWfVMqcXw z=rB6bip6BI%Cpdj_h8(sUA>5ipkoJwS;WTxp+pOKM?kI+lonL!2BxO#fYLVXba}p& z^wtZ96gIuhi5HVzj}rI9D5m+8!c}Cmch+~7>e|;s)VFmKRa<>?l5&3^^`da+Hrz9b zV!F~ZsQ%=D$-$5wUVP`=$6tAR8&UFMNgGJy?i4h>fqL_EDl5Xj9;Vd2@bc0m3dO;B z-)eTR3nt|4u@;+L6^bExUg^cqUeQ_AN7ej9#PHzpa3?J7@7={&jxfg>>^S^WW?ILZo1yn3mz$ zC$l18F%vK?LTs)XCxq!`rRlj|tDU<#9hCQ#6$w5)aS|8|F`fk1EBAe>_McTZgtAdk zoQ$a^4nb{RBZZ70i5BvI^SR?*GuX3tq=0Fx&nP=??>u^3Z66o#YB%!%Wj|{+i zgxrBRu9TEc!bOXVqWgG38^?{=E;wvlhD@%Hc<Xb&RIRy%9BEQAKL{kYsmD0bj*#i1!*GU%8nW-v9z^9 z6ReNi4eq$V?LTkv`(|b4K;wSv{xlrcN!k2Z5`7w%6Zxx=7b2Fv+k`U5y2(wSBSyN zbYK~k;%+x# zZFW{(+WONVuS8@%mtV3=yqH*;ECT*o>OWSzt2s~zJ_JR}XBo#GcA zu*Xm47#;K3Xf6EL^IsNyfVyNsQxNIGG!4_5(Dzto{LMrvR+Fkp6*r%kJ4ofhEtRY_ zkCxS2|G92|9I<`#7mH^5_9gDBb#vG2bfYb4P5(tOq6>MX$7LSeI-NH|$(R4J@lx`zUnDGE7wcMph9@L(ccfBOJ% zNOYZL&(3<}v20kJa!sjPygIubH-s9(tf~D_+G+N&0nR%eU)HHih@QPX-7)Sq$Q2hA z2|eA?uJUPg`tq|p2;68Y))N}>>U`H7PgF3+?_K5(K|45pUG+C8Vf21j=2M3=Z8_>Pf z97Nf|??OfbZ~UIu6OQ~|#hSN@f+)ko4#4vl$$rPE_|q8zE4+@gsk#JF9@m4{@>_}u z-F517K}Ah!y>9_h(qzcIkWOz$%<&z~k<7#qNec@LnvfD(R*s)kd4BmiLLPf`1G5Nf z!|^R(qYD)pcHPk}-L1F^=mk#!^trKGEMhxiCl;hqbyx-FpCy2w%%^;=qDoCC)FWEBZ)(q$p|Zp7f?FS zxv=FnF}P7ikP2wd%*D{fk+ymLW&aD?e<8hu4@M@rgztEC?k%>S9E|cllzXZhfo- z&?)r`I=0x5#)=gANr_61qB{-Lf2iTSxVa9Y{$(#S+Weu^bWi{FI6=MoRVq)yPfh;r|^yn zXKi+w>JO1xXRyas%9yL;(srJd?@2})6L;=Q<@JKy`Q1@2%l+E!t#6GMXtC=iP=^6w z3G%(!cCY-z;cMj(08R*irdPD=Z8HH^o(*&o;#f7*GUq1^iSgen*Cnts89k+F0knsyc6Z_uy+C7L4WQ80< zg8Y{%Xw8_@m%F=)iH~>Ie90-hi66fC2j5Eznkt|@2-oi-RQx;QLfityz>76_J^~{)<(SneJpBu9x zwJ+Jm1Rl^JoW-2^M#%4JJekq1Jc`9DKC4B!%;7CKRqb_Gc$s&q4m|fsDkvwPs+PX9 zt7mk$0ha*0#Y_o5kmCOrlmEbvs}m(yx;yp+SiMq6D)B`r6wB|1>$N8Ta{E4)H;Xl@ z1d(}!TpL%xcjfZE`{9jE_7CO|nkJVid;NYe%^}wMo8XBQ$SkJLmf$wrF5JaPnJ#Uz=TX&e_m07D%cBw!q7nSh5-q!gOCabT+H^XF^y%mKKFd z6hxI80uY4eN|1FO5+bO@GVVWkBkNRt2(A#cmglJdx=Ywq_OR8{Y8(rez9MS%v9Uow z{i^S{K{}Dl{S6`8$O>d!qj&yo4$O$a8$L)~jZ2w$;FNHcQgR5OI7HmjG-qG3YXkG1 ziK%9trGyO40dc!PGj;^PoM;yFYxhIP2Prav+j0-sGMoR<>E8x(3=wiuG@R{ceBh8o ze{URih@Ehl>dbEt$iYK@F){yNI{lA}*T0H)LC3;9UIW+vF8%-hW6){}L1TY1od2gM z^KTbYA6okybl&l&9{7j9{rF#!3cCLPdlGd0f|fPIy>!>Rzu)x_HvmwxIe#${o3NmT z5%!a;BhbziQRL)qJbr6*FSAeD?pVw^^Ywlz83sEgR-MXz)}+_{B89@;$O+>yPd9)W zt&fC)Ird2>UDbTe$$3*l1?#($EzCtH=a_EAHU{NOx8904`tTVM6$eBlqAQK zzqLgO2_GYFn@06V<2)3>N94hW6(arYN#nymjPr*mH8oNc=gH7iBcxTZDm<3;=I4jt zwyqk_f-L)y9uR(QElR7aQv;6^R};f}0&`qZF&jz%S{oreGJQxXJP6wroWHr_f5=DI z;x{1*T~9VFY)&LG>D~2L4SBZr5rd+i z%)v+{Gx5ySNm4(K1}#?E|Fz=zh?r04Sp`oxTIQ=Nt@D z2Vs((TvP=SecvW&ik9mUC@6XdGI`;`a1>(MNx2uGICrd=U6u@u>C-~k82A(&So&{4 zcU^}kK|Z+h4wT{cYw_7Tz?VtY`$oeL$82T1CXP^6FJl#&k6(+LOp1Cp2mwSA3MN-qTOPp7>G<)J79-roswW2Fol zxLGIJ{l4IzqG!$rKC5*eHzLDu7qekuYWhKU)zJ}0m0h{b`vZ#;rqOQg_hjTBL=gA} zkT8m7q;{9)*RnFAml0^^R~}pUU7a6Vg^|uT3VKMa23@V!ItWtdFziQT`NET1mbGg0 ztWWG>M%iUAeIHeN9ERj}3IV;kNDf+{+-$%G!9q32BdTKp7mu!E$}%}C>tPA+{`$RH z=o8{91HVT=Da}@noZGF4VBoe?;rOTo&Xd~pz`6o!lUne|PZ_;7z(+@B)9cpv!_v#L zt@xD;$tWejv$6iF3O24F2@|^%z_S|GR-!(zQN|Az_*JFUt-RN$!`JV2CN+Z6Ruh}h zYV5z3f{PWpC*J^O5Ecbfj;b*InYo7i&1_&jJ}E_dP5d_EmHHg}y8SC9lrIEAZ9A+) zx1w{C?E^U9&11tCIT=G(+jKVk1&4PkGAmc7R=T=!rY)Q%R4)6Xp5Wh;xxAq}UV)om z_<C9*e{pY=uvR*{e3{ezqwdp%hU-8-ddKafxu5rz>LOj>%S# zyp7OuSLNm+x5h_K{Hw&>t&U2>U0(!_D+cc@TA`}4^e1|mlotj^tR179lKf;%W+J1& z)gS~y7{ve|v9K6^6Z+Fpz3*T1JtWl=!=4hO%}FpWH_I-PqqNIBy$Dq4e}sH*Myn?O z!mOYA!uc=rVU7lAnUnLb&}J&v#qeJyeF7V@q5TnC+=LObV5D2kQzfgZ2^)_CJ-1GA zd~*`pw;$ZrY-@6FO%z8jugYr0ahWrMgjmV;qF`g@yuQQjvVXL2F7ZPPuob>J?)2BC z3-F7^=q29eMbYk(cHA~SWa?!AXfOJB^NC(~66iTRYX6Z|J1Xf6RQ))p+6O{P6AVl% zAdlh`y%&`Hxd69QFM>5YV&k~M{c3mu_2}nMNwIIgg!2p!oNAdqW-JbBxbynG3q`ze z(Pa*4I`v$E<|KPKWV@a<{PJ@h`P5^QymN5t2PGUFGj~(L;EQ~DS8K6RmFuvGBwD6$ zN{S#}Es?i*Jwxc5|tt(R;oP%3%gxFflqVdQX`HNxUD#YmPA6k9l1GF_6 z%`cqYVA=H+#g}I2EJ@VSaz0mhE{B{0%%YAw0>3>j-!=~$NKNy}H!5>AWv9OB994Cr zKlCsg2HeR%-~+nPDToLD@0f#?1K}c zCu1VLO|5Tvmt9e*2W||%+NLa$IZVGLRr+-oZfBoU{k-{XxQS9}=1W!Wi0n_uzu8_1 zm1O-}_RX~*N2F~(wKbOe4u-YSdFu0oa+x`t)qpqX`gbNShsf+Bf<{mY^myg3?DI1X zL(-$}gfzUS=A)(*tCYvZdBZjIIp64F6j+B`@@8oNgiLRVMOjq%8SfrGsO5j>Si@{6 zSrKZuJj1u_Hva7$%2xh@;J-8uU`}|QJ@!LVwZj?5xE?|Fe52q!F_R0e$HgdEOLK$dC=&AY{t@ARo*`b)6w ze(jCN(HMB;$QZUkt@qT)jOa9{b6($2kLdZgUpbu{l{*>!C0QlVeBzhu$X*kkN>D{m zQtm{HEg1QFFSO^A5`d0Y+Sq8MQBt}*mx1Y@4Ko>7#?+2GFLwaCO88kWMR^}JbH-u( z`A?`J*LZfu?p##gLKn;(suPH9*I8O10vP8IS(C*g?>lt3)qR3YmD*w7~*TYvK zXKhkXhZt2sZpF2QoUP56g;KSbZAl*l^^D(|ndY}1Tr^!N}7+>Bdjn=xb0CKw7{)j$mCzp>0QKzLZ zAZinPM(gdbXo4mhKz{MQU%CBRAIXI(mrY=y9Y|Km&muBybJ~h@zc}u1yQ2P85h~k0 zS>vfVXBJqUzLi;XqxXvH{^G*OBesT5N_!Z`ZmqSGN9B65$)XZ&j>8Vy^tBYJWKDmq z-{;At{_aZ^eY@KRYsoQhb$}C3rpE{OEdUOV(%MDn-ruZx7p-8eQi zkARp}-w}U2CRT`KW?yv7QEfni;Ql%a4)f}hpHcL~IWRduYG4e1BVkVz=c9J-jRbaa zIhD>N0ifombw2r*+&G7|9BrA5_=xNEna`ts&x=V9Uu^%wsQ7A^DP%%G_5hN?W@c_E zmxX+6F2rDL(O%{rScrclK?-j4xFoXkm8?ffmysg&z7WCZ*(A4Cfi!ComJB)=(#P_~ zHZ~MyKeNS+jux5AZI}Y2b={9DDCF!P(OR9Tcw{pp(b5pfNVgzwsE1u52&A?e}Cgi;e#E%%OGNG3=# zzGsWrr?$wP)~KW~lu!H}F#F3r?J5SvFM`q~O@2);JLHv5Js*I=h#0-79hGc_Lrzai zmoznFMoER`zAcCCes8b6%X2gs7#Q9RDi;lLmKDZ2-3N>g%(8ohmiHOX{J{-oT&~lW z^I0viGM}B{$(mDDYfqx9Gc-{FM%oZrrNVdeBENU?dC0zKBJ1Gd`g{bhVO+l4FCoe( za4%o`KdX&MQZZz$q(Jt2cw{~xcPYc%g0A!h{5OQ;gi@TMG})Y{@Mc~lm5H&0kSkA z=dLh01#}rVODt5XY3!eyOG>!K=tcY$LYpy6uN>^3t}mHVla-|}EpodHO8W|-s2XAt25aOePn&|S-dG=y=aQMQ#5kdf-L0PRu7{h|o@xf*}M zMb2)85)xc%1p@=mBzRmqGpXedBkK{?+$@$plM=K#zo|Z|$plE(=W(TgC+LA~OaVomE?(^xW} zW)&~m%IaW96bibpqSf)1(=iM~ooSj$d_&cgtkYp-8>(9n4k5cdbOgTFWNG@Mq20Sx z199Tf3z}j9oc+ba7{XZ6$ zf=U1B`+@cc060ugtd?Ox$qwSrAMK&7bGAO_Y$6j}jHStuf@i_aw+Dw70@qsI*6CS2 zZOZddj0dl*8NZ9|9G9w&P-R9Z5Ysa|l7CVBm7pr!?k&c(f5OP@Nq^b}=sI5PGKz8- zJr%A&t`kP&e>xg;^eSR76q&>&B^R|1?)g#|sO^VBOiI6?NUsndL@G~Sq9y0@EwHo_ z3Owc`EnSTvuZrlmrB!(q=U~w-6oqV-jF;t5e}@y7-3}`yj$+wGd+6X1>@I~c?|Zx(&l2d6E$1QYxs3pM-h4CqF8cl%ad%2q1kCTL>mr;OEybl1)INQA&cQS|mZ?CVfKR*hC>; zZn@wFmw4%vmFd6&tVh3C%I8IjE>L+tGw0~~V4Udrru3EG4w~bfb^Xh+{WFe-EZPN) z+KT??R+m8?vO`wli84|*vQ0U%-KmPbJQuC7RrHFzjjCx?0=>{%QrVXA=q7SKi|);j zRbB!9@hb*1Nzya%VB(m!QFxlqtlPJ*Lq)TevQ!&DL!L_Q5c3!^Ypnyvdod<1QepDQ z0aO(H&;?|Y4QNQL^6ZB09fAfof)horl2RU0`nrVR=Py9i81#dgs3Jt97>pVTqvAZv z$IzbIbgfwwoV*SlUYmi2(+=JzcOWJe9_t{bn{j1ePoQ=D zCC}q*;2bigEUq_3$~TilO6x24LRGSa!JQ47tq#b#BtWD2*zv8dxr^rHZrMB1Y z3QN+Up|KFMUAObXmXRk(By@g*%r6!&fO$h9q3ar46hqGdE)v-e4ZBks+3;D3AcX7# zxJ3P1D|PHrG2qcsL^M#;1{R7_H--c^&Kd(O_x1ZM@}Z|Cxq?@Xjv^5^Dm6;grx&Z1 zNPFaJlC*D0${ZoY3aPkm+I^78CYLDI@R(@BWwVI&J()X@KCo1k%duFS@Sqj% znux<3CQ(S|{Ls2{2^VU;v70q6v8^B!Qk?CsFqvppMkpOfDb5mT)cV}V)?!i=eC`}y z{7;*YsDK=f?c*ecmmH3~A+(qrS8@a~s~NFaNK2^K)&`v)$I(SL5fVmd0FtR~(h~bp zXa8M4DNgzdVrsjCOy5v^-ypn`X+j$A{$@6$`bE7VtPq!Iv4P`!#~W8Am)>crzk- zq10&f7?Wve;`+l(X#SPcNL!Vi0k*c0hk;WAA_G2(ZRt7ytC|CTOA2rzQ#H`qg@Z@tv>$*}({6a-f+tVlGUB zPXCXpw+x6n?7F=bkdPdtq?rLhx?yN!=FyQ;8M?c>Bn0Vh1f{#X8-|W|yzl2Z z?>S%RfKHmF zDG1Rg1bG|?k|yPYdy_i&0a3;=KQS2Io{9|(w$nb8t$h8bzVS7u@BCikXr8s!BG|#Q zZblntYipCK&Gy3-mZCWHr9jdt?Mmz8Xk9MgCbDrpw!eo~e5Z1_rh=a^mRa%dd_?&A zoBm2Rl^9?WuE(blA^a7mOsm3AbX#NixY%GnYVNSx&)FbeZVrE?U{d9@)Pp4PsHi0M zkiPr1OgeiOpyGHxbmO=mPKuhYni6o#GG3_26$ygR+$W%>r0y)7C$_ zKO8QQN7z8%s&8u|!dA=(Kwtsma}bV5Uhi#*)F2|C*3Hl^Yhzv-Pm^Bl=2Q*=}}he;6@!?PjQ1lYZ} z=GIg0S^UjOyDh~B`Seq+jM&;&o|7DcK8dGCA)0PH{e}(i!L^7`#Z)+SV~UB6!wXwa z!$o3Qa^dGj8Zkx+%x#kkmj0J^YkzHggz~?~cJMWJ82)RW&nKzw(SPPRA#TdIq3ZPI-NsYz|i%`iDr>r&Vpw~8|uii1`gP29(Q6}BG5 z($<^5umR*E{hg!dPr<-jS)9V%{3L3UA0sA5{42hfIz6Y|) zLPGm@9JZMa(0kM@;{>8yUo|visTo$iC2;$xTc5KGik|YyA6HH~R+8lZVfC+?W%}9) zxQJJEa;|3OA*@O?HL|HWNi)0MWZ40^>Ji{3FVuY+WRCUe>3x|fP zO03s3@R+!;tif7ysU=m|%$0@g4%#Rb6|<4vFlsN-BWGqM2r^PM>JAjyTjNG;(_&le|daU!!hwQ#&-2F|1O1)AAiz;=fYmGhen$E z4Yzs@UFSs5!I!N+J!SUTeMx4utif(DgEq9(r#AaI92u_ZM53(t5bF!)v)3;CBn;*+GTtwn-mBimk4TM+v{x4lPrO-`;#F8+k!h-?#LoV( zo%Z(A@nDadA&a^<0F0j$5s3vk8M7G8Rgmhyi(VI; zF|Gn@>Dh!zrg#6W1rF4~QUcMueKrbJccli^VwJnSaALlG==!(gU199UyU|W{O*R3@ zIThXx6XsFy^Wm-hfsU0L<32%>uOzV?p(rp!uQ|I63Wz0MnAM1-U-^Y~!Xtilpevs_ zFTO0j+)tO>MnltOsCj7jTTx;O-$v|MK>7(0mY9H7bzyk>!gWB=mLLCu#p_+C?h-j@ zaLn^*%AMM_q-^y|B0g1KOUXzf&=i7)W}c}jehi5V{iVDslEOcI$3kQGa3_%;*8NG% zegV%)_Bi#wdqL?hw%G-yNo?|KIq%%D!ynBa_+R3e8gEV<_l}#RWe0|R3U4+_dGaMc zVe8!_RvGbL3M~xqzXH)`8RhgQ1c%3Pv12}|N*K>L%eL`^H61LB{K@_c6O4;xw?QCJ zNe%1f5?^`Rd`b+zz5l7V^x8m<5a&oUfK=R`8Ipq z&=p>j38JU-*!CA3q5yLTK0j7bY@LzqSyzkmwB~FHJW!+@^$!aL1Zy?O;?+>YPap^3 z?=&}(_j@*Ye}0RMKVr8AH$GjX3`O-kX3L4lyqHG(X-3>k(b5p#Bo4LC!Th&ANd7s! zX}i)2HVt-Zf^c2w7b!w>5gY&n3slgE71*%Wng|D&iL=pEzbiS*B;)Wi|DuZN8?3EICTvp z%i^&u(m}K_2}pYWf)1;`8Ddl01;=)zl`3S5V#LM2LaAj7c7iG#rt2#&nHstPAnzuY z<;?`@-{gL~$rnq>%E96OO9Gt#{1}Z-Icc0yJNneGc7y|rSL|1{yPqQ7+!{N%M|Ykz zSF8k^MVlIp<%kjqc(5X4lbyIjami;H zFn27Ss50|+FI(*H9I90E@zyWjPH+NFLqsahUbg3A41?AiurCK;B6g$`l2H;mRVioP zE9b?W1uuVBX`5<^SXy+ddGNnb{- z)gOmYr9Z_<9*~yc=>KS0=Di9>-v;h4qa-i?-gt>S=OPvQP=xgOikkpY5E7Af%Ky$_y^SB#@SiW27I7M;c4dpd$}Ftx#W0TpX(zY4!xZdFWd$+JPR~QuyAh( zRHuZ(%liy?0pc+VCE?DBmwS8O>!V<~e(bO#Xt;sbm!<^KvRseP_%w+>N>Dj)4F_b} zEP@F|H(W_3@iiUHdv=~^D@wp#GDyFF%N>VCK#f?%1u7d;BRbCnY*boAm(|pQ#N#Jg z={K;#%0PVyeIQ>_kg`TQVG8nAVr3U|+@F>qPl^aSxo8DZ1qJ$@U8c^!0q6Jk?1=kY zstPkDkmsKG>Z3GIk91|~8q4Jg(t3?``AL_*{qCqgi7~PnF2%9KGCVQ8UGlMpvS8Lt z?r)eiG#c@y6;Rc!2`cLrYd~UaHezt2vGzD3gW;M~I8gE0P7+P5PL|tVa-SBZ&2T5< zF3~%@+OGj2^}p31uRBgjG&NwJ5=BS(J#%wT!ic}6Ss~Ax&3CwzKqWN=>ag%U2TP#( zkW^VhyjrQ>&U;e-LnhK)IJdWkpG(QUrhUL!CPg60IR*VZ*Cj1P;Un@TaH_YDkb{R( zlGtGc=D`x;$5EFuL?AHz9MZ*kT$MjV19Y!f<@zfHgZ1Q+N0m=C45p#I`)btFTBmJV z+s~jP4(Sn%YVe{h1xmzZ%vA?`d_4|&K&xD&F=7CS^OiByg+`LRuE?CIGW<$u`FSY{ z6>YVw^nQzogX{}Xit~%kX{rC}dhRdWvVWiZ7dJw)>b3YxDHc(W4$tOh+&pe*?ixE-(I+J#bu$StTqGGC*Q=<7q)vs5f1t|VGVm4!?!&B~yqI7Nvc1vuH3h8GEEU+#C z>AaU7^a{eLRGF$>2VPcDLDJSot<)xyrnED5`I zFf4JZfz9zJm#q>cvH;M4<{jv0(OPBXL((iBd3-=|hy*XK{#_cDidbB(s`h(6p(oA- zHW_jB3i{=b?uU4Z;}u%HQRJKA6NBWXM{xbakrC9Snq1O81hsfCi+=}N{N-VJwNudx7{yM+1qQ7WwWZvw`tmASlUC6o}}?f zSU{nuUq!t>ZU3A)al`LH_ZK=dwEQZQ(Yxv3SI!`T5jB5s+MrTH2u_{ zz=+!{4jsROtei`%ys#%>4T-J%3LV@ujc*OURAMtrbFWfSz0W`yI*{s4Kq_Qkvo*!K z*gY5In(Y7Fp4^=i)r#LJc$<_IU^tbKVgqN^QVvso4BSkaS>=4LA}P-Q{MsDJOc8P> z-eTPH>?(Xe zWDC$@ZXQ_oxxtB1gn(wh#&Z&i|CfXF#v1>*I6G4+>ptL>i+y724{>!)nzu(nHj&dCOb_dI{u`;(>QBTBDDTMSHX{pEA3d)vI6@?gS-gr zXd7W1*nZBO`#}Z9U%+}RSedBXTb0u6C9S)IG9o`~^C-Zmd`w%02K`<_rvN>kb#+cqA47Df98b!i7yD`LkGkfiDINQ z7VmdYMB>0tApXDN>YQWF@?7-qfw*MvB-slCYKl!~b82duQ(YA;8B>(LSw#^Z_Z*e3 zd|gB_-#9GirebJno3+O%w&sgx2+#g>a7ARJlNx;OsOg?=(8;n`cQG z^zD{WX}T^qi~uhHuODjRw2vwNB=zc>@x9x6k^ z+vTVFi`66TEqO6?TEt74D8&Mk2w&q@!3>$3QT5hi zXajx2iQa}?>rvF`0>o;R>kqU{9B!Rw|20pH0FmYiBQJnU}NUoE^v#4N{+KZ^SKovpE9hpFBhEZ@_L{-pZR7r$J=VVbz``mr~K}S z4e`j%Po~eQz0(A#fy=b50z}%nI(T0dq7Ou`FZpV6UFn$Gm}P$tja)&prXhZ@heY7TC_5%&0~m{LrR7T$Rs z-43hhTntV*?I18%J2zvbwSkqF6DquXqlgKm!tV)on{{gKN!caLBn*|J0)SLPgqIoq zQ&>yl>}B7*!`tzHW4-e53V&KUrD2c4fx|GM{9(?M)=_hxcrWla6<8z`{T>dbuH?^W@|uRiIwFfbh$x36W$hwU=U z^W|EgPp*%<{u16yL9)tZlE|KDMlT60_}3lz2TRvxEnym^M&2jHXYuTe|3PES-yn?d zrMrPXD2@7uimpEU9+H2N10D=lwip*=prg%7Z8rS6#C$EN3jgOKB`C`>$zO(*d=t=5 z`z$(MuOsHeGxuE8{O5bWf|OxsGGQwNLY~A_(pTgnu0#&32)02r|6%4a0w@s%_EPGL zKUf@NRL~Y`?jE$qXZ*Pt_uD%5HVeGTn|wWT$~*is8QMFRIaWG|y!_MUG>#Wn4Cz%V zNwnU$hGDy1GxVUObzwrob;~0h3J_h(qa`h!2(UaDt*c;Hz`_kDGG4Es?Phh3rp8sq zGkOF{nxZ=k)(n97wKSdvKg6N~sUGuwhGr<4Mo7i6mkk}TEs3|&u|$4 z{IDVP11cr3s2BlV8PrV@Eo|uX+c^!4ayf6tfc$D2CTnzJw~5Xf`ta}2U+6_od&E*S z#5`Z}O!gl3zIeKq%}V^b)Yiz6fz9Rmk~Qy-@qtF!NGfX8%F%4CzG~uC5t;nzc=IcO zgZa5mUY%-CK=pY6z*SHAzfi${+$WJ?;93@!PQAMIajSTaz73B(@!$H1w=So<2vUBAIkM z>5~or%Ds2f%_|Z*>zDtq@Vxi|n)_;g0l&kP&LBvkx_SwoJ}6DQNG&ZRUy3lTXa-aj z8r6U*qU<4QB5mnq0)^IsnBd(gHTWzl6G>tVLrWDf42Y_B{Yu?k9sC4D%;2ctR+oST z7sQy54%(82=9LVyV8=kpH9V<98{lID9(6RgRg%=RYhDl(dcK{MA zU0*0%J*aM`n5s^69r-;*AuQU2r)$bm>mD{lHL8U6(?+L(X;Ah~sA3 z?XCLpZ=tqpUJaz*e|ZomixD}#jD6NQ>dEZ;bn*Jq>s;!(ev+6@M@@GT>nIg{dPbdP z>g)0U59f%4|0CPO#k{h3h^En!F-}6;(x0QS^Qt<(hPRy8g-`QVn{#jC{h>JWM-;Hpd zzzHCXFL4?6qos24Z%!H!J_gLwfPuNp?}stKQ%*C^ z--aS-Yh+X4uOMm#nQj~nB-)U1Kh`2ifh^+i6rdgipi2a)f104W6D#A^!fWeIh|8qvv6_R_m42S=Fc0PL4P4|<7jEG1Cu04U`*R0EW(R|*auaxV_sA^cdt zhHhTxj{>tSGsRZFqko`MzlD~l%s;CEL=R?32yLxK4_WRN{Xb1*zmQT&rtG#c4M@iQ z$z$SSe^MzstJ-liSFpYy2>0EisfPBKAcA@7c)1?I}AK-oT(~&BsO9AQ6s!&hhP;#eeZKG0NOHQrbdWq~tKse1zY;IxxieE#8RDU`Pi2$~9+!25aTnVruZCsKAToI7+!7)n_q za=fSTk5tWV?FGy|+?@L99w`W9j*XfnOjo7E8pnL)L#Pg%cB@rjtDBgE;Gzj(d8g6s6U1 z@Yt%tq9asq@vkvgO4|CxK&^}t!+D05sS~t?B1>boG~A+wQ;S$_afoshYg_(lhG*#i z4F&38!T}l`%!SLQbvl=0u2(!Txle!D1Yb!|HH-baiP@7Nn>9zBSbm)^<7(`()Xy$PcMhHseiF?*)`u_LT^4}X`@jq(j z25DbNCb~vryA)^LPuxDkUSRT$H8_1t!Q_E|c36LGcBaYi;?J{&n216NDmFOMi5y>a zEO=5nBfs1`B10RT>C~LqkxD<{DOks~&BQn3RA!c)VFG?|n%Lfx!7ZuT{reeQ7|N;q zUJ;LrvL=N+{utv1d~IMnCoJqp`Dq7KCWUj%9|+<7O(4#8R2)^rr|c_3=JP{Yk>Z~C!g4FJ;aR2Anv3~mw+-bkB zKy;jU_ik=;467`B*toIO^u^AU)2^G;t-i^X6(bc=IP>&2!I=|!kg$uOwuJcxX&w;oZ#Q+7U54BL)%=$ukHZ?c#c5u zi(~N~$whvDft?MBSq-U`XSA{F0g3=1YbkM8f-$ty3K_3IeU5V$5GSz7v&w|hw7UiN z>G*IYF-;ubkQ#Q>GSTW`ovR##yCh|=)l*D|<4DO-5BHqL-I3TC%?c3qkiaA3+2^^`FS6kZJ7G4fOuMa@9Rt*RO zkQSlQ-r|x1VF&B#PQ^xiQA&6_lnZ6*w8G|eV1fH8=HugTXB1hk6fVJe!B5{=vyOfS zSc9seHX+pp3yav&Pf%RK2W3wHkdMLc1$e?A*b8uzyBImw@3OYXj$Y2xPoXmwpR|QM z?)&Vg5&Q%uqSiKq9`h`$Ex`DG`Tr02^S$#;6uf`8*z>i^=ajQzpEVBnpBV7#pbl=E z6Ny9>vb!k^~>maGo6J9 z$B^+xFeED6fz&&Otm%8a%1Fm%l32z@%IAOcl>9168q_uv!EXYk$Cco==@)^7Pgj<@ z?W@1MJa=-8zM}A#!+t@sdixeN>B_LR%9_mUD8;LRO36S5ipS za&l|9lafv&FD|7(+s6Su7UJ~q6py5b7ioO3im0nQM@7T9=O{Vk<;0!0>!Y%=fVslT znt~0F3I^k5+h6fR56({+Pky*Pg~6Kc`_DD>n-e|5Ehhf$<>l5gv+HmsC=O9=LWq1k z7Zo?8P2!e9K(k{@L)9}Vq*5M0y--FL%k-}(*a};~PvWy*Ecr*~jP;|cB?JA>C$*kd z?0T`9(X`zaL~4WzT%}z1kr|&x39F6l@o|x(JK@j+#NYoe&FP2l{u@Sb>vzWQ?l-^d z4j8$lwI3@a4%u3tA1o~IflZO@27h6%T4muNkB_*+F(85CATX#w|3Jkld2d# z>Y-YxzkTG>aejV%dbo=hBs<_g-Fo}uo7i?rB#TOea)Z*gk3x}`ujQf)(A|&0l_ODO zQ&&yryMMusl5oKV+n96UHc>o*D9!J$ARrQvc);pQR+Zgv+IOGmA(oM=v4t}Nv4uM?IV59mGYsc}X1Bn{~aq=Nz`rS6_NHAifp zJmu$S>*yB6aljbdjxXPG4tx#;!ZBi@TN6zVyOJrk*ky~euH{b^qEEubo-1<^{}g)8 zHvwt39yVu6rn@7w;0Y9xOD9%(SH7A3A_7q>x3;hyIXFyJLB}(fmYB^xZa+A&U-iame%=F_TzbfifQO!sK z{;oqu8uEA~_FkgT+T!oTL+jh{|+3Em#Eu6)e&)$bZ|1eQVUK3YlIV_npJY=K}{ zGI&2r9E+J*M)$^M!f*WdPBAb($FLZ>&w@dy`jP5e3RB-P;bGsl&wQH4g}(jm54ZP5 zvB-sCu6eG)+eths2tEZ#6`0&(BCmx&5PB)4UjtP&=7}5>FVh zCPYuz08n?(|vhixfkb@tofv&RXKpi{4`0_k^(tpekXJgyRI zQQU#heDn)~jfF$;D5;HDFPH;6Ml<4V!Ii7&AG*#z=ICP&O&InS^oDlf$Mt_2N&3;O zpGDG(H^`$&WA7XXTX(e!m@}XaGSBaSe++1uJKK_NI~9By{6X1&=B2s*o@63*Ukj_^X~X|Z zb%Oz15?MPE|4euqDV*f#v;pCk!ei^M6X)a-?MN5~U+3{RCT?~l(&LInD|lf|6DE=> z02qC+VAtZLgPu_!BdT51sQQO#ecMnMB~Nh&o5E+q1MV_Xg&PUL$;?L`BIj4mCQT_8 zQw~CdRuvJmhBrgr%B-%uc}~!6&f&Ynq5Z^%vRG?UATlR%DC)b!ab8ZlZA(&>(Eg)X z@ug>dv;<$Z$lsCLCiq}cbn8&(HESB~O_8mL`viGOX^TFGx1VQkRtJ0szv@7Q z-y+vZobfEFGqBi&bE7V2Qm#RXj=L?Dt?6^cM*zR(kq-GM#j^en)V7vcOX50U_F32Q__$x=X~cxTCbYAxRh zelwzIgI=R$IhXhgbo=gL{HP5z3Cy9J8o){yEb|>6^lDP{_ff!wA zX}I71GPb&y`{1rWdnmf|?)nG`it)UF-^krhJ50-1M;?S?tousEwyBoWkbXe=UPV`3 z2cyUfLB&UiQJ2~hd;Z`9)wfra_I;p~m=y-K!a}$ItQeJ=ozF=aRZDBWgfrw~7!wll z;B}s@`Z!x&ow_$H0s`Oc-G_T9eMQqU9FbbBwoXRigLF2r-Vs@J; zcz>x3MchzZ?5OL5nrsq$4<1y?NNTH-WlS4v)U>Ck9eK+5&8=o5)#nD~@AzSMW&OA4 zWm1)krI^2OEDp^W3#>(L$u^pr_Ij|#E#X6aBSmV|Pr{+WNlEvEbeSfxl+A9gPy57G zil)Ua8r_Tfooraf?F%^H(`4|9OU=R(?(S!Q3!Te&t-lFWnCgMz6Y%^??7$9?;VblZ z_$5ZGc04zbK<_gMi)nURFf0y_8`I=5l^I>BJ0-Y(lpzfu1sAgd=s zfMwR#*LHic|F@@{w+iQ$D-%vy$7Za6mQDvXX9LllfnYGJI0$|gQSWq!CaN+`m z;Sj$0)t{iKarulSLWS)z_|mab%TkGC^b9C^n^u^B72VPrF*hd{@-8af=?0s3`|EyN zF4So80?O_EcWmme5T(70=1clnkvrn@{tp6KdHs7C?Dv}n3j7y&kts7Vdp@ChPP>x6 zp{9r3&TA9mHpf)Yvrdayx)rJ$;#~VWKSGq|e%BDzMh$sW6M<9|&eATcJbRA#`qm4q zB}`fa=@*y8*xVHXM%rC|+vTO%HYep-Bj2F>Mn!d2)S1$2bq~{34uPfycxZfZZAQW1 z^@BO8UJ0t2eOHf*47$%I1&492djcCRg<@3nHR?jxsEhmba#=m3dG$kd=C{YFr`UKw zG^>wX41||oG>jK&NUX$>dJE-uK0U^JUNR1(hdZ&dZH7p#{6eziB4PF3@WIG#!s~fg z-h?z+yhb5prY1upJn6{9c3jXmu#BVN*qA0K1?X`sqb>G?w1k-c^=lnYH~gX?Ox{m* zh<)hj?IN&YjKFIyC_rIN7~P#FUq~%=kBqCh>z^Log4W*;4_`Q4z2{!8vwKfyOBUTa zyxRY?!p9|VF%VYI3m@0a@qfZ?bnsq-%fgsroXh$kFj@Cvc$4ojesC9x5I9@~T#>9~ zSRBTS1O6G=oJ=n{1|GLk99id31BbwagBSUqa6o zMAa$yl0((N*FgTIo^KAfAJoS&_%!WW?QF586Nmh^4@s>Bx|L_Y_tPsI5+Bk|8Q3t$ zs7n009-b&9WtCj&BoY@uBIiJaL^uG=w%5!2f>Nv71L#SZC#LXXb;8;`ZkG8TJc4}< zM=oj_G7qR}99boC`Ya{L&u72t|Jc#rEn}IG;2qRhcYCis+lgF8ok`!~FD>}T&sE>U zq}Z7nBeD3W6lszAk#N-Et&2_vIU7*YNAUTktx=$_pF#t`(Prfi{SMyn@*iF&rG@+17m4ZwQaCs(a;Vaw7i4K@b<> ze%5YMhPAJo`(_IxqD8d4yus*vbC_+dMb$B%kmg-v`~LeC-TNfAnts$cWPl9};RNnl z@$(t-kLCRsxV4^8enu$l3oiKZUBnqMwxOoNbYIS8Yx8qv2WSZ!;Y0w^-rjy=QEp=) z#sztCgoa47TqDT>`K^!aP488 z)@bo9yJm@}#HoJUh5wUiRQ`gs)D~1m%@FdPTu%J0OM%Q)%Z6PUsb1k>@?*G+%-DWz z$XI}B43q-g?F8NT%LdknZH3!R*4FnkT!qvrJCT59bo|R5V1D>IW1lWC6*4F`v$L!X0Ibm8M+ z17C#%;h=lZvI&>SeI@}isX>fF4)>4ITv*ep?Lz!O!f6Ro$9>3z1ouJh2Z8Aj05wuq zFHQ+cKpOFKDdJ5{eBTD^L1pS1zh^A}59|{%Z}9cwwq?X9!-lM+AL3mtmzh0~|A}g; z+6C|d`!HB>Ww__|eej^K8`lT@j4??5^!RH=DS2#kvy$L$sLmpFn!^`N-COFS5}h+8(y( zkm!t3#}JtJkdYjx%+9V+e-Y7^FgpOTWoqr|(a>}JCr8z(yNshOJVdE=cc%XI`f*=* zYmlmaSwz9sUC74uWGQvj_e6Q`@qKY*0StiiKF_)|!)Rgw&f@=_Zq@aN%=83DbYfxo z)gX#=G&2CdR#o?3Y+s#3eb3nGsEHt5%=@f;%n%XZY;hBFkkZKFYO zmJ=+BGV#Jqx*V{pbebdM@`Ib2xtq!X@2-Q?I2Kn$@`@Kh%=R}{ES*d|2fZX$z(O!m z)5O-*aDY1hw^BbxtXg=dW7&n13z>4~GLBojRq_@Gjj;gZM7?vn}YbUHFHFR-4J zcErniY(LBf51faB4BqEssR?ge(^RXt8L#vAuQ4)2cs@fZ!m(et;A}Y1AMwKIpb)&+ z`c88Dyp0{;diW`pWtPpbCX(J=d`lT&w8C#(-M?F0>$-4;21^sbeV|ysuM=BQ!=Ke0 zUMA^ONLKV0joOHBoIuj56g$y5&sy1)Q=_ib(amT}%Dm!%$|qH0$kBlO`?;hXNw2_s z#Ycftht2*HY8cD377aaZhG}vCiT-BS=5?>=J`f;&RH8UN$yIWwY8rz|5UW94dlpv` zVe>DFEua|y-S-sSVLDn1Cr3+=CryeBd^0^bNFLpHwM(PzoV2knx3Wt&AT&SlkxyKT z9{Z6lEe`fl{dpJr?tTF<2$MNmWfEW6uIVBZ=SkOe7MkB zD@WhJ;mH;?aj0}F_Vr$*2j3(U6BF0TcZW}MZ~Y7!p+SSx5%ei!L=ydSKhm=CTW6iZ z{{Bxu9=3w>!~!EQP2z?xWB^{tG=C>MTs#WsHdp5I1hR)9I~t{yUS8aJ?e(h4=zdxR zt@--%jM@Ib39Vk&sQ;VL3PY69A7ED06=bF|FswmVFCTUqVHXP*uJ!$ShaY1)dD z{p3p|iW}JNmiG0lu#V{{d3${V_I&1+61OU3#dR7lXfozstm@q0*8b!%$v`?-1B`d#7QZF%9 zj0xpoWX+?IBrX{$ZMU~KMdrKz+sJLBLEr5zT3w=QgRKAfmDLeWKUG2DYnC?1X;XI( zkUJ2Qalyh-D@gNpRc;InaLhe-Ct^d;CyI0o+TBtoA5Pp8KmPQvQKB3%)0yecz7;Tq zl5g8ONU^}3V0QmTUF*6a%)tpMbfk1J{2Vg^6qnhpf{o#%%AEf}*-RC?Yy!f(M_L{s zRc6#B)c(oaY~WQ{`?C6gzWWGsCI~<*=Iizp3`1s@KX#uf|6bK0B!cz)xZ60Q88u(G zbtym$Q7?e53hD2rs_AQvXc!f^7!~lh9*y$^w_Glefo@UT6Ia zjNopkVbIXbYYn58av|N=bTO|ov?3DJEIlolyB*xNE>qTc{zwuk?qlq;_fYVxF)CvB zZXgnQSTjGvzM?cVO5C{hM5|Z^9(jo5YU2Y0St);NW;+sN>-2~Jnss!v5hd)B(zBdQu(}%|wc6_Pxp~TE@X-Y_A1>>`R0Jbb5*qS9--dEPbDq zpK;Dd3faM)RvjAv@5g&w)~LG9Bh7-(D=PtFZ~d~4RhB0VUH{ak+=U7p0hua@tZeNJ zt7W#Z)6>=jq2k68c8l$Amcpc|`PDU#hmwxf=5-XNVFk`blCChS3|FR5i#Q8`u(>%= z_>TflmBokZaFT67oge5y?d&t#CaJN9DFs9n$2ecV$$WaS))x-Y32^3%b-iH|Eg9U& zSA*$FC+=y@{(_Rum$6BiMT4YF;}3?J^^^b8Vx5NC8$&c6(iDp;f5BsboWjdE-6G4aumDR|2>O`XToG=n;l{;%u@#b06pZ-RSG1n5)I5omP0G?z{WAT>! zB~8XW=zy{i+`(7^(cJSP0$Z~NI0LV$Eu0zZWSX6)fW=T9Ga%jdi>{#v1x=M@;gfY^ ziNCaiUcSepIQd%?*lZ@!R4kWu>tNK0j+)vywGK(RrNQ!-4S>R*2-6PT`RtL9>J!n# z+DZ$OObYO2_otb+6(F6Gk2(>YCI+{nQzH6ic>B z-N!EY5V!p_HUE=)7o<=SO#<_sGLA_sJv<|X8=BJuEn|b*DC^RiH7&CK0j?4kw=cEs z%xCKA<_rE*RD_>UHAPR9l$2U?0)aY-SiFUq^oEX8(NV{!lfM(Nt{9%Ia*v^trE`|4 zALUBrP%I8L`*rH9tSw*5R)oEeC5S}@0E76~fe;KF)C<8E*O9mUw6wo}2bUi{J+0K< z7^9CIi2?+t=b--5g+yl+xPb8w#mtfpt|JttjNT`VNxtcPnH-uLO8A2Q=3(krV ztEZah--@i;Rew&D!7y@Xp*S8Fn6O=HS>MnKgLQU0;`cZc) z=JUe2KKM8Xb8!obfMag}Ngn~Zp^_TDG|xZYed&0})T*_py>NY~3xe1K+ergQO@LD* z8-6M*_thfwfhVoSu5<-g$m;O2}1bDnsxcV)7(SE`0 zbRSet$vQ@RVwQK>wtMhLs2YLx`fsdaQU?PqX^o<SafGL71>Sp$PE_f%jE}zKyC122(9o88X$z6#J}0NjB<#aqMw; zOGq|w?`mvlB{R~2*-Qf^EF(vN3u^LBDC>bZiS~;x$6BFH;G6&bzH4G3A~;fMbK8Wy z4-yI*b2Io=E&BsxEwE}0{6*VM-9=mT=;7l7p<}Xr3!vO|T=wHv*+!Ecg6ZpO$LbMQpizsf7IT7pR*Kf*(jXh`aH+|;aMI$OM-yA88ei46_=O3Ms z4@2rrn@3n~Nq-vd*lUV=A@i0t&*;?8<@HZ8vBq!UVGzK*IFCN81^HWEN59b3drrmr zLuq?S^U`QTf*$yHA5$H#yq#n+n&c@%x3J+!filzC$=%J#5f|k6g3P9;t(!=QLyt`v z*SHh|R_VXLzN%J^O6lUO#T5wng0>zU!4DiUVfTr;xalCYCb0cd4@8jerBmc`L_kAI z7Z{8`yP1A=d-Fz}gWLk$%q_9lczBv(md=>}OU)Trk34$9g#Q_i;;>zDnE~l3v2c*D zV_Xk9e-LzA5T2JU6uI`JIN~5dHzQe*knI`L#-fF=?-8jG@|k&I)JOni8-wV9{Sp|H zll{~i$*Hb==Lrin&G%2G%7@p0WCK1*d-z(gp+jdgiCJ32-gE_4wK=g=$56mPf{ipB z)$lm&*0#wcHDS>oC0+lsK`G%o2TF;96o*PgF*E&c`yrFpX+LIt1{^ZnAvEK9-y z%fvr*`N3LNiGwI8n=snRH`0+U*Q>Ow6$Zbk#Tu2m=QQ&DkLby8j26kK~o&ziNq^rmNwT!y}QS7fU z1Q&+qzO%bSoNd1#nyIjAdhB8&*N9^3WQ8h0Vx}}=oK{GLw>qB^$Jbw_vr*nu@xM$4 zN_%|C?q)3hhM@OU8;zS&u;dY2pq65Gv!>F{iot&Abn6{qJUBavy(ElA6U^=lw#OAo z%qQb_G?==c9rD|TH8D(QOQ#aCq`|lw)Yem_0J@)BEZfb*UYm=kf*U9_26Zoa^`Bz{ zyrfx@&{qrZ`@{|bP2o%g)!b@K)Ig!@X6ST>zP90*fY)I>(90$U_!srlyb7Y62?`P0 zSGzW+83Pb!VPi4ndp-vL6Xp)3+9Ri&W#^3AsL9A6u$@spd?%8lv=XB=-7L*<*Y0XK zwz|FG(8h0L1F&ac4Q}jC12sP`V|7GzD;s(DbaV~Or$}&EdaXL1(05fE6+P9H|Ka~9 zAFl$OOEYOjnLTMfIag4To$2L6EE_zI!P$wp<77#nn6EAITrm>Pza!Y>qmIwp7EWgE z?7vAHV2oRbiW9^k-_lahrMgmwIyTa=m$F@bm{&mSi^=IL3M<2uzbN}SRHBkfTVIm6 zM0e^vg$e6W6_7z`{GLeSg8d3)$03D)h;%8}bdp}LLfS_sUjR5QLxZ0IgB5s4`$$iz zX90M}!{q_xojGLR$B79Y-)~}i`N?&Gp?&!ICGadK{a9n6QAa9RC;yr;hxI4+SarU~ z??LpJ7d+JIr_w%USa52NeN2kA#6P|AJ$_2g$)uKQ%wCQd-{oFew7 z*XZF;6YA$r-K)O=Pd-~~MEAnm{@FOHWOq58fWJ;jO{ODb1Xn>$+&&tCWJ=MmVc%MD zS^wu~|GA){)bY{9e5_&E_nq=T-b~&?Q5U*_k3JqQPQNEc#~LtmT3M5GMC`M4YU*=x z?iW+;#5|%RAHmkEB*JTFLLE(REW+yQ)*T+HdU1g|OYV>EHZ7JhU5}w_TYj1xPyw$2 zKD#T(Q6~l8%|3f7D7uM$G+C)D6QrS&=0(0dAFtLRbls9A1liE(?3jz7eSC{mue!tt zoGjt5ayClEpq#F@4yC61=d9TPRRm^TGJ=0OD}OjFEIMNO6$g2QO8lYL93!+5 zDD*V1(z*_RvHS?e(m=@%GR5tw7E2q>@lc~EjN_5OJ+&pWB&8)gmk|J`+#SR17v>^W zji`!~5zN>KsV6jYsP415x^xi|LI${5=(NshP=F9FBou4RPYgs7xo+EI?XUQqPXZQ= zB~GpG9^MVk1v#J5i;Fu12_~ln6(Ur6zbDsu-1y#cf^Ijy&8*yGM9sSlZ|ECMrWj|i1w~1R+%wzJEo2y9D zd@sl#@{|Qs1zzuNhrW%Y06w16#Aq*H5q8;%`KTz|_F|B@#*}4=?ISbOt8&?MAE9EbjGkR?}0gZ^c9H_6WLEghhG$ zy6#wJ4*;!W8-V1waW_F{=JPHT@C!R?9_K8|`Omqv;!*^3;I3}GP?6|X_I#z1^D3y8 zy$zV-`?9&WY=P>EbnAfjDRth@*vVGZzT4LXSruaX{Uqp>T!8d%rLEZ@vCGFh@O+*E zH|?fkbIj9kBjzJ=zJThrxB!Y9&(2lY>fz4vZyswy>SV8aRu}P8+@IL>Hx44q*HUPR znzOyboBg_!II9_Ts{RA=yel-%1-=a{r`TqvX}IxU60mfLT2qIE{wdF5WPZ3t`PuY- zg647QY$)&>@Hvkyr~E8ztvZHAS+u)6`HhUAo z&*Qog&2xB&%F0JUE2~OESp3v=#*apj-m;_IlR$?#Y{NdzEH{#T{-qtiXVc#MX{{|n zqB0wE{;$R@J>_D3r0a4^*CJonB_p);NREFnUBA{q>r>a67h?rL(O72I^h%JR!%;p6 z+K^h0L71EHvrFc^?DyueIzF%VGV#={F_H-Hja>v5FcXMo1CH1((fYB z@^>a$RbQ$5*rpE zJSq)ljWgTQ*Q+f^NWG=m_wdbk#}EOl))ZS?0WYKefnMMQ$k!>;oOYx>27}5 zp)q+FmaPf%kdLF#dm5q{N|l@pX@Zx6^RF2b+h{8s$MUzNy0`lb;Bq>b}C zlm4I7ScnW-o?ks4M0(p5M@P%D(0+Mvtom6#&W$+KfnXSee@TUZ&~G4y@8OL7GH*aF z5!{gJsqTeD5`S2(WuD1Y{Q%BdRc3?h zCUCFKnrKO`0{8Ko#cfIJX)(-R8uaESJ7#xZr9@!g77--Z7_YY*qJ_3MlB3q?0u(U& zKs+okMb*|F5+>!G&$cA_n2asa7TbuLHfzfJ@kXN7KrSDK3g?0H~#AHdj%!+53L z0ON2(N5&zY_=DH5iB_{QPHj;4MIvxU*pw*Xe!F~;wExb}>x*}Lu2P%sXjV}R(!&8X z><*trrS0K0()+WQiT(!AO=ptd+0ya71dB15rATv(@Wv-n!CUUE9sBAa+5-I3TgEp% zN%ZtWoL?^xdN>D3h5guz8+c*Ozml1oyxSz~xl<}mw={9x z07SSsj-^qgAvF#gv+O9uE}cAyuAJ(Yr@7{-I^=?MGIxV8@=om-V_WY)WYz(~?(uAX zhjaGn1mgF8KAw-d1`lwKrQKj;(aTIJ(yv<4Zt?QQJ$*+?CO(*Rui8iAdDS`&j-8mj zZ70>UIBnX-^8_Vhx2bd6pj*?y&Ax+^VB(lcokpiQ~-&W!FpG( zUvOkIc_T`$(C0kg_-W7#Zhd9Uyuq$Z>zjb5#;o#wfej*M9Z!Zl7m8x_4=x47c@5gS z6*uprOc4UlaS=So@SWeuRQYDH={fPaX2wQ@yORqj8}u~Lk{M>lcNJszq=+qj3G!~W zSY&LhihWDJ)*=o989mzv;R$*GNZ$JyYNHnAx&@TV-~MhLX62tJI0YKl_bT8x=$%A`o09#i8*uVol|9eH{}QR zzd*l-2C{z;W1+>h}lxFRMR!a_h6Uv zXy;MCoHNs$XS7h6Gq0u_6|DZwXU{=|lWpNG2JuTbm2hdlYXy0%(b%tDUoV1vd|0SY z-x5?u`gvY1rP+FJzT)Mk8CrLBxOr8fZ6l;DcT}!5h{G9s$XveHv{#S5nC*0B4e&5i zzDxb5Ioe3|N^)~J$WT(lU3|^xf|^3YP_U|ptw(iD{V1HkqdH@X3b%*z=>`G-jo^HE zcx-%c7ELh~xpAoXC{<-(=mR`dZ4(QKIweB8bhe_-CBrKY6QCvGP25$Ft$8G4D)BdL zbk?2`1+{FwlO|)Y#=*WCrM?7^5<$sbVaTfRg=#m#s4Yn$=PLhOay$jGPXcLK$oO`NT`w)hmkG@8zfRsAOBV^TFeVz5se>n0cV7iOZVr@Rq* zA1zX8V`afA5jVPC!32$i3w{VAgox-n@n-BPkJiR8zCQO8z{arobLLmSAtCsj&bW7E z!{wd@*jlA9j@*ivmC6~D_R|-GNROpc?IqAxQk$bfuo;v9I#+171ozSRNLJAMTVuGH z%RM1W^z1el9i*h~^Wgfj>8AJX>f?C2DR$J$G+{32-nsGC!2_0zleS2m)9qE}Ji3tv zznhRh^jOa`*E}Y&hoka+m?>l!U-{C!a~D8Vn?}9rfaUHzcGTTn3H1J>KI5QiS?O5% zQsHiWUfc*Eu{j8vY%+;X{H2MoHdk#Fhk&ZjN84Mx0<>ji`?E(;-JLmG;6vhx8<=LcR#IT%v~Lsv}KT8S(qkmpGURALYg@ zoS#)suga#@%ISlUNsAzQV!xh}ywMq}_ls%l=B<9I5X`lB?H#B*CGm_>iIyfAxy%4W z32LM4i|OrZDa8I}Lci+F16)W&GYje1X7tNDHBa@en{|wa)zVtorp<3JBaatsg0;q9 z^2av`TI@3Kv^T-AL6ZiSIr4A5%=!-#7u5%4A1KOCG;MwA(wfLai_326d~j{_If_tO zf4*uN9FrMOhCpFhUL6J$^w4IUq324^VplPo?CPkc?3T4@cepy^K1idrQkaMFX@le9 zFhUj4dnxBsi+sPvn+nuqA^Ik29svi@0;Mll*P;oJ=3}gBerg+G{>MybxIF99d&V3V z11Omni{KW%*(UKEH0i-M1GbIyDph_fIp~&K-hq7TZK9GtQ69yF*R!9}a$O&{b}eWz zKDMEZ2RfwN`s0*u&+2z+>$Y zkL5S{Hy7(b)p^2gQqRE}5ykC}@$R`)Bp3?@t zKXj_Gx*wHip`(bRS8Kp1qA-PFzTfnx!-y62UOmnX^jWZ(we zE=aiAAJRafTdgEqO0TwdYFW$p`d8T?duq94XWfQM!1e(>i>GUaLENqI67TE1&eP&q z9#>ZL4F{Y2aU8Qak?;YmEn)b>;onyhP2HO}z9C0M$EpdHrCa5|K9pZ$E=0yyVjSD^q}|AMmOpRzx~ zxK%u;+nOp?^@s8tYDMLMJ~GJ_GAXbPnV;?pY^x@B@;@JiZs&}2D9?S3j6Yc%_`-v+ z)VtR4aSq~B=m(_}At^eUkEe0wD!;@tu4EO-3BxysxbL6o?96 z=4Xh1PgcmT!UbSB!a&@If2poYkbd7X@ES*4yCII0ykPxQIYM@oks_Au5CvZ}jttpdAI;KBhL2#oNDQl#hlr zd=5m2D1MUOa%7&e_pio?G{?@$pu7bui}}ZWC*L}&g9+|%efzqiR+e?md^`BwPmZtr z@^q^9_*oQ3W@qP}!F6djEKayRO%TgCP1CDhLMV?NnJrO3Z$XCeCOTY++?LiWeur}F z7wd*IE6xPbc6vc{_DyN?k{bCEqIOFH4zXzKwX#L4sc;+K5MT@xY zI7sTFC7y4Ft-w|Ddk!j8znYwGggG`*h-W^{9*{Up1ti*5)%o*b{|?~Q#lu!eGCk=& zg1u;)yo`v^Ohejr-+D77z7gsPaaRkA9I0NX^^oBydfHj6#4^XWEXbx(X@$RfiKVGa z*Ac4Na7h|!8{~Jjh8`;{#=cWxH@A~9X^O5kBpYx31Z~B{FW4kEa`gpN0Tsy25s=!I zZz=HmDt}opF!o%F3g2EWqsAmiuyeQ=f6N&3RPK+EU==)SGAs`F^qZH)3BP8%MfIxs z%=6r!bFxI0=BSB({Gr+*R$fEtU09-Q!T9}_&o=f>SsE&G_T%rJd&KC8mVgQwR;r5& z3%`x<0s#wjZoa+%;J|`y&XcFCaoVXW87D2)kV!)J6TSG5uo-LN+x#W!b@s6DKy{PD z)E^$dJJy@I$Au)T%7J9|IvB5C$KoHhW_Qb7{6J3&NTk1HOVFGIx|E6mfYHQ5NXuJ) z4oFtls+{YNXgoFmkT)D9F_fgJFXm;fRM=%zA|)U)x4$Wx7^C$Gd3iNV{z<^0f)sF1 z=NKyCB-o{Ke)-1hnut=ne5I$K;i`R=pho7YM%@26&ToFmeqxkdb4Ty=$#vP}p}^1m zg176>*OJvC9oOmQ#d>j$x`(Ot#uS4q123;~wybL>RS9A*;I*cfLrL?FUCRW$gY{DD zlr->9B%8LLdI>Sd%;8#_^$g?cPH=Hxz&))2iWH6$7vZFzbD6%$UiK4jH#Y zj&`zXA8^#yfYRZQ(AzXL5E$o|8ATNnplN#fHx`A6EfCgZ_mPhpDDi{jzX7%<*V{9U zix@+f*5%jHoXIz?y8npJwvh)9(RGo(W5X%l6($ALhIbGgofpQtD$ooS+Xyz2fZ(o# zO2!F{94%@}!~T9?Wx7*P3PxM-@8+aNOoaL3Vp{(#hy`LbzZ1wTg6Dm#ZGgF+Qp#T~ zR7P>=#C)TaP#n*>5kosp6NaK>Y|h_tX?L^M z#zcz+zGCEYTL*o#geyAB^o-&PJYJGp8FN3hKaXRdc;baEVO^-W!9a7xmE1+}55FQ> zddj!GSV=Om_I7z-(Y?L8furAuZM08rj6~h(;^LUGrl(u(x1v+Pu60*84$Y(3Y{Qhw zzCH0TJ0Ee)Ukgm>_-$i+cu~jDhH%qC=MxIZjyM-46+dUXpC^jNe59mUWNEYLx@3(?Si0LV*pawj_zs~9U$LQ06FWSs zo0>loNN^hQ?WKUJj2(3(RW; zj@L~a{-*{Uy=`t!S!OverZYohSXS7hTPxu(cDN0)5V)q;vUd{N1@Gx8M+cmvm z0g2StHj^1S3wC*nFhYLUvyf!3?-)!y)ZYG@u!DCyF(NXBRbictD>%|@g2ZkyTkv*GKQZG-bMfrndMFA_Xz*hyk&*<-?lyrxwEYDIE^eR&r-N&aI zKIHLt?K7|5W!5b0_E=se@RhYsJ#pi3_d?R1j98jcST1p%KUB;V zGc!hsbhyv(f1w{#XhLwhL!nV#Zi_w>nDK{U&gZ^&m}{nNK;!bK$|oPQ-evk5Q1^!D z1XrVzLYh^xI$Jls#Qj>9+Bn{TK`}f-LAR6D7(1(+Fta@^h33JYA!MB}O85G>@?$`C zK@m$F?{kFFsDiDMIr~W6H6fO}ABaCQZZgOPB5-99bvn4Xv3LV4qVUf)E;>Y}xmerlmc zBR^EIR_T=@O6mScvzFbq)%MY9(0qx7yLz$Q$_&x37s*I^GjFJZ-)6p?>^VosouroA z13LA)Oiq+PM>F5!NdqQCywY|0kky+{mendrQ@f&~T_IKaJQZhYw!;fpMimiVX`CT>6ZzRYo zSo?Y}LfjCTo*p`;SAVp25|%XX&z%)gHaF!x%{E(w^gE@_@ICeRVP{jfUSvTs{RaNn zzbSp}*iyd_IqQ)^xR7=5dz!0h8#=6qnER31Iq+f}jCJl67L$_dt4R~JNeMo#u4n8i zaed(@pHW$2uvFAr}VmcHG&E5;pwoI=N`Q zn(}BSUSvc?oAt6Hx5GU@^K$n6gq+PaoZgF;xHTA!C(dwfyNaeu_BvTjS9*MbHZxXi zuna3!oiX~(JlYS5c<8O%?Hb*tpgIn9$Ri2D7ZDd&gY)H zh9+TMiQoNlRGR&OfcNG4U8g*3wHB+yJ5Dj;!}iun+;u}Re8ljhoAR*yOC{`yB7yr01x1( zK^@P$dhdcLRg-FLNkzuJH9{eC5Jgh>OzqT{X6~soG7#~_I*8U87AJvN|Gm{sUMQ0? zKwt}5F{qc?USe7UM_xpd&T0R3M9@P5RzIdx7@ciH zc!Cz&yNOLR4!bA{8;p%3LhY(xq^OqRkivdSUmCxPD|oCeSVj1}EpidxJdI8^J=IN9 ze5;F#TW!<~^M@~u8lTPHhr9kAck|m=mRuuxlr)*bWLI&4{oHPW=vUSpU4&VN*vqYY zjLvAOhVie}IVSuj@Xe7mL)JQ`P~3m?3o$8p+>+M=yxa56a1!#UH1Sb+d1Xw~GsN3I zJKySiDUII@6LbsW`l_Ou+yT4J+8GpyVOmzxbdE}E$kVymYRN0U$w? z!mKX)411&G!emj=?D9Q27VPW z_P51Q;ivIemcumv-~xq!{lXXK7g)z8=K?o0uf~(N(AS%M)Uh6E9-APL8^M#+qQbM3%|c%mW0RnD>#K8j#>q1x?)4lY;so0jqI;$3;f+fHfc z$(Fze3f4ql?rYPuVePBYeC1JRr0hF8^dbjq1(LXKh1vYaWJOV8oxw9qdivOKO@=>* zwUcxm0)N6-3(aAoZXqGG$+xuYZTX0dF1zay{3FR?@#|17v&SS){a zb*?Z|aWip1lh7-YaeEr~d#LrNzz$BnfE>=9E3X*#01>6BS`QEA|3lEGtfpe1AIOghX>DR2qFiD6iN3} zsa7Su{fvBO$7+KCV^JRV`7pZ9>p@(a${H|LVBpM?fz{ zq7mIORcY;T*jJw|=@%l3Mi&cSgb}Saq#-Qmr~Ev9^sJrjBoj>eCdXZg!TcMONx;WB zu}>YISf99QpJnbT2ahXzKeFvnQaDY29Z3H~GsVuFOjlx+<$o!+{>$k%RN&7d)#Pry zAKKNH2S% zq>UmyUfou>be;3)X!&aSqY zRB8?RuVfwbgYjIh_9B9)ezIb5p4@OzFpL(4ng-2?)zPv6i)vKUab4ue&Njo^C7SFY zSucDNM|^xL$XCudOC6FWdodDpcbG^UACJ7v<3I7iMMldtHM|9@*5Ni8<{d@TG&4P} zunqkfPTl!Xhk2i}@nT>Z%O9%}rq=UeT#$}< z1Ig|?Cl0d4n>H9@kNQ&u*`_hS%+=TQT7EAd$stWe6OXIgyV~!Z`%qQ5wFgQobbIjQLAc!Ft%>4Ou*wKkFn?ky5K9_vM$pYK4_04jk`>_k$^ zedpV6ck~GL*2^Dkc@TpkV=X$8b7L(DLfFVIC=Y<^MK70;B-^{!ftEpJk}=L3@kdMV zUZC+kV(&AcJv(q<3;=FDw zPeJE-_L$s>obm3nl*JCSHE*bYwXc)9$jS9)*5-}d*^=vB!YPz%%6E@ll>mXUpx2HVx8ryzw*oGyhdwNwoq8N6U*1uCT649Z+2 zn)s8y3RyUaR8jFR1Hm%q+jwzT^3_bhi(3u8BeqP&gM~_?g6Sg{VoC@{2G@ycCx@@@ z*FES7jm$>(F5kiLP=!F$5Ba<(wKs+Y7{o_quqDyATYm&} z3CQZ-J=H6S+wuHUhe-V>m?hx2i|FdKF15Ps7#ULQgxEW=L&a|Df8^3s%nkzY{mjOYx=aO zx`df>*|^^Ah&;C*B<~L!D%Ra8C+mmpNqu|X`rk8mjx&=%5s0sgIe$VLh+}&Z>iM@r zP*fMa+xYYNmZl+gvGlhKRy@sajT?tPms-o$5b^eF4+$jdfR*~N^weQ~NLrOsq_A0) zQ}jJc{0&kRIL^plm|8!GzwlOOp^$hAbAQoz&1g;2Kccht!QIO*HQi|g#4B3xRwmo! z+wXem3D)m$7aP%igJvTdn=w<$;c|}KPncJoC&6x8A6s2bdiGWglzUQq(n6ztP*N^9 zB~6CV#jdcUgDO>i1GHO7YoTcd<;J1tJJEA8(hB*MoiiM39!k1Pr5sPmwYp~V$q<}B zF}=Z5;ele1i#dHUWr-C41g9@NE=kfPqT z+)=|E8gO{`-Z52`6>jU%4HE^PW&m3pKDDuBiB8GILR&`G4fZAiwcyI_8afXjeNKh* z8n|v}4p%`&?$f@DFWi)UqmFAcPGbRM>7sMW2c1Wij#3pOi@eOP{$osNW3+_(-WjV7 z!#m1WU58_UPgwY@6)hsHsObsr*4QPq_1WIU0Jg50MbB~Yu z89gsM2FBR*jQU1mpDGl-B^W8)#br*Jzyl5BgvkoqGAMvbdc_eonX~un8sjPl; z6X(7m#C)a-c`gr}L4}3cdMc*qxzU;fwPiSR`qm)NPGV^A-%$ex0+jpoIcbV$hr6E^ zw_1P16_$(kXgLz(W9s7?DGSlFeYIKO@o%F!=urr;1)Q+odv6%<>BvLArv+FQdLN8k zWlZr|4U>Z)oju@ctmv|-*v}in2$ubbq@wkzo(-u@tjphN zVJF|=FS#eJK+hXh(teaHbX{h6xHfId&1Libt-N)5Ope8Y&HCPx{1I^l=-%&+ThGvy{7_6KD&M0tb6+sVM_UBeZQ{Un{C;v-IYr|Gs!?vfk*?wyv9Df+B&;N z z=>IbvbB=E&kam7p>XT+OmR>Vb0TRLg?So0 zrDiX&v$`C83s65APm&m>-J0c~&TLA6ACK}6uO}Q}WSU3LL1|i~&|aS6Zh`H`CFe{&%g2POwLe#8Jx# z|0d0HvA5b#$N7%lQoRNHF~6o`Ph#Hn+gN(nI$aK%=sWrY*|Re0$UyP_^@-LQWKZC7 zuyCN75;{VZ2)3vmX8eLxxJBIP-_a44m%QsM|D)43|FYdjz27l}+vl>rn9uf(mdhnr z4)h;pCg_<^dw|mDgA&_QzNkE~KYN=mUf#vd|yBcfz7I6x@-X0;ILYobAEwbi!)H;c^Q07c%H(?FGA&UfKx@iYH9?!%!5jP9dS?*oPPAv$zyZlHtpsb{iQJrz@1w< z3jE~%FJ>~h3B39ssTCBfO2&gJkq%Ra7s;M$P}QNJ2o68u;_R8!Bqx9;aO%}U$9)Qw7a$wZyhav6$6~d zoJajJ1TY2m^HF;4=;6uY`q})q?uzT6SWI|zktgaK6ddTPHjncWJAqS%4t)vm_XzD? zG*rLZ>|(@P&`*cmiDMGKCfulKnWZ#N3|(&ho{L}Qplf^VuGb-HqZeTI#wMrx6$I>R zUBr2h#FbzXDzb|eOCAmJ7P1==>sOS&O@KcZ zXF#yb{?@P^p_YUGLLkk=6^n2`LT}*a3&HssGTDTzsA;?_qnIZG9&73=Jesu+0Wz(b zL*l-GOM8lW`WE%()%3mGmfL2J)HSV_%PQV#!z$>Nn&u{53yE~#POy*Dpbpma!>8NE zRsGwwy8)bnIXrQjAEKOD0nk>hcgqFkxT_`pVppmeRr6o2*76Gz`aToi^RN1a*O}Uo zBJgWZfas-e|E-6psGR+&o!e2oxOo}EXIBfz^O+RZWaSwmkNt-1I zi-$Wqj(HlnQ_9O$P`DOeEbMJpDPtPs0e0PVgzou*G$`zsj^(ilxU$!p&B*p~v(?*{q^GKMl^icQJv7z8 z=|RK5b6vr}H0f|#G2F2s_7PZ>>y*u99qI1*pv2c|ksHSN`?%%(kSTH~W>44e@fO|Yl?Tp%9M*)%2ZEJENei;v*K&etb<)4C9dkblY)Y5X z%cC6cHs632dNW)3E5_+6YF9Te1Ds)wJ#3i*v)1pToBz&>nRZp`dJsaNRRZ0!FMp_X zdqlJNO;^3)TV+_}DOWZX1YTkg`yf@ck0J+K{og^O2_(eh@K;y3Okn`9EgMORM@0IX zxOep+GxGB$58($TTx+6`?Gohx#-5>yRZxHE{w;d=wO&E6Hdk3dr&93jPhzCLSq z9kn3k+F3ZO9nLZ*O-bjbDiXQsHS+mFBWX|F?KFCv=CfSc?w;I&)F`t0H$cr*oi^eL zZ4~*GD#s)5VwW1k>TRfN3&GF5nKp<+yL?6HB$iEo9NzX>xR>!U)8QgI+Vy#9GBFZI zY?Wd#WMIaBSTOX{i3aWR7I*mbO5xo~f%_0zBNaO{JD68AGo{dF$bDB5emsr7{l1c6 zNxYKcG3B*II@h=Wa#9nya8-zy8gR*506oF-kCf4gjxIm^d}y%`TZGD~NZQjpg3Gus zMJ$5E>pwLSOyT|-W6ooYuj~f zbMT16RJ7u0H1J;ANt)yj*SsTEXtoy@nnWpe!9th(JpbnBa3U$U&N@D77Ly zqG{HY2Z=4ib7#>sf_^yPX_djfziNSRolhzuP+KcE-FUQUKZbSv4*Ml#oH&tv({~r; zQq{a4&4qL{pvdbT(wVL(I4o@m&dRjM(>o!earKRcp z*;wNHGVkqYxkDk{Q}$owx_uHnPuXMK$vso;dBoar-FN$fT~4~CMM;R?`dyq*rlfwSnPi#GwlwvNcz8Yvc5*dHWYrG>QXi^0sS+H~tmC1|yIK*D&IfCk4Ga)(WE zn5bST^&vX#H{};F?mzjN-4uygw%0!U5N~)oR=8Ce`;s@M4BF~kShCBA zw}ksqMp0~0&^I2^SGXvBwCIq;gs#Qhp=S*W^H`2J?zT!yGe`EqwQxXkUk=*nk4dWW zwIS3bHQU0Nhu3CFm1rY|qOLA9vC9P22n(eg-9oTgr(=c+o`>_P^9Yc!(J}wJm~Z`m)w>1NQ4Ky4`F! zIxl;kAWH>y^>wE_c@0i6dvHEgvc*dIuk!|z4MY*O9R4&6Z4n6btKHfst>j(L#-uzK ze=53?c38m?(n8um{)N%DnIl&ptEUy+MgnDU0-9>G^W8>ss(5;%`?($vUZei~Xi0{x zzNheh#aqgECdwzzvO~1WJaCW5V|jLP|B1_RClIy4KK+qve*# zI1%7{lXMv7U~W=P8%r<}(u4z&s%?cY`{Xl!U#7S3#n$busSO6g8rxLLbn{mZ&nFP+6<>hG^)NYuZ{)6`TK`#-4@%a)s!1`W(<8@r{Zd?cnM zv|cD5^xIysK;$35eL87X4m(^oM6-rz{S+fUejPjg#r4dBfb*8x*)c5ujBtyg>A!M7 z*Yh$#w>^s`8F&XzR{J91AGv1vS_k&p*w9}3gD&@)>hSewkAYeag(gMXdkP4yUEljc z&C*3$#en-3>nOsky^ubU+<_aQo|=E8#<(0yKwW7pfO9qh4t6~$6hR_KLWlLMN5$7` zJ+)^yiV%v3Co}3BSu}yU7UD&4H$&lW$brCR@P~Hpf27nxmi25DmeJ~Hj+mmqy2h$8 z%jh4J>}?-11$Dia{C!LqfAifX`!UNhj1=riVgTi(H~G6l2^BC?_K#hKD@bK7uGwf1G@G_s?dhKgV$)n`CF2S6a0GzN6 z_`Hp&8TydK?SMFqf^!j|5Y~*j^qjNdCyKIkQN;1_#5XXGaplhMY|z?KWRRj9M$|#bf7a_zf_?n%RD+^wB4V#`z842!Q`Pr$#z{ED8cj_O8;toR@mwKuRTN&Hkd=gOnhVX6+wW*!goJ84qfW zSvco~pAq<@aNfJO{Ps(Fm|wKMvv91boShjJAfW*au>qDJiR=IlK-&j8s_iXBqCaY< zj{4HeQ@?I(8i9X5FYWCgh+OyhsA{o%F4_0ymB9I*rVJqfQ5-uzkX5ok-$B&k9@JH5 z5tGj1(JwRTiBo}IFjz<~7&)_;=9{P{9doVZ`_bww9F>l|U?)P%iy9`em^RYGUOTRV zgKw|2oPIKte4Pth$|Rfu<92P!W_e%BTGSg8Gv5DhREm|@c!ME>0&tU#R{ypu1@m(~ z`yNaiPh}{YMl+@T*~U2fm#tfHjtH?ut6X~5uils6s9sEctR^9uWNEjUl_5>+H)N5K z$=|;ZB$qlo44{8=-8fV}h%)cM%kD%f5rDGqB+(^_id0`Z@BP&760h=o_hY!;Ql$7C z$x(!}LPaCy6t~ksP=GnQF;Sl#;dsMbFd zTmOx=37X!3|63une#8D2Pa`6ctGbWrG!ghZ^@CGxanwN0EG-|lc{our=JdIPV4QsR zNUfJhG56}KEn7XuDD_`#(P7F<@%5h6J|7l#9bwm7)QIlvA9&@p|MddsXViy}^AEbp zx@AecZ(&gbG!pXfDuv%4lctvv@{T4GND~EqYYfKbAM(wO_gyjYlM0UW5K8TK6n`DQ zxq11nuHEP{*z?Dln+3k30vaFw$2{6VDvNV#2imEF*4V}*REq~!ky*^2@<_|6A_J#gfekf&B6L5ANvrCq|^%7Z!ODutkw0Hqv&cFEq~ zSezAgO})u^jdERvi9L~ujHO>%K9UB0pd%{CdoLkUDRSG6YDpMa zIJ(dD^RK*bxX_TU?fWGV%BHv&+vUZ<)T50#VEdD#!s+}kP(rMlY)=LKZ;qK`k%Ih(%sSxA{{QB!qVN{EhXLE%hDhvEg%g`cS?7MEG6At58wJ-&kH!` zkNHgAGjospntnx-BD*S|5T{+`hbzr?6MEYA4>Wt0xxNWi|AAZqop&JtFXO^F`y~7C z|Ftz&iYoPov@DoO=vZ9`%F$bFAjt!TCn6SRb({0x;$9syl_n;eE%VTPVf11e`+fg9 zew*Evd-Z^S-N9$xtx6ZcUIXQQuJ%7u(rega^vd1ZI2S)_J43R3oGcorG&YlIge3n-Yn>i8j&R7?JumZb6Xf3$S<>UP`OlS^Li3DO}Qa(}n@M z&!n@H#5-!@XsOeQXwW>9Bqz&a+;Lo|@dt8ors_sbIW9`d`g_+IGl@9iwqE$j!tWi0 zq&Kse^jrGL@J#7u`eTnXMOOi-eEfqC6Lu*n+IcCy_i3w+!E0P4n(|ah5e1?g zO~I?UOe)%NScrU9&+iH<)SN@wwcO-3S~WN12&u-God;yEM~yWA()doguhQYFeFh3 z{&h@fh4OWt0MJG)OnU7=r5T*eZcaIM>LHJx*LS|Hf(%A3CB~MFgkHX$G0!gk`su?H zOyOuU5bXEzWbyJievB?~i8UAHEKV{%eIXRc$k(2p=TjU|LAF$(|XF zJAk!GYKqCdDw0hFB?nbZ zK((+1pd!tDgWT6xPL<~=M5*s=Ug@G1Xd^3i=V5BOJuz^}Jz$iw678Cf{VOxzcJ-ux zEw0u$Sdew)S>9;~de(Uf7s^h|lyMX5bD&#YY08+%6KE+&5)%E>1pC8}&S z(f%gyEaqPRgu+6Z3uXpdnZ~3O>uzn$OUJ!2^WP*+sd&Va`hjpHgtLQm;)Vy&L{BfW zf80|EPczF+)`=Og@cNat(6!0-O<%c$hZjb|y1m3VLLvJy!GS5X@MzhRIW3;k5T4?uS9G69v5?ywXyhif@9tKQhsKM87`HH(c zQB~xs`j~WSCCaI7d6#W?xwU$&QsJ<^kk8-o()PYYqiDk6oA_4mN4DH@($6zkWIqUw%48{wuSeeWQ8K^& zReUB_mA+Qdr~42=cw*R&Cbfi&oZ-tb?tZ>qY5IvUYeK*$LT9;Z^f06G+dMK7#RzY- zCxMy-wc6%>$@&P!FG`k_8}KS2B>Q^|MMl5Re6tO{dlofi(7@FPcccHOBn#BDM7v8m~J3E}g!`PvbTJPAvopba%zXqdT-3+f!6f)kM5A3KpG6FL|R}*oLVtWky-$WruV~ z(R0b#Sd+unTchqAg4aFhU_mW?7);eW&*)q6SU|RG?K-PIr?W*Q=BM<~JeSB?Yqgd# z&H9sihMk2FXXXN7$W$Rg;PH@X369Rsr}$`v$omBK#OUtOlAC*{6Ob7QBeP=TJzebMnMfkW~v0%X3D)_%nOW`O{CUx zxV#GbFV~?!06XeElU<<`<^%UH8(bG6O~Qp4k;pL{`6tM1Ye)7VKWybsN*%qm&ygwg zsh9?Xgw`@!XxtI{)jpLZ@i5_aqW6QTEl|rIl|BN>Z5?$?Dp_Ct{Yf0)$7Qh2zOb~D zm+h~gZ=QSi#2teNy*7|IMudPL3rMMCNkWomox3~X9ey4uiAkUh3DZ#KXBnJJ=S-zu zifel6heh;heb3_G-g*mD{AGqa9gt^4|GkPFt1r=ytVAXioYd}Gw%8r|UVwHeM2me> zkXBo|7r&zeLi@DS$4p+#a;S1-nKQp2bh>VDIS0>fiQRyB` zq#3u_9#*axT8*=^LISCUt>O5y`Rj^qe@XK=?^EiwJ|hvYyb(0@--y0;J~O`Iqg!7v z9ne`mRa~x|YL`rH+}l*6Trh>GX~#00pH(U43+6hzj+m$WFtq^_o6$TZ*hN5JK7&J_fd=9tXDR(cCe77K2X=TC#gHrW$m z&5Wt7l%8PTLFjNS#V;AR{+Rpq(sof)m|z8G3AjNf_^%n6zL<0R&LivF2%j9Ux)TY2 zc}^7VnnS7B47NjrMmwFl&JqOsG96S}Mn?Wkx@Aw{?12uciRfqH5KN5>N0;KNz!>k1 zXum#^vt1{wHdX3G_hq0KG@knW+%)R!)u2sFE9&ICs$a7;Q$w{aqpVHvCLAh}ZVb_B zTol8iYPMW2bh{ud`Qc3v!GS8~-xf9bMTI)7jZ&zE<3&ORA0{E)&Q zzh2At!B!eS2o9DU89qqlJonGe#Nb~{BRv6~((#y5gsPY@V>G$J1?PxwCGe*3Xm#}X zsZ5M|FWe!N<{k36qy@5EidK|C%C>eHtHqALe#Boz&QT`2N)*VSt27b7b`GLQ)otQm zaUX3el8h{*GKGVv-~-BXu)eE@3!befQ-dU`0pDAJ(ZEp6TE3+ih9D*J>2#t!dn5e7m`@sq^a+bjaCu z++v%KWlRF-7Ew=%My`I=+tK-w!)ThXo5r-V_B9fIXGb(+Q#vB@uJ~QXb2@iiT=RpW z&Jak_#qo%=F|$_NJZHY(ksg?30(7 zrtTRJYW1Lhn?h6BD|EhG4bSaQc^_eic`JcXxq9Z9Vuv$O8La7&R+&Fg&3i7O@2MmO z67(X;g^!1ugp-2|ev-U6duxTlBlzWQtyT_tHeOb=c!Tj*CpH)1bG;O&*nM_Tl*k5y8Qs1{j z*Lx?r|4xt`H>j#q3#O4MQ}r!)+$)G=LlPR3XT`oeJ#*Gynk6ivuf&EGI9U_X-hf$; z9mRuueaf@(9-16C75Ki)8`$y~izO>{&hsfW++B-*p@fW7of@~>b$1QpXtD;0_-IQ} zFh*92hX_{Bme!8lhpH)s;Vd?PWhdt7Jq#C)@kM$UPqQ|MBfWHZz-h3zJRGm~W7?_d z3_Yr>lIP+1rZD?)mN8zUoj97?FCx~D`DAFOc6YuJl6B-v%DQ@_n868kO!x=g z4~02cf`I485%OM?eiSH8yF$BY_K44VjhR4=1b~R)B`vcSeFL)v|M$17qYy}(RmR!t z!taC@Jjl9JA&q_Zr%~8b?m|{_@~q#()y>Y*_v%giMu?u(oz25z+w|eY%v+69uRuYe z3rTN}ZlJEl(BRKH0!y^|5)|~MkpcYWVOjFp;J7tQ&TPgi%*weNJ>ZR%#PfLhQ~?qB=>Kt*L_VqmfaNU&LC!k z<`v278NK!)aflzI)VDG1v$`hL-38}a+pe#*M5Xgk=5}Tlokx1j58FcgTFNE!4C;f! z+cV^4GoE&BZQg3j$-0Nj;wM#2ywgXF$#d{8{hOsYtI|43*6%-dsUV?fmOl3(I zK`icl)fqyj%-%N8BSbf}TpV{jV?PtD4Zr0CX#Z-0;(3;!=Ihku>z3LIJ(@zauVXhL zytoXMakS6Vujln`lpi~XnRPAM2Nz!1^^!|uMzdCwrUtPB^W(5%pT&Nf2~Y!}i1s6= zGLnn9dZR4!_`Xghna`Fa@#w;m!tO^lZsUR$ih_lfj!Vr%l1q56D#HN(flK6J-J^K) zy*%OUcY=+8|H6cGhA)ve^oq0$MK(SWwr5PSYP*z z@5uCMou?}d6Ws>Miz{c;YDM+$mwyL7m75m1eaGz|EzT0$RybHMY>6Gp zu^$(Nbb2{)lp6CQr}#ylWw{rL&!xH>ERVql^3IrwM{0e=aVTYzpI{10ztl*ra;?7Q%*|I}k1D_}+h zcUmG~DK%O9`tdG>C1^Mr`;|150ufW9DA!G{R%z<d=NQ*YWHE{hO zeiH0yI%=0lr?FlhPBscZ%y!T#FRy{cFLF99XXPe2kCkktqufVA zDWZD`N0is~1=%`s>Kymv3URTf7b)Wr3JO-ok|EiR^r2zDCtEa?Sd~cGwI7Nl*Y47T z!zYyv(z?@Ih%}fkL)(Ic6Ucf~;bjO;on0s}7(YffmLw4eCkY&CXh3!Qi_?dnI@oWr z)4ldFff=uz^Kl}3na;{xaAqu7y=3_`bV8kfa`O?m#~JVFc1h1IV!KAbBZmLD1THFv}9 z!*NwCh-s4+?umHn)?-RTXeDDD z4(#}>nweitytz3QlP%n2HCkv+s3Sk;IMybCexR|s@3yLnwm+7YrV6`(1-m|r{nh{e z{ti~}5itod>4gdSZnG{n6 z66sLjoTdiV-s`lP>J7PyHw|;|$ImJd(P}I_is`IvJ(Y{_y`Hs+`=|4rn$M-1O6KpB z>uoEXde0XPpN8Jq;uupOH6M(4U9zcaeY)z)!Rz3eItax~O`TG)9NDZGw*SQ9lR+pR zLOShDtz&x)?0@Abg}|e=!}jdDEDoUJ^d_Od&g8{V%uv$Zp&%0oXKR*m+nRXpQRTG$ zK$+hvu#LInNyJdlP8$7*J;--pKrva$IRpj#pMc>y=PNg`FIVrtFJ&5#`{Zfg z|DaPbqtKg$@3$lERLv7&fNY8^`lD@1r9lmfQ(g_xG~Z@)GSO~-Ilvb6$!s1fdhy8# zUKZkA2u3pnRXeMtJv(hmwtU@@qX)6kMQ)zLa*{bfl|_sPJU@sVM<{&8&hoO(@cSyM zcPbBKnnUxERSq7sN0Pv4mnlDS7$tQD*gJk}F-@?Z=Ttw6L|)fiXVl&sujk!rR37`M zB3~qKWkv80h>#+^$t`^j`IB`ox`a%!I$0%qFb$;Vg(}@_erV98EV$ILDroRN#GSmZ&6|CE-;vFe^g;Oaq1H#e*Dx+z zaA_pOzVdvPalOLl#$nlFAcZ+v5Sq_McCl!vVlt5JzlJVLa^`+eU$&1$GH1&PbV#~A zX8^hPat?)U@o7FkxK4IR`5G2|ji8FaNJ3&%sDnd}*xA0I9B=zpcvb;VkaEJvdVb~^ zZ|Fh@8(B&1x=6kLq4hEdl3c#f&LF%|ywYohG;-SvPHdB3NW8nabE6%*J1y(8GaqyF?y*lq zuf|O_q-DF7HlhFz+pM1uS!vPSx~MvT{Q0uE8`EHEF%?~yS%7SB^(f_aT1@$Q)Qk53nMto{feyWCJ_~~|xSlv)6L!Bd-V0$!?cuq$ ztXyt)FweZ!zLNq8_c^pg;@eeB`HD)Z`?o5mp=Nz{N$cXpn9ocrclD=>4$G&L`S!mc zT5H87MeQlmE@@bgQkxgfd7T z-fP7UQvQYe{b=66`ToClz#ABg_c2O>tFo9)D8sVa{+HCXEyq(R^faM=uuxGsI3$D& z+dpTQirO{cXonQ`q%fzHr`lOqktPI-bhnk8-3;RTNXFiLt;>IEbqOtmSbGxBUg4Gd zOC03oR{NIgW?b!2?|j@JAr-z66FO3DT{@N%hkx3H2mAGXEs(FPovbBKs?%VaBnx3C zL)dGyO_iTJr{g6!W|504tD9`r*}sRW5e6QQ&d)nM6w=rEWzYt}7NoTP(dsrkFIwW&fDH(6?bIagpWim-uOdq>FZm9Ei(~md0b_0xikA0rtt` z55$$HakePNq0Y^~DyuW6(9?zZkx@ID1dy*!!Yv0gCl;S$dtUECIqfr7A9>Mj677&x zmWRYa81W3&eq<2rCT)v=n0gK+9~Hxt;blp!&Xg02(IZ7oU@f_n@HF2p8AuAs_O4M% zA=}#fT1$3`igN7v`DFC@Xr0Rl)Yxt!H^CYsST#0#wj}1-Ae}hEg;Q9usXiI3--*aZ z_E^2@KjT4c8~t-xvtOHFe&_O*A2?M$EPu!2^62a3x$oFuc^PuXr&!S-*DD>{txJ9z zD>&(SlMjdP7rX*`3os@Lh67w`8n>=jU zyr2NsA<$1K$Nu28zu@@p1sN;3P|hO4JHW|6>+YKOv9{r^@9}Q?+Rcg!t752rLEY}g z??q7tm+;QgfKt8`^eSSq45L(3B75q8r{qhHsLV{?MI^Hf%ffB0GAv#&9OTn-Ivwts;%mi z+U>QU!_BS-$1^;|t%bx{uwN?jCE%~w;30pk^>}UZxkTRc2{m8%`6o$!{(VBl)|PBa zV9l@Jg6wrYqyLKO7Tr8u82D62iHL4dkgx(-6BWiqoxj@f-}w){h=fkKtmKOxQZyod z`T-`(#*h1H?iZ!QWNa)|(aWzFTbslw?}VYU0zudlRy=<>C#W{Cau{k7fBNB{4o!CU zwZtFU6)N`Dj}1TZ(~L1l63SvNs9=yKLPk%xn+_P!!M1rnf)NR=e*b8GLyllsW~9ZSLyjSm*m`@zAs(E(9#7gQs(4kq&O~JIll{P z*u%@rug7qrWIe3TpSj4ZVA!oD-l5`mV|?18M&ym(<&}X*xd>Sw^k< zg@Xr3KBS!5)gA4(U?}qvK;$9%=!E(+!H+|B$t6i4g<#H#lGLn1t+s8*z;BVK&=S^l zI02+hPp+ajw4(WN=Ys}}=05jQ*BYjk{f2^v5su7Lmy=W@gDx;JRG%_ZG;fIUl-lGM zlc)B}KdHSK^hf-V0zkdM;m0*hXC>M6JCYNQl__3XC3s`F<<-5m%FLYm-x-vhDXQc+C-<2~H=c9bUFlaX zm@(TvchL3q>3Qn$*fN9p5AX6e?PnODR00ojAY|V@2Z?WX!^G_CAXZjeMFDdS$`@H4 zbZGkebd;5~$LpF1(E@b$Ztea9%5coVks0t zVBjlS>C&AlBPByDu60sS%+Z}s3QPy};JDD6lTcfma7hl3&u-WRNpMAPT{7Tn7iZ0! zD3|;&bKE)&$#LaE){N}7DUUogM{BPL45nc=f~a|34~n)Xz%Ng8^||@-sSZNM?ElhgYRtz^pZ?i0PLp26)#9=c9fv zZC&KJ8^IY?Jw&>dK{B3>)1Tzla~SpIkY>wnR`D3@I3MYP)WS+Ixn1JcZlDfp+HY25 z^y!j(6Zhe}@Upc}KxO!b;~<^CN_v|stgb04`47+D z0WeQvTHlzDSl;UHV?aV$&^ERh@X~FYUV){9`|X1%uwN4{rQ&HG+V=ahIv6R`jdTx2 z1{nz>1bF0HzBkC*xcU~Uabz~BIowPAb?e`WXl}yaDv$4L%I+f4ZbX3R6p`znc{D@% zlTAhm%hY4lPQLjt#Ol_j=}H*gNPIt&+B=RE|LH10L4}EBb&V*J{jMYhfI~qGj+jCt zhGcXr0L5ig8KGn9mHy{R%MzDaT?uz5a(`Z zBV@0toK}Uc^Vta$fYZ2=mCp)j03!PV3amIyqv}?CHn#XBzu`hZCejUfc>BKnA%_h5 zJ!;t^oXvpK(q&w$C8G^6VZay)cL}U<9qB zIt{ll?f+piJTj1*r-lSDp`Rhm=&Hcnk5;nW@4G@Kku7At`bK<Cdj+p43#xiek}=3pJq+PN$o=%DX^(x7Ts$s=n_OcP+}NU z-MjZ@(N*s^F$?C1DE%nu;%=^x})j=j0ne62I8((QczvzvV|{ z7Zd8eYW*R+_ba;bumwz@P%$oDEE|`2Y*$jQ+Iz6=5r{Pe$Zz}OUwauIR2Bj;aWbk^ zLB@h}=>PM6PqR?EE52GrX6=wOEd4G}-gI~5lrTk^?uuXXDNZ%e&v=DH!SUxL0wOxN zwtEfXCG5j!xGRvips;eqI9H!Zw`uB}%tvXuhHRS+cwRK=v;l7~QT>+WV^V{djQ_O8 zzC5A%Mnun^sP|wTS4c31CmW=zEGx+kC)F!{z{ol&LgWdHp{@e%-QwaD!{1(%f&li{ zdb6IBiO1hh7JEvHDtquj!H0r|1(RnGrTZ=n z`QYQFIvpnGJ_x@Ozuf!rY~~wPJGitPOQx3yRyw?Z!!!^g3ZPUn5;FjcgGwrKIDsaS z76~G6vR1@~9tHL&ocYDGHCluVf@HM#!zwYXEl>`MtKOkRZx|H0AeTFz;?^`$)Y{(G zeT*InLP5vtlk)p0s6AAM!i+A!mb}{=sqx*z2d1!@Td0+QvKUjTs;dIgy%?dfNQQ$r z_eopDk;W%|#y*sbVJn3=dZZQb&h$J;M3}Y^gEi$C9eVW23mH7ag)V@mfX>#>)Af%2 zoyYFCx9}_rfIY{&x>TrIS8l*4dZI7h@ztgmkFACp0o2w30$_nD}wGAIIq z-%P=H1_49?6nvN@KsXvWY`95UbQ*{dbZdOxEr7&R%lCX(4vrGa$nF|WQ>_7H@(nBw zZP!tzGJz0D1pwb41y*@_x0gKS$WrQKN>AY+P>#uzY`*ywQXo3$NEL`B?4E5Ib_u;MZA?z-ULY>^1Goqzk zuJlT6a`R%nyi+1MC=Mh zfab46cA4z0t}Da`mPC#()o{?)3#;?MXqWJ686O8YH$Mn2Nu*(a%m*Rkm6u(oZf`yj0%)ngIfokR8glvz3z%VWibP%3?#~D=Rh67 zdym$$cj+LJM_&~kI}3q4G$hoO5@al&Vm%Fe2mfj4fNu1aS^5}$I41S0p^+_Ef2iR3 zGQD{Ii+WB~4&zqh2+F`O&X#l+np$~RUInO{Dqn*=)EEcx8fnMMwepf?`h!iUk0dvM zQ|OQ4J)U>2qVI~M@0l&i7-~P7@1SReun!Nw&~SXH!=I^?tjf6e80`1 zE7L|%*eWKHg=r8TLh)OG zlelKEmWSS&^T`NgUS_&TNmW!*c|Pu+mz1!KZa-4hH{^flv9#_P3CS`dU%R#g>~yb8 z-_A|nJGttTdjmQMgY{SmEdf$hq9jBBu9bAr7gGlW8O?pyMvaaK{WO?*m4V)2H*x9r z=T`?wai&9(3nn)PCw7pFw^uOeg#DJr!J->9Py_qid`_R3@ck1_|lYbVW7ZwH8KZsdGvB8d(>cboskk$1A=L zk`QUmq3^nzaJEn>yE0NI@B3JBh|WQtNydxp4RiucH2o$qPJzv<+Mg<*;y!-K3Z!-m zdNN8ye2Dqn)>_lk*p(jG#vVqfS#F+cIEhc(&nR^Z+|!@3gYpb}NIHHs8*}_+cQM)B z77i^>FquDgG(K!EcU2zZb_rPoJ{+X^?CFwx*T`dvG+187dy+g;{#RZ`H=il^fNtyU z(cE#b+IVdOp9wS*a&iSewvvBpU2j)h8yKV}3XKTg+*G%A6>I4V z5pWU^`SZBPy*Egl@VPzHGN+MWy!8t}%EJa@BcE(0&`Vh{f?jweL|Hh(C^W(#at@DD zXbVG+qAc@<{yCf8x-0q!2cVh<5C5Fu=2gdl8Ed(*oKnLj^pF`i*?{ZtU4<<_TvKkS z*}dU0QGui7ZfE8j8_}8gPRpGziIWyGPb6n`>Cw`FaU?ZP*N%p4Rn==hNr!P5ffcT~VgLxf#t6@_Jmn2Ggx<9pM3#K}lE$QV8e?cvDNr=gToo4Cza~mh~&Kkqf_l2%^WM(<7{(V zHYtbP0o5^~>m}uSP6K4NMSTHIV6}ac9Dg_M{H#8eOyvyRHS23T+d^$*PaQ78)|>ca zMkoa6y^`%HGU3)wtRUBqsDL2MdT9r$%fdzYHBg8l>!fAmAJarORXC*=loF^2G5A-QmO!uDGV`JmH?a)Jz`Z`>A2?) z0m#K;GjtthWUD%Nn7Y$7UMq2%@s2xhq0Ei&Jj72ir>!2-aY zh*HxU<-1cVOFEp+E4=fcH(1K*FQRZ;F4D2ew@F~!q3d~m%_bOhi$ZHNGZW7R;!b>q z(UW#XaeqiSKSyM^@msNO&-Cm?W>Yqc>QqF!hWE)2O{J+j+ruNQZ5k4nCEy{_=ti%q_BvFHAzVB3&MJOW z$es#K)&%E<8g}$;Ab=x7RR$b#5c3WH1+=YDpD;AQ}f2cK`| zASNe!%`ZRXM{iE5<~j_q$m!r~C}uY=Y*&vcbd1`+FU(Dp#Iw{ORhv7iUGrCDP2idh zJ0OVNqkcNo&!Y{F7;dv57@q362Gq#<;nMn! zeD+{yfr%R|2oGw)S@2X^*EAGuLk|+(*Xz__(&?>()YAI++-ViWrpo*UsjcIInCr=+ z(TFYFHe-2k5Tv`i{_Np#17s5hLbxRcnY3Bmer;?M#}FPqXhCfwce!u#f$?C}jD<3CPCGr236^?BiR~ zG(;|On=TkA{yl)T@#|!38gdi1Bl=A4nh?*JX7l#Yu%+dx_Ug4xTp`dC0(OB9hbOea z8K++6?M`7lfh=+0!0QFiC`p|V#2xG2gN1ac1=XWmBG@GWAY9PJ&AOrD1;T#F*ov=v zXRuRf{>NAQ?A)if`?H;Bcc`EEb68OPXa^qGp}g|3xs^}E$Ldi9To>uLM z5(v^4M;ThR|Hh96G)yfP?73LQ0k^rWXZO#2pX{pc6*d(4q^3>a6aHrLN`Lk&R29lk6{ReU1Y1xi{89RfiWwtc%m1o^MxK2IZ5G(5gWKbmscwm{?NVWdncxTz)7P>}E&XyTDn+m!W>SeFygufbO*(mYs7; ze`;OB^Esb^%QRue*Tftm`_*Nr$tV?G?cvZQj$M*P1PS#C^zo+5DNtf3`E4g5E|!%6 zqT1*eJA>J%`oCHh|AgBMsoyME!iayobxw?jDZ>jgX{a&-MfUZ0Hl}NIwQ*pAwA9R& zIiRy)Y2#}5>1GvmrUhV$AL|+?P_9KHCG_kbQ$u}88c3GFMSmW-)T>hdc z9vlZ^$LSWdM&C+COM}pUpjM`SOkqi20UmU_uT_6`M*Y1dlIUD}j|K|EHzqH?qC!Sz z$@IZ?>|Q+mmQ=?oyDPH`Gz7OZ_$u6^^_9hDmUDQp!wf~lau}qMUI{4(7{Hl)eEcJI zejKT-lEW7fhj+eJ7%{7|KZ=^BphCh2kP8}gN-bt3REDjU%R4MYw0bwdP3=$#Q8gS*@+RkH09Y{i*$|tTfArzM#+c+ z?e#PqXdi7V<=XYicNl%N@LEWl8PO;5mtrGD@Fs!BB#mqYNE3=X0}R?+1Ht z%?)OpC-^gdMPoxXJpkW1teG8-NG2($5Q9UtR1!VQ}iN#oYZvD#6YLJO+jzpUV!5!@V=U4Mr`XD5yZ8><4WbwFURle_34HDrAnaOHfR;IUDWkZ zNlMR}+8QItEjfXp@i!p%F$hFDdc7_TppoCKBR+_iSY*Qb;o;hhZH2Amroq>h1V8E5ROXzDC$eQ&7^Cf_E zaO>wKjE#Sd+1OL)Mr!!WJ^-l5z>xWm$a4WA9``z-z96?>0Z ztH&@WwS?O}5}#U-q}av>q@0wK-)<}!QlH~juTbj9`ib3DW6PxM69KW%+mcUL*}W3{ zRtg0mdRWDZ8x`Ufla3+U8I@lStAw;e1)h4?ILy8k zyF$mD>P3#Dkx0UP*!%$-gl~tv+{rDQQ^W|K ze}78)_5NdFtIqW6^{}h?j4bajTHzAKd558hN$7;;wU+*+rQ4yQ4$I`iyc5UdZsDsg z8%SNxE#wY74lCpKPA8{w-3iv7jb)b z`N!$@*`~QM$4$CI_SE#*=Bm%vpAUut{sy!UH4q(N@cyflzA?g9{@H17+1E(Y?jRWh zHAVSX%`7#{+eAEsXp*IwcQO&2FlD-*=g*)8riSW%qO}&~sQTpuCQ)bS_LHYg<+LbslmfiUZRbMqsyc}{R%19#g_BQ=%Rnp_S=91gZifLgf zN(eUW1LYp>D=;xw%?}*h^_UQ zgz$x#Yq_}4f^yO$EDC`F~zkV904^vw3_k*|dOaju0Mg0ac>! z$Aa`6COs9_<5kk%C9>`j(UYhihX!<6CY}l5V-WZq#cv zV!c{y2FkiQD4uXW&}x1v_7mT7?7xBX{1t>jh^NHLiDuD>L^}hEkPzCQr-g<`KZ|3W zogvKxPIC&N_NgSpibdj-#f@`i5JxlAl*WJKqes7`#WhI8jH!UwEqq~xnD z2Nl#ZZJ1ic8SZ*SS-|qA(?Wy@poxt~8Z(&Um0-0M2d^yyvi)?gy;giFckphKcoeYk z!8>52JmFfpVA43r2Gc`F>w4l2GUa>^lOgo`jVIMs)I=E!UH2ipQ#8~^VJHsYw{T$n15`)Y{aSsnRR2XzB%c zx3MWn3M=RDa*VXyLa~b8U1C^O5_8^4npshP`w?zGXbK+}0jbwj5z|1HR}F2Cwl8v4 zIjS~<7#ry4LZrAxP^yw_b`9gi_vhn$@|bm@;G>ENnp1yP;&FomBg-YGcOSa0Y-H-X zm`1Oyfsca6Dxas0qbIQD^3!%a>t2;?>^CLIN<#^IA@dmOnA2uhUn?DH=tZcleu}`l zM)tz{+Xv5~T+-K*OftN6acun+aqHOSld3<`IhK=H?d=n3{okHo)z~f8cs1nnt_aVx zoX4hB)j-j_6%P{Z<|0n2vQ!JPP$IQI!+#@!ttWbUrDG>4v~g+L(Fk59*RLvrq(3Zz znpSX*_Xq4aZv>(>JD|s$#;@`a%38RQjej zh1kcoOxGJ3y_ESeSerq@7E@DCQ1#zLW zO?YSdesnNivZ1nHS63CL*zD_?b^ZLeGl_5G;WhXXAs(NAimBMbiJ7m2*g{4v5;89v zRX>s{k_~9&hftH>o^2in({H*IEWGta?Fyk$LH9IB2Mya{!_y;P<)U*YBlKoBs*hnE zBJZL@;Wf`P9g7rZ9&;W`s6ntZ+rozhmV`=ST`dp)GoaSq3Ug!51_DrMl1ADJhIODa~Xm_`3|zJg;LXTVmfEzdoc>HbMJN zU(;cuaWRn&=l^h}@4OUj+MgbzN~msR;*#FUAVmtkqEVGTw4ZzL^a_QjqaCw};4m0h z_nPkpk~<`jvHZjp+hpb|(98ln1U5s{e#SqGoOKw&EvnSD8Qcbjkcgd9sxyb^24<)2 zj%M4xR;DJ=uPb+v)XbP7P<`enEqtHV^iCK3`@l!atOD8gcey%aaEydOJ8VT2mS9(mpC={ATuz|Eu3SW5w>8>iTM;OL{`NbP(R z`$g0HMFK5AxHU$O_tRs)d%2lX!Sq4CV0v_6y98UJc>z01>;t;9zVy3`?JQ6FOv}vQ zKe|9oMWLU6%svaWZ(S~qmvYV|~p@Hf8hRd-Pc;z`qiSPG{n39?*x=c1;`mS-^l^;7))Y64m$f* z5S}f5!352h7xgn=?$6YQy{okaAof53L{iAXFw1M~W>TXIO{<-ojUxx-(BH z3>slSl0OhBWUCs7s{tCenL}y}EjyCZ0f5iM1&_J05}@7%3@Vmg<%PJ~xawRg{?B1U z0d$WDEy%ssNq#?*nUGsHEP2N0?~p?5<3ru2r4z!{-^4jtt4b;l0JjWM>!-*D(f2KI z8%3h9Ocigrmp@^dWrkbmdlJ89_^rTp5|2udU8=62+)6-*3~ra+zfR}jxWKvr`?{AJ z*y8*;hw>5bX%HI4O~F{fAgkw93g>9cESy_Mb|R}8MOi)EVq|N=&s*oq)6>}v-+0Sj z+vL_he!*Kbw0SA95ajY?Gmo{s?|wXC6?j4_vFcsX(ZX&xj@Z5LmCw-YVtpSr*QU5P zVW~Y#c55+@_RLr=${wht#y>R-KL2?3ty58)&KJB7VHLYn&+3P>O-f*m6SK_VadgD; z49FSy+~tqOB!XwG;jGdxa=3qC;0XWc6T03F-+xIfe57+18eC~sIA{5Am+Ea_1}?zb zZini1ez|Lz^LIit|HKn^Jnbx?ZZ%bV@Qd%iBlsMeib_<(NNGj_82BZmGAxaJ3uG}B zUUSn}#}asi-j)X_eXt7cl^O)JIOg!DMg&IP)SZkFhFpWWZJVeCILwr#ecsNBf3h9M z|0qzbFH_t8)}I5zu@oHW&vhe$po3}NvyVki3t`SuU!gpy1}g=b)GSnYe&Sa){}PIB z;LcuoW=#W;u?gZ;Q4D7FY-3%DtQYnulcdD1k_CjyPrQ<1fi?(=YOzX}P?&BGF{-Rw zAf{a;oK%9d#qtI?C&C(zIL56@To+{a`Hsp&_ZOeftuT3NtG>t;eD|94g z(C3p7t62qV9So$2HovS<2sLo3#x*mc8$@*Jd!lE0K4(AcZTup$|7;CS4{U#sSkP~k zSBPt~uEZEKY$78c5L~Gz``d*$tG(H#G&X`?(O^PE)E!DXeF#mu?Z`@pWiYEbPs*!* zpJ&+80A**c2&O5&py~fFgfK!%>F{4-9WP)&a!n*YL}Y{$@V6JYsVT>2M&=S_ZkUly zlwUJ#8e>9+f;GjF16M1g_J7+tK^0icn#D{8D2B?#S^%2Sn%m+yR!DTBH+GEW^`3c2N z#wZ=H8431G+WQ<3sCHo5K2rTzdGKI_B>zHyDBw=Xz^04By1pQpIK?#62DwqngPZGs zW{$W~lBY`gMe>5>osMcB>Rc3cpprQGz2@+fyy=xn;YnH#&Uvw(j$hVI6BU+q4Kv&l>qKJ&S_aLCE_J6=I)I zW{V`%d2C~UwmWuisd`iL8<$Y0^s#t?WUg4;BmbID>YjD=LG?{ZoG$U~GbBRae(o!C z8i!&}yWpcuXqOn=*OMJ=7#~xR1K+;M8XT5uAAb26H7esw-)=HHWLOz6tBSKmtllb?5-wPvv*Pxz>Sv1>8h@=7J4nZvVUB4bh;EK}pGI1##)GmQY z()M7SZebu21O*)-7D8k>{az}e*mJIaISU|+uOY3K2#YCPNyQwmpjLr+4sFR*{Q4Wu z17AnXG4BSZ7bN36%AT z+b`HEc{6}JOEO1IOQ3;nC2?WAAhvbJM|N-y=<;1JnhNFq@2Sk&tf47#Ns3d3DC3c0 z$5@NpL(pcXCrVaBzpq21{W46jKKVi#ZFrmaKj8d-OQi0&bd8MN!1fdk8e8QVEDRL^;3T zrAJAeRB}j6C6(8z<{d);4LBK(2#8^XEkP(BcA{vXL>H;R==jhq$`)Hp)=8w;+o(4> z>o=#3@``ik7bBQkQ5O)FjdA>RK9D@4M~`=OY&UU&lswEPM&8*@fM;C$`XQUqy(K z%}5^}k~=uc^A!Ias~_|VSw|ph!&N{g-tVI-yrfT1K&a9%w)>{m;**@WNas$>RuD8V zn;}9>{@L%*+G=UDd{RR*d^2|3M2~zh4g_#y)sWhgCC6AFh~c+TM`z7)s zmj9y9pj3ZQl%h(Q173#l^CE_Pifn!Lx;whjNTpAU**5%BAL&_}{a!`S&-(rvlD?*f zV#3W6hWXbYTtPh}cSVTinjl@n6?LsWmeN6YDQIz#`o zoHQz`RDl~*4I=IrV3#Gso#g4G(3zvSdg|Dy8&gOValGBm&~9LC0F-3;>)3U+kEGBi zRBhx^!IuA725OjxIdtx`_lxCraxj* zyxjUsVq+hFp#cv7FLb**6rph|30_I_px@%hoiV)mD*I#$tq*Iq8$9XLDrGyn;+{(O zWZw~>JpTWbS@jnkXZXK5&Y0*f_HFvNgfm~)%(6AaG#S|ZWDw^~pi~YYu4;uMa!_ff6sZhu@ z4%`vM?Z4~^>f4nDX*#@i2n6tSWU+Qj=QC?M;uImEyk6R;fxqw1-4MHDKtm&P7z*kD zQU>$4vF23Lzpsy@KY(<^-W_}?^EmHe5`V!Y6Jb;7p56x9+0`?Bd6B}|#hY(I$K$jy z^Im+#60yMb|v?I~rc+fyUndeGL^_WZi9# z3w=htj^V)#&RYng_Tp_HT*63<1Ne(4jX<0t`g1xupv}I+35|OeyL;bJ;$2cv@3X&$ zcrHc(d&&nw1N4ux5|L}rHGW6`F?s_hYJuD47~>*tDSHcYDj)TcOYB7`wl(ZU8cx8< z!-pa_WL}!YX$u+g6eTA&ol5s6mhJ?_{Ci+{0lNQ?Q7k6^C-JmEKpLgyRtf$dcjo`e zzTi1WN^YO2Dp>LN3-B9MEzA!rT$-Yh4hv)T+&2k6AAU5^9s68ZuKIXQBNmR`qm9Ik z;Qlt2A&ZoS;&7i3-DB!3mw*$UP8?Gd#q~w^Zpk(JR)777qC5mlA=|>rs|q50Q<;r z5%|Id*YO`(2@4u1d@&+hM3^exuv;F1dqU72DNLF#Pe^SP2dNwOFkM@Qb9bgR5ssJQ zw(NpPP+c7Jd+Zi`X2dTtMKuB)bj3;LZ2ar7nKP2q8pPbF@wp?!^u`Ke7MJ|6ub5Kh zyPeE>m(Gj-=VxS{xW`(x1&u^(>Qy5A)tyxszY8;HzPelcg?CNMtCi>YJd}7fnOg^& z<8Xae+1CX5D3WKr*G*g!$zL{{%rz+@4wR>>64`X&SGq*orGZkw>Z4lO8nw?dunp3T zX0pg7I6}IWG2N(eWGL4kq;@KL4KwHHT}Mg!?Dl0}M%%&qbcYCR6&Ck(@2^oxlw(2- zQ8t;p;+EV<$z{89y^58!1>@ZPtsAJeG9_8xQZFd12IVr$3+_H9zoBCz5G`x@;qTUlbp3G#g3~qw5p%p8svNX#{jg|;20`c_ z0|+?I35F)+u<;#T*YG{xoXBTQ%Bu6{B8&PZJnCoSH zVP$Ksa9gX@#XE27!`!D&7evPE64{j6@;}}W2qIlfja-X%3wCi^Nc%psX^voj2u zGbwfOiL9u#-&z5Dh8q0i<$UZh4Kw4)Y`N`58nCgrt(CO|d!uO}pDthqtWuI5P}6n& zG2`*Mh+S#Y=LGiNKqpTtQs~>?(YO6M+^KU? zD*h0Rd2D=kj!w`>(u?XEU5%@W`u1{;eDV!UXl}L}BQ`j*5Sb3n>1deIQ}&GCo^xjX z+N;As|Nq?TPb7%GlK-1P34mRx#$$N<0iT3}fdB~h$yY(@%cA~;1_N0Q8FMFK03qG* z-?6q9^LSZw9iZL<>(>6Cc*zW(%d(R3tus`T3OE1XjV64eh6GP#IA}s{R2$ zWNTLL9B-tt1pO_fC>thY&BUFdltulU?5yI?p`wg-g`xQrL0b*e5VvWdgT0AG)bTn$ zRnFqO*jyLzhKhz+Wc}75r*=@`#*B_jQZ2^8i3hwBicGMPXbu@>@~pw>mSy(icWfj0sMf`ka(565yf7Hpu{xP@X)re381qTD zvtI8#>sP_-n6OatzO;CpV|&8;&5~L(Yj=g~i1Iv7>T4Q<$~FKN92b4uCZ` z(7%tSPk2bONvwU}d_BEt8_lJt@B%Ihhbwh)uf#yKOb{bmVBP50+&t2HphaFL$iSK* zIGu)TB`t%|0I@I)Q0&H#6@{HkRA_dcqvOu?RF2YEsq&`IdC{Gqe0AN0I| z=u8w3o!@}Aw8CkN^XpxxGY1aHOs=Lvgdw7)#|EthM~rVSzYMOk`cm8GjB;gRKVeL2 zkermk3jI*+uK($QZ%N9iP7CqZR zs9!WDWZP{1`4xjE z7VdAwl$!tw)<@We+izm8zMAwR<4L*7^vAn-xyydJ5V~z7ifB0$_fB&=0_BYpyXdaF z^thp6x0Ge}uURWEZJtBjZw-I0%{OJ)UIe$jKN&7-mzI|1a}g^4vW=wFsYw4XL1qUM zlj3k>(Vu!J_`c^wbKm>1@vNq#$R>}=5BJjf(Pbyu$*wZ03w>o{HL`Zi{VYPsXNnD4 zcM+q}e#6*_z1DVH>K~u=`E~=zj>gDXq-GD1yo}Z{GrfCx)Gpgh*$cSn(mg!pN8j!9 zZ8=J0SoPjrRm+}a5#Vn{#w~K{=uP(b$-lG$$QR%Z1v+NH>+KE%E+x1O@x2i>;CIWkGGjiq-iO+HwxN-8$c`<>c*{VK410j3Yq zX;`$_1)iH=G?t{x{qAuEi(1ISp!K(*)OsPXj!ho+7^1x-q5iV9ym)uYceOdJK#DxW zsL3dYarceFC|@eU_M6hFZ++Y+z#?61o;|?E+LqIge$F9+A7-y4nLr+nE9YAeTvIvU zEM$d(K(X{TsC;IljS#`aiE+%@DuySKh06E@w|L?}AMIRPO6WKmO;Q|Oh{fD`_bV(h zS-m0R>eZ7T}bj8ux6Y>A#)wc<6Ib+&wZz75hQt;xXxTdNg=rO{({oh zO~5t4MgK7vo75w(U0rbEM9|M)zH@z&Q(JmaKFy-&UGwnM#r8UVO1->ImdgmG*zuOi)?hE@&woM{Fi5(rfB!~JDZtL=8uKfb_`XgmBLC>f|Ql15zdG2ogmNP=r`wsbR zsLW;i#CrkPc!ATO>#i#h=@|o}>`&W_na`EuA!ZPe)<|PdX>uVgh-8|h2fm$Y#9(tWKPBH+d-v6FAN}*feQW^k%og09fZq) z3km~0JQQM9zoXO!$uf)eM>_Nakx?Xy`Bc;He!#hcMVj@KDpOBrm{Z{fhS*xq<@F#` zBzb}ETwhkgSc#sx5OS4)Xe51WE4qbJ`cszrFvY&Bp}-bCY2c_7Tx)IjdwV_hYo(Xq zP@s2fimTXE)a|FwRg!P+C}Ge2jX*(~>*b)x5h9XU>-0#O~A8;8X=2k?M2+-y?K$sz;>TB1#?EL>&B) zzNtL)W`O$7OqmCHo|IO0Tp*X*+{y zMAsqB@66tgtwC8d+``q8cU!MZc0VTAQy9nVV(IpphhHnpdS1_jC~9SJw;$+cS5A4R7qha#_HFn{!;|p_;;04q%-4s*$GC`ySB$MVkWn=y3<||51n=N<!Nq;MJYe_uj&JT#K!f9p~v@7y(>&{snvO6-slu4U;YMNHG!%!q_jY z#<|8CXj+F3?z624zUUbjQ0AHn37ivp<#r412>x)L`bd~ZO5FrIxLEuHJ%E~K{b@FC zq3~HTZoH{gu~}ua`ZBNB>13w4)-pR=*C%PR%VHlz=|yP=$oKA&o+LlKMk9fk3RPeEb=rXX@B}n`F#(_u zL?E012cO;@@|OMrklC<*zVIp127K?%j$<~uQ(VR!aXya^b?Zq_*I_?7jBHZHygfT> zxwf^+dtDuN6Ub4k7F(h|x}sG-6q#-bo#&g%_7$NjhwSKX9FMr>I2npjwwertLE%+Z z($~pBg-VCDgbJC&Hh~(Qchh+W?^GW)lN3p-%GYeZVv~iK@@lgmey5Fje_hrVl%yjG z;u4y3EJl8LXI-1aZ8xS972XzHpf&pIIYZ0{1`|5E2Y|QG7po#KIcYRy7O9m_IPyup z#XA3Hro(`PSBZsQn#dKaE#6t5V0chn(npb12y3HgPSURyui6V~+mEnHS?HRmezX@k z$M#4fTWq3-vY=}?w$YFJICpMNOa~h_l~__m8p(`hN7?GtUgsw&&@65i4+k{qM^)0{ zSUebp>H0znuih65^H{rLJG6Xxf0*|oM&U-1E#xQ6ia2Na(YLc7#a^{6B+Z;-qR7(L z6^i=v(5?bMy71gzWQJ6ZaVNOO3H+ze8N%svl%#UEw?%ff$8o*|BR7}4ekXav=wUs^ z_yfiG7i5C|YE{t0P~reFR1__RgIbpadvUhJw#g3DYi0%hy?dp?Z`GdJsL6^#^A(}= z;?>-V3-`tr;}6KE@FIDN?db9Sw&;}yB&ZBuDEqv|h&8*2iO`ms%8%-H4H(o@g>zB;B{>m!3X5-;aAd!@i!lRoQm2e5q_SRL z71N_l?wYp!eBDXK!@+@WZFL(m67a{clbgJ&F1dr)80Kh7&Tz3!j!|dq9wOzKbU_Ku z#y&Rx0GDj(vmMkCT~&HDS2LdCI3L&dYMrW?P(lt~e($ej^%|J) zX0N0(b?eyrOka-P$|A&JI_X=XD_C#7#9Cx%&@byydv-yMdLR=0NDck34#odOY=8hf zYN9HTA3A+2xK&%_rfGx+u6B>go2&a8zvq-^9}Ap?g9S_GcbP2`<%%j6WdTY;qA24V z@j}|DtYx85Fj)c_?m^#`ab^vYQ%XzV#N&^J9&A(Jh&|#eAO$mHA^l)Iq=EV^HKY`} zGr~kVcN#~D|j&aoutROY;Lkq)SeUkSvoi2y=mmxVX?nDKzrs-*DZtvnLW-&IQmT~MU}u~ zef#a*VctpoS97TvOb58UhfY^WgRZ-6iI-d5>cf`@Ns|axPU&Wz43=yvSjBVv4DFmO z*xp&`{qf-b05LuC*N#_G?ASPnf4hits5L=Z5jqJ;rN`#VEKI{D+#sH_GBk z;(?x5pxZz-Sf$%Hs~PwVtFJP>ONy`TVzPqdJQko>m%YC-o@0GsJg&Ao=#}-=Ac)ib zFIxqZW6Ccwzc}W_KO{cuRyo+6Tf~{2tvxfWSvI-+p5fT-DiN61O;iOJR-=1S#{pVQ z-S!a^Rw|;fV46(e){ug>o8tamsoQdrGfdm{ZxA5R6oT zFuE6$GV*@F@3jldVx{*Af%x$yFO;xyLr;IvZ~Qha@R2R(FKFVN{22+7{Bby zDnEO=^jUC(jGQX99``kms|{7@9Hwo`4+j41@xB}#_rG_ppKV=x=D%#!ir3L;SLl+C z1bM@orZGG=!wc+Wp^jd`o=R0b@So73rs+>ZNpoL1;QkIbUFQ#|Kk0 z#4EVS7~UV*aQknTDwtTfKR*+aM;X47W(AmqV6tkpFP!NUn$FIu$yvvy2}&NG`5b4l z^v_UMy)up)C+_)ECz`O{5r-9YnndV^PurVt|9M+W<<3NZ`k4M_9xI*=LicST2l0q)jHVBtvX^IJV&uf z&AsF-m(Eg`tk6yj2fW*GV2>9HQ+72#(f2u^QuB@Wsi#c22)H0Uv;4JBVmbbyeZeln zG0f+_@7!h&YAqTZkYUTdUEBTjIf-(#`jqa?Vt+4MA;F<6cVcCuAlvtDW1Ec_vtE{W zc3iOW*muw0vwLk4M|uq7`bW(^P#ALYb9S?kvM+=#d3c1+=d!a$Jpd~)3%(YD>aV9$SvCE_q&$Ae_N+N7Z9Ja zy^w}d4=Jk1U#9=aQ!ALIQJOE}r@X#4UOoGf-lCYswCkPA+!@dk`$(>HlKZ1vr%B=b z%<-qrw{{p>l6V|G-dr7EF5mKEdz;7C-gtu2FyHQILxN%ZAQ??l->v|mqX(rttOxWR0bGz6=Z{@w+n z;4hXU(jq2EdQ|EvQHd_8h@LTocnWuw?5bch$PNeTmayZ_yi=dl$Lto(N_tehH<$V$ zbBl)_9Kor=StUga!#hYEt*p69EsMFI(C8OU8NV8Fa7bcDGq@wU|9;FcXy_k=0^ggP z1hcu3HS z_La(9UQomD=+p|&_V)&d$hOm?3G%$S9Yr#ShyM0QN&T+i)rS{La0G6GOHs$uTN0mg zrsSApqeO1jYQ;YqM=8}a;JdjhGCRI+j5eAnPlEbB!M&ADNxr<|3u2KK!R%@2eTPb; z3L9@hgFl5_?EFAJGJc`y?%5{W8QE`$ImW=T`NyAYqc05(K>uVE3940sTEa`@_V4sr1JJCBz9HJnTv4|m8wwKiu^i`51WO5v0wE6z zYvE~3A&@l^e{!);;siaamyOhKJRoTBO(5R>`#&z2f94Ppgn1ZD!5q&-L52kntxAIf z_zO~`{Oe&B6R$=F=IdlU6A0N~y}zwbou#p7v&8JI`jxLDvZAsm`}Vi%c+tluw-NSul-kIbMHH3?b;d+EpfD-8J~@d3`?3hq&YB2+6Qcbv9Y5?DI)b8N7T6pV z%+D!BFDt}Up^!Do_w{PiGK7!ZSnTGZ)^M05G?lBh&K=JwuT%Bg4X9z7T3vV>mQ+8h))+}ro$XXNLqeDC)`{cQqC3S zfo;zYv2gP{<}3+H*Z6uln%2GSZda}usgQlJ@o?A7{#j|P*PhiJgMM`U!i){C*df+D zzVxUr1rdMx6NtDJ&6etv;0OLz>8)}pEcFzNkKh^cxl(tfkLbt>gy{6*UsDM45j<#c zr7&(E)G<#D*Jb%O(CZfMCY2+r?F0N&O?~U%(RO3tyIir04Uj(b>wmFt$1zZ29MJ|H z149fw=DCRhL-Xp>pwW(--(eTF>rpDX-P1_<-RlrLrr;yge!lv5wnbTmfSlb8sDF6V z%%Rx!i@5YX55b;!aARfS2Dg1+I&C_)Vt9}!FydYb`&g%x8=?_TZ<B#E!*w`iYGvt@AlNsBebEu+UoCCPCed)&T76~*;y=XTcXeiN* zte|t~uQW*URm+gCeskx4>i=k5aH5-MFjAi*z4D98`VVsVX`7U1mJOAnkJ`hWvAX?| zLpRmANO|*{{|hC+3s|6eQ93pZG7d!l*N`NNAUfoU&F`?gfhAq`o8Tygj1z?#u|(1y zB1~)_EsPI*&nk@}8G-gOp!lzN&h>>3v%U?C8t|ST%K=COAcAv>XZ4BNC2p(_SBIV? z(r^3YZbfo#yyjNG#0c`AU>S15k}nvaEHXc)qv|!vlxsKt@uE&@HSN6TF2e>~B&Xwr6&qsrlyuI4#Qqb{$*$lZJl zSNJ<33L!sz__X+3cpu|hB3Vj~%}trWA%0-RF<#1|myAZD%Jan?hMA{tm&kL#t-WhW zr}>q1j$kkvm#r`51>8bu>n25|To4t?ayT14OOV6zuu<~WV;|9mR-Z%;z6m@lCgYH2 z-`Kl&N2MEOA8aW02s?+OH|MV%GzXOMNp&Tia|`&s+~d8(X)rtyhwAvg=Rz;$96#n7 z{0ma>;m@q#!XV>blfBBJtBBwCi@|pb^j41lLnB^Nw7yBx?2^{~*A|8s@BzL2cg%em zW*E2d6cD)r20=vs5Zr}9z6&G-B*4H!(uG;2{{7$~QLpyY@p3}?35YdZxPwg0O3coZ zQt`mSkaiiwZ8>5kt(5h9()Ud`z{4NSg9DjH(UhoC$DH}%GQL84=(7P7<0z|m!gs;9 zXd?zrT)P7Ktd-Q(&91?tBsAnn4|+sZm~zT+F6>xwA{={%f$}bIC6-QykXlN|dXhd; z{j*m=VLI70W*JrFcq{q33$wnKlBVsDX`^qM?PIZVp&Ynnc`^V9k8J3YN| z6NzmOd-osPSa^GxfKEG~_Ufi`+?*CYpTSk8;L5MH35HP%DC@j^B-^|LH@z#>ZbwAA ze^QL@DPZXvw@&Ret88NpbOJuzm;Mgm(vDqn)1?o`taLb$*=ur4c2#A7s#R=qi>oTX z5^$*+^Redezx-a8eyp%F8{$cS1s@M{v=4zRP;aXRb#`gd<3N-W;kg_sUJ=HG7tr^d+i23C4Vv!^dzhr29wRPtLI z0FKe5cYmtfwE~hx8=w3}aBC$54KYX;wyY(?*-jt?5NhFOJhp|>r?EdvT1?&V zEI2*u=Vv=BuLbmpn0#3w-wtA8lIag3f{Z(oyh&)*#@)L=2Ex$*k6Sm$92*30*o7n` zkx{?C!U-lPh1JGRrf^5Ek7Z0GJ*SUr#?K^uJqp~;d4Ivm(N-zmpZ!r zBErBL%NJVk%?ZPD|0fK57tprMv+>y9aHb6!1C7Pg&w{IDsb*2kk}i+S)La#(BWsOS za6b3{FWL+*Ambm0eg+_Nm*xeL2^SUsq)}5lgu@%?Y!7Ez7iW(VVj-@d-3g00O zdZ54Mx`uG*VnLATZ@77grR#?AQ8(E94SxiQk3W>nX!wV-rnHu;W%F9O3hV!Hjf6&= zX?q3O!g@U9>C5(XcM@+++W4HGo(a36!-1o`{#k#g)S;X$&89vSgogczrfj0B=fct2 z5#$74GP|)Iz^GKddT*uPR!Pfck<2i-i(T3#mQ|Si4&Fc^0EZPs^AQ26Fi20kghR$C?ZGR!S*`PcgJ9q%9C`xg`rv;W5AkR#@}hK?(U zg2QmR`2O(MFin)Hl^xkGL&fr&Yr+tOYn!_VMUWzdsW3)?0bBIa5jbTgp=SY5?)@O( z_nddsC%LQHufh~4) z2dxiRo0MFOl1?O*ZS0r4;=B|lk?HU6O@`^S#b&Tc%9G%nLk!1(LqQbHr(&;Me=7^& zBECuuf&Yr*r(T`9M?9bAB}V!o*T#C=I$}7TpX;1czq}cTmLUD;z-c?M131C_JB>8SvQ3#x4~Z&0U|E`wfxU}}2RX`F!*_U3!a9)$QoM1vI_BgE3zz`IsE%+L&e(@lHdpUt{^Alt#@_D-IU{t z&@buuOqb{WQFUO9C1aXogK#3b~PGQk9f}QU!n#CiBqlhb{~+MClRxMhZ>FDS{7wkL)1CIP|XBY1?a|s_a4y z$p#s$ZGSOQqTyR#DP36b>%8CB(m)3!&S#j%T!BX4qisoy{W!#Pmvra&ZV_5J-#6In zzU`;+1*PeiN%f#&sObrxKKBxdtYMtt?z2L49AGZ`d6`ZQN9mD7XewK9b?oWW6-T!A zs&WPm;je5-+S4-p#(~eTe!>)oCI|1QtnAkpoS+*CIo_m;7hF}(4I3^3S=O_9^l_ub zYt@&B6Niyvq;m*glVW_5WLs8RkVAOw<@ad*Ka$0Re;Vq+?}*+14%Y$z&B{*{P{=F0 znV+8u0?AzHotK6Pd>aUR#wKURrIC3+M4yGdF3=7740l3>9KxJ~XNepEF}i(rts8#& z;>buC>Afw&T2pAEh{Kw+*~RXiN^PbKyZhdY^f}cj+6BR%LBL|Dd;)dOg^Jr5CW@@3 zjD(?%g{zFLy!9${(-w^WdY?*YOJp(rT2(z_Y?fBxivzER4;383Fft$=C>+RuW%Q*z z95?>`JD8FieeJ^X_Qr8ffWMED+X7@&naaCn8+}5l0%n-;F(46h{Q+s+Rf%}X;@oDR zcfaGMZ!O@iuu65luTW?cys*YE(sfnS(=RHCrDqWJ0!8gL=5mdXY_S%dhzL;L>1NcOMfRN9OQf`gqt4@X5J1ZaY6=|lJ-lu(q7YR$;-&|r4p zwC(oRcZ$CA#%kC?b9bMQnjqP?~ zZ9OdXikq}QJ%|JGp)2Wu3OqswF+D(VKr$cVIR0XR3|>|_QjN~Oe-c-$ z%7~TvS892r2+0qk3c`HFtI6QTaS(lS+Gs?Z*p8yy{cloyjp?%0nf>5{O;`8qs~Wly zcYV+1`bxN_`*g!n=zx%xt7{g!gH211KPm?&rbb0=TM(`S&t6)~>HX@@s5?*YYvulZ z+GL4WA8O`h=C=(RY+*GI4l|50LqheeZU)sl8)qITjMC8_BZFqeLD#k~!w{Mfx;rA$HF5UApVU)ia=WWh&n-@=fO&pyW!xV61;G%saE{A>54A#c^6EQQls)0+p*mdX zpi>|fKx6Ej@SS8Y4>ezwB)6hIw|>@^uv{^Rc<6aOijBI|^N@-avE%k|^+L0>hpCs3 zlyX_$B7!gaEzh!1l;}9aWCT-{Ezp-7Cu6v?s@QI@_(jmss2cAVKfxcbn#n0ok(Xnb zXFyJCnJ3|te6@zsec=>~*SK5Dw4jjwL0s0)a5oz^M-dpb_1v=(`&=z?@D!UwMrea+ z18ld)X6t#XVLpOOvv1v4fpTkhrt{_U1cRJoZ^)o}&|~OUh^-*wW1#alyh>?b3M4*z zRFy3I4=j4M&L!KY$-pBv0k7ezH__{K;3LRWw-!c=;9$)L%Sl;9cX~uTLjOd#CgR7w zbBg~(Av6#g?Kko+%O{9ptY4Pq>z(bJg>Z*No3-Moqczh_+l%T`&Yen9*I{5~?0@?8 zPVmco`>ALp+~prZ&lNff&{*=YFgMdB3(*$FjSU1Ym5Y%8BbIKiQ#U@Wzsf1f))8md zwxEcE8$4^{t<*4&U?l{Ievt~(uXv~`-ozHV42)K)f&xy?D3ATb9n_ip?|IQ_QG#1V zp+IVuDoeC5bj80VWVZfkCcIL>j}WDi5MAb!j;h&k?JWDiw5KJ1G!p(IM@5Ax2@$^V zrfx;|Up}(#wF1LFij%sHQ>1cA3yRNS>7RPOOXb!w-}O?WRQ}#3LW@{LbZ~gPm9PUh zJ9?liVQ{Ucv*WJzBeyk%&ZEdFZHPEq(pL-;*L)^~A9AtwAq&~y=~lB2=)6P^Ysf^5 z6SpbDR2uP8H4Ho8a&X#z8BP1j?1H^euA%#I_wtf1oM7*#kG4j_ zDY^m=2tEcH2U;UNDv~#@E#*fofw{j(#(uh=h+EgSJN-8cz?o{%!uyUak8EVYTa97GNlWqHttBhhy@i=yaEDohz@3-4}=EpJM zVw(}zJ~sNT&~T-|k6iX=Ki3Pj$K#&(*+t7LU2C6*z?2W1Cz3BL;g8n=+_Y|_7d31D z!~-aP=@RP33h)PrB0pHtABS=S0f^y1C^a{}GmSy1Vwz*(IBJIT(w-QxJy>|>H(|wZ z1qvAF7AZYOY|`ibHV_tAR4;MAWZV&?bFip@x!&_KtkF>%n4rOt(zQS6!P03eh*@4A zs{9u0aj2d8lHg)7#vyKHh1D2PCwndi9>cTkMhevKnbodWvdg>D3PbeVH6bAHZUdP% z+;tXU`rC`z_gV|Ne1Q1o`&ECNqMP@7x1*zoj59}AM@~XkPf9&5Xp-sqQNJtLX;wB> zhH9=II^TCbu%6(^12a<7$hEmW!uV?V(*IX z^4>63C9MrY4qPzIf3%L?n(@Mkoy&5VGU$);$6 zgZ){e0i@YTN?F##_aUD7TkEx4S5-{{c5dR|9oGqenB~kja7AN|;Tbtocn8EB3at!0 zdc~5{1~tm6Iz1p>jZ!3*KhL45jNyUZxR*K{Hnm)z`>*F7WRq7p{8ZK?TrKTm0eMrQ zdY-A5xoq%4=7*fi{Wm+B4%GjY@0YxQH7=(A6>>x*-_1W`kQbkcUm-dz6bTn9LX(z76@zlmA|yv1ZDh92$_asIA~$FBSJAfkH!av#A5D!+;g zOeD^=Ewvxrr2Z7#mbB#{lRUN~=3nM9B<(xXq8yrD@u;u*3BD!IBI$7Abjk%?QMLCp@M+pM;CBPWa2g!nChZZIhd*B6o(TgI^JZdNO<)V^-5`OY z=#<X^@l-rKP(ihAwFd={)#6@B4n=b*^)rYyStcXWzfQ*IIiozmUzH?A!Vhm-1P2 z@x@f+fqlDeOrB={wVNtzg<;J#eqD$?8}8AJ_3JFPIFo?C!C)59heSuEZQoAwH4f}! zpa3F%u%KE+yIK`8=@^5g#WO(15$JIefMX|*H}yZ6Q4;28yykuZm?oj()O#{_-JD;c z;%NlZh|^om1qfE*E;r#kXJu+^6}|a@5>yb-v)9I)FU ztcVIW0g5eRzoaJisSb7XyU@2QC;n*LUfFFY3NQB!opk$}H;$g;5!C2Ty<(~OeZTvt zwMFD@9@A#}f#A_pA`t1RQU?B3O3@6eIoeaDSZNTgB4?BN1KnQC9VED50Qd~h09*iq zLn|sy_&kd;;|X*ihz^Rk-gq#U>XjGxewvp>49oww0s0?L3Mhvr#~Ujo$5wit^Xl4X zQ@=rqfFKYrA#F9Gvp*M4>wDxDg0UYU2t?_)2~pCGOMfpmX6{yL_j5oF#Xdwx&Sla- z#!<6&fzfot@F5>RlmAn2r|?=Qc)=@c{Pkn6J5~Igzt&wd-{;(+e`?YbaE5CHpqkj?BJqqs}VbMqe>ruM#B95=0jCeTV!2|J2K=a^p8lH=FupU)L6tJ0GvbcOBEi_x=FpYgDV??&o!V=r)ccI5UO<$9UuHa+{Pb3%v8k4eY1kMb5pAL$8qxd{WsM_7i$N6N$;hao}yCDA=HD8hD_K=A>|H*s1wuD@;zmr-DBIdSM7qIkVeJz*5b9%v8{!RBW#fRiBk3vV ze*y`!>9J{scP8mYMFPaajlBbdeNOV}HQ?!D{Z4t%X*CX?@k^Ed&*;o;=q2)cCrTBw zn%aiglhf?u7p@r|AI18FZIaGEoqChOzfXR-TNlbG_H@FD9VcPXyFAO}J9enuO>}Jd zT^~BuKs~!;<9>q0=MF`=y|@;&>vF-F>)9Y)=tpa>kGXU5eNb$MikfzRLgTw1Wi8)o z{&T?C#5cjn_lL8txe-U#!O;=TxNO-UsB-`l6mfPC8T4a?}e7xpE(*6Xr_3h`>)}_^< z|LU2_AmSuOBo4-?jgKt2;xi8$hTZw7N3L$XiTX9-86LM^*jlKg)Vi9%v~|v%T^|{U zh%s#yU`KXy@5#3;JCD_c(kq2s=UsF+h@9N(^)u#@$8Q%$=vP#I7$?OG_!s5ks<-)^ z4GN9j3FLymxte`FQs*R$RGV!_gJ`5>=i{tDbdO>+|NOGT@7zwxdIAnnu7Xx|P}g-7 zJx2Z{rqTP1u<$q#G03xs=JFW}dU_tN9q;$v=iKMJSUO||X<7yZfbo~y@Nnl8(dRC6wj1HG zif$14=L{4V?O%j4O9Ry^xtU?%LLfgtVQX^eHKHrf$cG+FoL|tDxRF>;z*%ftsPV(l zHY?GLG*d_~rQ^sbo}M&=e_?s4nZgsCg953Hzlh!T4Vy&%c0SH`^zMhBQP}m6aqxq< z`%4~pfvzllb*$Pi2ce+JilmQ4D@kwb&rlR5KY}%poFolFam9~8-J#?g7-KBiVsOVE zTbaKX_s=CiRfDX5%m!d<;txq@=`g8oy)!JF%er`GzXo%3!Q&yNp{g;cuW2=C)DM-% zv`Eq16M{&+H=}Y^467gfIC%6b1RVTf!fz&oSpT>9qjj^)I|=DRZrf1qMC67&7WUs0 zUFh)o+NCkkZ96SE(4bL+B15TWC|344CjJ*U!53(wpj}$Y6mTv-^XsS9fgH zB2~y;POOD`mPMY@G?kuO+C#99N;+$Zbgnp460I0R-%#eKMh>0p`_#Ilh1iyz*TYPw zi1R+EDi(-Xl;u6PMpMu~4ncEL^W-x%p?a?8Nv_}gi!CSi3GIu-%tuI)jde{uF`Me; zzpk;m!!HaKxthln(G#DP84FLR8U_!1SlQR8#O14?H+qod2V-q*J`MWWM7$3My@zN% z^(zd&8HInzhWs(Q=UV9Y^^ajsIGD?hee$gHX_-?$;Gh3qxq;OP_dH^x1P zR;@+p1{lnL5WMY2gd#q^fZ=3SaA%l=cG_zQ^aBzBEY##t)?X4|D4E6+N`i5fGXbfj zw9`hyzj+)N?96N62&@D<(0GkC-RHb(+vcVg((Kz^cro{oKwM7i*$vATwfdM z=Jy}PbCDyO~~t z)LolABV2HdZy**-aQgk-V(QCo@mo5*3`Ql-;6dj|4yf;V#TCWjY4s@ai=g}ujZ-5cc_RClH8qQ436UH7bI{F#BPO03sOou8>g87-_ElD4R&QM!JuT@QW|` zJKM{+!6}wLNHUs6{wwsHwFs_Y#14ndI*#>#1QcaU7W)GvG*~O3I)|I1ef$F@=F<<3 zx$&S66`)Y+j9x`Y_2;a0A$CuzAV_;rbuxfySz-1XM1qfn@^E#buTe_!10&E)Rll{BjGMv4^sSRttTNTjdfoH_Nw z?c$>aS!EO=s%kf4XK!C}Hl16+cZI-Cp$s=Xvn|q<5}~WF>u4V!H$6Y8s92{>he_LS zGm%MU)8?)-4H|R{2Y+}FJWV_Qi5xMaRZ7OE%KJBH^5chLGLb(3Jh%PO#0q(sGua68anR;xQ6i6& zZSuES6lvtD3t6{poQtiGU*hc^%?l^wh`B+YE$JOM&s$Q|qzu4>%);HVEk8!YI!EVH zYqIIjJM+Hv?LgW?&wS?K4Sv6n?IR?i@r)OJesffLy$e(t;A8BLp5>ott8K4{LG8Gp zhiBCA=!@e`fDYAD?PzP#KUFOM8>4l`5V*q2t+#b1*G2vI>x|o=;%#HfI_uSl{_e9$ zX}z+m%;z0O5xbQAC$cgZ1tjKu9PH;pXzqQZWd))I{R>IP26FmVO2)+rbmyHYs+zDp zpZUIfe{}xWCh{RrzpZtv6oME?9Nn8NGZWWIAwWfx0T0B0newqWJ#Z4*~G zVVoX%b9kUFswj5Te|jELX0aDF2N=Jpbc%N#my1dGU+;uUR9uGSDu?&qROVE(bxhe$ zJeN!Y+qbZe@u@iY$QFT?<#sK^Nj-FnZ80Z@Ap`3KrCnheTwm{mS0-Ge*|i|JtME62 z&yjTKLC_}G@sJy60uUYd?mWt{WZ_7paEJ{*%T&q_hyn=8K(x!5~HLT4W;}Wc3jLLRniJ16Vf{TBk0^SvvIKr$6G69+wE}J#_l1vBHn?p z++}Br!SJyLyTQg_rm5cC&^>Mb>V)gK!eyycVRnHi&!n)fkT4EC9&kFA+Esn__-MWG zx?7)UUm_g3+G?70>Nv}LCzGXXKmRR>>5BB?$8S`73_&nx9WCMAg=Gq;L6w0m$vcnZ zD#STs-wjh$oT5O4=Yw3Eqdq)S?$Ze@cs3zso^y@iXoG*TiEmhn>~FG!`0T1M(^{F_%rH?0zRE+ z=Mp8AD|?+w@W;T0*21*U+vg%vrPXnU2p{G6Fo4iLLD%6_pFZRb(?s0^jc?kv z*&)ImS~im^>qu?EHLfXa6jcxp3!{qB(Bi`Z&C-)!$SaUy2OXUXzqQ+Xz#}r!dqBfr zZ+~dn_%^9BIwaw|w5wKC)EvQeSjVv{`H~dnliPvxRRA}z5WH8 zFY-b|JdGH(JyyhK>{8Fw7^ka!+(kr2Wrzh^xf=2`$hh~Y zn%~WywGiu0nZj?Z-p+zPmqN(OW?;bvw?2H&^?QXx3~mgceGeu>ylX|9!d|p^SqS-C z3GWGGKE)H-mflNV_`-Fdg@osNpqM13D$7UPcSFQ=qAGoZ6Cn|Boz|Xs@~i`hsQjnl z3PZDOOv|@$@rQ{~4e_+{Kbtb2XA2nRo8`3@?tMQCQCp9vR0jsH{EI4?1i0429yyg~ zPeYuMFc6=De1-@hA>92XlFErLa#Ku%hx<7g5)ZHdKp_1s+6nLth6nTHGG0vQ9pcXN zgO3P~Ko7$+i4f<5lFe3g^1VYw13VgBGhOQl6_8WR zbj0qTmAk^C>J)js5lzCD20m1~R!t8fvCLk&0w!ZfXMe2qTW#VBiVr*DEY{z>#Q3$7zjb_irDNo@8Mr${@l-h81=FPdqf=K2 z-iuBtT{`h~q5Zd!`^IjQ=5p^>E5naI)KT5e-I_5!z>X4(ris6edUlS!ZmLtlV0O#N zw%GYhJW0*wCqn`8gq)|_&*j9FW!=_hr?s9XWc0XIRNPA_KHfzq`Kh+kVI_Tw$q9x8 zx|XTgCg|WB(^>roMtn*;hz%DtVHM>E_-}kP0f~LMH7~^QK!g!l_sUfh5tb90%;%H2 zc3{$>LU3|2nE<{DE_s9(?z;mX0T!g2EWa5wU`QqaASWaugB<;kae8l<4gf}6paPGM zazjQK@tzZ8T_U|wTr~{@N4+gj5rf&=ja*nWckYwA#Wy}9L6!4{3IPxORJbT>r^+R% zDsXCYlbU*{p@e$8FO7+;V57o-ZW-JnYD9DelW*|N=ko={l_?YpLp}?=#kh-cmp#!rs-4SjqWj~RS)uPrNVeL} z&gbB2FZY>#vbKO1?ZTLj{t;_Zqa>%wcE1oFlk|nAsC1N($s~>N*1!0sQNy?=yK3Il zkm^m8GT}i^IHTt$tc}aD*wk#kA4GGohB56lYI$erxcQf3-4>*@t7Vx8W6c4t$$=mGk4v(fa=)Y9oJ<&PF1% zt-lzH01X?!^oAA*7Z}ah-xc7${~c;<&_U0CmQeu2Nb6M+JS-2c+!2Rcfn0%^fGPk7 zhQ4c;2p*iLw0Zk>+<^u0+zot%_vz#*MFJ)TSgWOcP?clp6V<6|P$bYfMsvH-%gY2z>Zo_Y^o&BKr_xt_|X+ubaa9xml^CwLVm%VR`He z@HgZ;ie^aqAh~p6Vu~>~tI2J)YOy^3an5@)n?Lzu(lw!&>ZKSo@|hB~8;Q#?{ef`_ zSHA8`Tkh?VT06L|m;xD|oNK_n?BJF3iZ#8dbX^(&ygWdR86xxFMrq8+0@dFFawQ8G<-v+N#%|4jA5x}7xMcb5@l?CGRD%F=!x`tqdxRVqb>emskSOeM;C zqb>*hX7_+4o^HE?9X!5^bhL)EzOKXsy86({H|8HGy+fB6g$-S%&M$slW!Uv!>0LC2 zT$7?HPdQ_48Ec!w|yqUgSaCbOWLfz+%MRcx5e+w?Y^W# z+Ja!&p{Prc9=E<;H-N(v8KceTy^x0W!=F!qn;k$l;pCYskiyTnkY)cUo~Z8FfK8?A zT?0F2@rT0!yu+rk``=niE@xh5zx^K@4}S($pqkU$#eJ~}_b=L=Jr`ol6dd7q1T2Qtz(a<7r#%)`ti9>Y}{XW<%#cwb9yj2P@g1j|7!F zFY(C5M3ak;^cqgS-t`~4S(zD<_1_}C=y|qLF04ZJ&s_1uX*Ior^T;s$9S}R>Edpdp zadXOA2|Id}1y@5dyd7>l*KcCZ*sb%*XVIX@Yl?*;6v*W7v2hii!>AlCKopBNf08cL z1~b7AmSq5C&i8X|4;$~EXE(CD=(Q`4Mj=|(8!&?7ItAcMVgt;%&C1zXw8M%JSI$^e zEdh&V!lzWp_^#5VG7GmhFwYO3=gnik@a!~PQ61Hoab)GZ!=VA= zqIq;*%-49%gkq&|StmUGV6~*fY;hjY!3n~i)`FCV7`U00W&A8dK#pNwgrG>J> z2uYvyNgOp!F+=}13k?-(iG|xk8WmAz3Jx(l#u3I%6D4&7sHkwFgs|!W_X08k5;L^xq)n8m<@I*z?T=~Q!fd8Fn?5%#zKZj@|jdonC}DHs>VpZ zh;SENr*Fl3-X1pSRO(82s9o@C^yBTp#1k0Ip3eJLOrHpA^lGlZ=g=3Q%(?&M*$L+x zIg6zAq%KI~Y=3fa6DIXbk49oi8L1N{%J|r9SwJiIg#7-Ph0hsn*dMeLML7hB@ZUsF0wC;Ok!7#!`Z*9?~Xi_sTeu(3pob^A$)heVP9vvE9aDk z{7ja-CzXQ!wvz=>NMMNs4tBgjyeA;-eYYM^C8EZ^4&ZfwRJBQ6K{zm6=*y1t!mE$X z?q$KVLRX*JXVJDd+WWU<#$-+kX832&~W0XP>^C3d`|VJE>(CW(aTFuqW7*ww1Yp{n<~ z_Z7vgV7o@-xGd8{!01;gZ~6qYB&758Kkz&PD0EP5D-2$V8=y`HrZui?dpFRRwkA2> z&e&>*E*L0YnyT5_B$a(C8p0K1hDz8looyRKK9STL$H7-9=HX{A+ya!iL`> zn^&q-aB3s%YfZAdMC3C_Yk$)5cW!vG$5Do7O9x@RDS;~)Oj0~?db;&>DJLH}bit%Ga#o7iu)R8^7w6k)Y*war<(EP`3AMy**PPnxykU>T|{{of&Z3lm_&LK(sAgM3?Qvn z-;>0zrg9ozj560v_}7Rp%h^jhxvXpWwBXEs4b^X@piQ?17v%J%_V>QJVRROy$7F1A zd_;5pb-HiS9#IF4ZrE`i>t=bBcn18fkaN`uer=|bXQ0XOAzxJn17AR zo{UC680Y!GP$J{ib7`&bb$r*EgU(;TTijiRTCDV+EdSJhL4@%#hH%fM_({FVro0@o z6DN53A6^_ss;4JaQt$0d<&30pNgGUF;1b{>*71vNTRM(kLLeIP3+Co*pmG6hXs;m&J1cCFcKVQr6cLq$^+*)90(D%i`6CuY;J6mYk|b_v9r{WF4f zKqsnjcrpKBdF*z-xtfcpJz`K!cxI=n6EFNf8URb- zWy|0de};aC%zavhchz6gG~X;Od~D{pA7sB6B(GiLr>IwTU;7Jpu8tc(aOuL@uq4s` z0?z3$q*4T&dab3t4F%>^Fz7(GCoCe%_TWBNi!vM+N)lBDc8ACTba&N2=;C3X(Hi8< z`YWW0Yk`7lri!N%P)TJixY+Z0f$Dy_bI6FYWJ!Lulc}fE&7O4j7G}WHh1A6=r1T=j zIa1EHVkF|3IU_uJQl}0DVHXV5D+YrK^DZkGbubqqk&tXw3sqOL=8z70 z0v@u824R`?({kvzxehQ-3l@*##1davG>UciJdGjsGi8(7*L5L*GYXX2*P%?vsw2Xb zzIBxR`<}J^5sI0Ps8wyRc3tV&Mc-Ny$+*N*G`kJ6MUL5eC!8YHfxAVVjw3oOaxG@7 zbZvgrm^bK1<2QgXO{v1sVarOB*cx`|@|heI)L)ggS&b(FT*+Vn5tK%+;m~JIjFYaA z(PI7b6j4*Pw2)mz>n4b>;>m9u&z_jQCXavlJ&g4IO&caALLsL*2UUvZds<2q&km~aRHd)LujP{To}Il6=e9zEr;j}^ zqFEKNlW%8EnT#ERoR5kv)DW}1_iK`L7vbnRV?x+n+lUL_3(@e|hMy97JT z=ovDqFQZpN56Z3gb5iZJ_BU&M*Wj1oRWcCycfns6>{S~hW_Mg#@@4g6ncEw4Gg<8i zIV)--(zh>b>V+++Y4Ijf~;wKdPF$4uV+^zPLHVI zKg*kadvLwYF2|QvX}cLf0a(EJ9$cxRRTE+8iIu$ikc4m?lP+Q=GHIlX+{N00;681f zX$|d}1p(zXAqjaV-&64Fjk8A};xUF*fygGtH#$tZVc|(QV%$B_mdtgrv4M5}n9bHg+%C{cbE401)3n@I$9{;=iXT{1V3U^O0cVxOcICAk~YRWEmcX~nz2Tlc-wfg4wzmEcGU`0&fWu7NgS-9LzsIp!aPu6ZzU zkN?g*WhK*m{wJE^$ofo|oQ&Y)0p6L4O=3UApgC7HLA*eBLfPN%6gz*|)!dDJ>IFA+ zq15Edx9hJHHr)bA76NB&$8vKra@N`x};fMSS6h zS5DM&JH&DdFL`TAjd{CC{Em3%iCbL->2q6t4rnz&v%BO(se|OE#yDPS_+^S6n13|- zP*z#cbuZ;RWR&V5eBMOi_xUfMpT%279iZQ(b5M8KoMh^rn@q@{RMpwAU&fm}f32Z>?2KFNO@##zgv!X?8Lz)~$#r+zNMXE6+t-?D0HfHZj z*L$eNOL7kdTNO~pDEo)P{zm*Pn%c_KKS%wEtB#6CiQr=p9AL(ghk#(5cTvt#gM{Al z)a$%Ff}O)3RTLW)T@S>PhtNh!-)9ehG!`jhQM-57W_tb(*Nw${pIyiJVYh^8R+sZ_ z@oCX=96@lG5%AI>mioPi*C_A9*NCY5@UhIkmy?=@T~p3>P3myj%Ii({LmSTBKPA~( znF<+cln*7~xAzoSo;M8RC;TJ4v}xNl|rga5vXrjpfxpCZw6fzJAf ztoDYs_q9(f7pi29NZZjZxnFqYqz*?CvUNHU(`JCof5>~2)&GC;KD`(Tz#mSrVi+-M z9OZWS-g9B|3n_=N0~7K~C?_X(lLCb0a1X3*ZuEf8y}+?OC(?izJ$MP1t^j3j8Is9} zbf8AO*X`+m1fs_jCxQofZ`gyrNgquCmNE{@xj(R*baQ0=fZj5xaZAbMF0V|lxX zoD}4yB{Va|;K(fI=B)!)iEJGp!+pp*E7O3|Kr-LYAyuI%z{GKv#~>3G2${h@dgpkw zoTViwa%)~0oX+Rg)1-@^hA%uO#xSFRnWRq!q$7Tvi`NXKp+gP1uR2xq(!Th%w5=3{ z`jTfY-}+|%7CKZTvio623FF;WZzRJ%7@=u2pX3`>35;9wk|dESOH`vAL_(DvEIbQA zNGr_QQI>7FKi0XymnJDdP;54xwJnTTk3b1WyAjtY5le0N`QBRWX2o)rj(uPFy1bC&VEk`t^!rTG~{rBkD<4r%D?lWfQoQ`uu zB$QJCsYwAm2FylnGoR=4IsM0HT5R03S{#I26WFlAvlc zLFE1A4X1BV6AG2=Q%AQMH#as4nv}IGtQMIE5loC&3Mn8py2iBf!{9lb>|89o8tvZDU!m2egIhEAVf)s3i^B0PsVxsqWb`Tme$-D zGxlnBQT6nXAPPYKY@h{2Tj;PGfvEi}*0&oEw|Ve#RT0X&xy6zhBrdU{+tVRQ*+AJA z3)+(l6heg2J=(S`T$H&Ur8BK(RLFUOEvQ2ThfETZ-XIZXln2;ovD5<7H(H*4gcr?k z2BWd|P)RR}JoHQ8zV+*D$ux&E74_?KRBo#Y^Hf)kEbIHqo+2F#Ms=9PL)oEwr`Gye$Sc@4z%$^ki~Y+Rxdnc0(kW`g6{D=Pvp(KrEK}3M z=~%}&0$lex#Uo<>als{;zrC%;WfnC?X1_9b8nAW-<(a&qyO48 zIJsJKlYV>~oymB}c@7qga2`=&aXWt7#rI$O+gk5wuv0E;m9h_ddM~g8ke1c57F+&E zw-pk?(CpV7cc_VhS&TvynnWa`8y3)I5|7R_0Bm$(P;^wG5tuFr93#LQisdZg=m2`u z%wjqO@_|vA4W2VG_h1NMCzWD?aw%x&tIubUojWpRm(U9D`#nvC)Q=Z-f1}89PKW7^ zfSPxAEg4u9(tTWNs6*7wfY4VGIcD~iraToaJ#o|0Tc>yeNrf;ADMl4O+1<1gT~Z%v zqg683PpYRh{7w${_yo7BRdE_DY%M5KtomVzrOa&aOzX?l=9wuEUD3&kYOfSn@`s5wi`^mwv7oO} z1y=<|UQT?4Ex=NxLjGyXAc!lqFhoGvxU~9mr7=WkR%_b|gYoAT$!hB9M$~lfPxaG= z<<_O)05&{2Hn^uLuhX-ZW#`aIQRV7cc`ch;>1_W|$Df1FXNAw;?*b}t9D;q4UG)db zN-e#Ui(gcn;q(jjmZWIN=|@#Y)jUw(BD0IV7Ktq)n)x;Z2G~{l`;WiCHE*1nNF#pf1JE^)Ji|f^5N>l zLi{QK89cHgw9h7&KDRSrs-)Q~uSdxKzZ_J-n&ogT{*_NZtujbsydVQQI;K3HYz8Q* zfOrtp5<^V{_x;e6H;e)bf=W_eKWV;t6IJ2MSY&KLZv1qcTR?b&h#<-vI)XMtmpl&F zUlDC}(M5YgeFwoi>yZQNGp-I{lS~eDYG5chPW?l7JS|*O9ux>t;hH0=1#J>u1m5Yf zi;}D_%pvq!Wm)b4kMc4W{V_p=vDnkj;=KdrXlq1)$ZxuW(5=WF+Ovqp!k|LA(mTb5plKm}bkg-( zr1NCnrD#gI$cChl41OI*$mDaLY$hWMbiSAy!3J48e=&DLvdf*ID^c?tReU02D@r}o z=YfU!@&uiezfkYftCA9Z<)W>k4%A5vTK~kDAO9r3)(9OO`PS%gv~i)(7DwStIWVx3KH71Vsbx zjj@aE5*K?NKYlXjiCH@hr!78cQ1|_s8FpOY}A538H#;w!goiSMw z-Qo-gto^BUOU{h^69Kd1GD*2Qm(OnyDH#)DHX)-4V-Fq>b~?ZH+pi=*fxe;AEA;Z& z+0Q@hCES086bTa!hY=UXegVYVzlxx$E|_2JyuIk*EUk8?*uAibyk@oeDoHvquVFN$ zKqn_}QtO)RDp)$3>VPXKIe+};74-ajo~p-^(y0Tlc|L`J__Jo_IJxX#)a-U)r}{F2eAmP= zrhOpv?711nRjr$bwTr(vJoICejM&nT)7j`oTj~DAKVV9-e~_#tHe93X|3lK7vIFu~ zY#=rO9S{{cMCm8o9boPQv^!|GLDEl6K)2*Hz|lq*x7z+KPpa`7qd#^tl7@j5hR3N! zab{v66|+jI@vX_)93_C4C2gDDf+oLEVW^$!!qz{hCb?7`yZYI?=9TDu6Uyf{UW zIViPib~Tw3V8J_}pIn~^e&23@&-uqL^R_%@37id+Z^fU~=0kBkFZp7$;Hs=$WoKAf zDGrbNIPiBr;lbg1pb%JhUp8^kw6sj2!pCMA15I0*!B(bU)5D&&y@y;^247V)w6X9y9(65%btrGFj_UI)R;Xu_4ODr5|HZtaN>E7bvuWyrXsYZ;Y0Qa zgWi7Fjc1~LC+w5b);UZnu076Qa@;FCY+OvF$x!?o zShjM=lC_Hu%qi?5huu0mUIUe&f2Bw>tPSqRW=_7qac)NFC;$A)pqg;S470!xtz8?A z(5Z5tbcP_3jF7j1zU>E#3Hz{(1LwYz0O_FXy_` zfdU|nZxSuNn?dPDUibzicogRIeb;#lm|}ms+%)(u zf1OA~#k8P>DA1ImXnV8C_);4F`m#lYHKLvS)G!kv2{g`KJZqjhpv(1XMtvLKytGq? z=_ApkU7^(6px4Yj1^q*cYxSA(PtOpsY()bNs!^)&Dgj11mC{-t2(M9U8(k(n(v!KX z1xT$;OI6&S6-ncS|KRg0h_)4qe8TpI(CdYw0&%T-d?aIIdiv~VO>OGk{kLBC8-|Bc z4FxP&IpDZdrIk32Bo*a^A{8n;nwze88Y=6kBW{ccv945ayL|mh-8yisA4gOF$lwIM zEv+Gkb8wqkL){{n-9EisLTX6~=bx z-Z}g2d1cRP5A?W-_S;vjC5Qr>TD9GmrQ9FZi;Z$m#3zIT#n{%&JMH5=vFlOWQ+5ye zZhu(M?9XKP_T%NHUerIfT!L$FDXZyC4^sZ$e5p*ytD4l535wAj=(yL zNNO<7U*b(QjyuHBpCV3|KoA_@64}YKUvN#^GTONv$oo3jK)>US%P!@7A@t%c5z4MZ zN{T}3n*yG;vLMxWL9d9Yw-j2Tz763BMiaXlLH9n-C)g1Oz|5+nTBUP#SoR;}x8>y& z_i0=7c_s0bAVCoCyBliWq_G7u@xV`=9Jma2)lwxqI*}`AiF1OJ(kIp?s(Z3z)DvT} zeWTre)I1`1(qySNDUl|ve;oT09VRtx zC1xL|iKLmFC1$}q1gG)p>QlX4TgZPF?=-OFBYQV^3*=*L5JY}vKV&_mwx>5A{w}*0 zax;#z(^n9&qF$Mz;RBWoKfzhMdm#@oA`PB?vY?PflpS0Hhi22l!O6*YteACTnSW@` z+3J?Nywj9DhZ0htA@)Um1d72NNUbkL=q;HhuM4_WHs@D;9D0Q;z(Im# z$e^~j=4?-*!cKBt5M>pms+G0l=bMhG7T}<)u<2(-!UcRI<#V0BEqicFgS~yFJkeyX zo!hgg&uJB?OzDb#!jyyGglQs`3PJrq`0 z^JazeGapL(skkmHh-6)Yj^wgPaz7^_^voLiKl9`_mbMkAm_%U~_v^blt*Ddn$v(!V z>o%mh|8;Yo@+UD{_ZJG4KqtO`ACW|Q0@88ufA+eg;y>KJsrYxVJ8agM!q{Ap9&I!Yi~J1N^Q z!tqYONustT-MWF;7cbXgxpFb$*k#iohx?+k=M!FXtb6&y+mKtF=&VNlF3V;vtG?Sa zNQ?qIeVp2Wy9@8(A-;ymZ5R_;E#D`mMuGHUX_N@{XvjN`|@cL4s0Rn!_F zCzH%Ss{l*{paHlIPgoNY6!91hI>y9Smq~*L5EUcfHf1&2XKXzjJ)$r9*rgq{Zi{6P ze56;TJW>Kt{Tz5z_+yx8g6($+2jaj-4d~Y)saf)>z;fV?b-FmXSONK)KxU~&j*Q2n zX1dFxT9!!W=;}VB&uO9#I^E{ow+ch3Af34+R9e5RE=^E3OwJBdersv7!s-=Xw?JcG|M z|D0lx&*(&pPY)vzlU&#&d)D@wuI-h`2qLM4`&2<1pI67V7GgiyYbwnH>KR#8)c`$Bjct^!}`PGcp07M#R^LS zUPFx+<|p-E5==B9+4t`$F{3^)7n58d7Uz7LuCTf}J6lvA;0swC2HWctqNa1e$)j4` zqmdEiO_p8zsVx~)O?*39C$bd4nH|)f0F-RbI)ObdIY+UfghH?jHr|^R2~?M^Q%#ry z+avhHnMU%mq6fle5i8C?G_t$Ka!Ef^X{^ubXWyX5AdeE>s}~OAwK1?1tu0jg=>Lh( zI~7fc4i6Z>+>E8IUx!2vm)GlZ;t5E=v=hc z%^C0pfZt#ETC)Kb2o6bX9VMUp)CJ^6Ldj3h7Ak|dvtv1I)Ey?{8-k4)j5v${L{wrI zKioSj8H1#dY2iaKw-zJ=bQs?k07E2o+w*$ zq5O*UFps@-L-c^u7F@pjyfFbyzJ90lz-TL!7N0%rrOcLjJ6lRyDb!+vnH6lsm5U5& zn4KR6un3#s6LwT0IFangEX9y?~CYKi28a|TuRVI=nm)FsAwyVB; zUA$%4e@|Hw+IUGhWqGVqJE2?0gTBkqT+_gp#~~4F)=-mzxeMD1$EfJ@7(Eo%%*)Mc ze|X*>uCJ%zRwnMn@bo54)2jYEJ289q_dP3!%|qWg zv90Nn@5#4Y*%d~_4iiT7*?AVQqg0>R^zbS}*N5AFpM6AVk5-UnxT1NZ&4~Z;Ivww@X@b{rd;*WOwJ;H^-Il3#RHGu#)5DExL z1S|#!0+cbp??3V2!(;=(Vo({iJ}td*14*0ss}M6pd!0r=7#Avmu~Hl8 zj15ejM~LEZJTUzXOG2|v3L!S0*IK^?6{O0wDwU71mecqr93-$!t)TjKdsfpf=veV$ zfWNl>3eXwJ2bMHoEew+-DuH&-HLQ)8fnV9T2Kb|C&2njhcW(kE<5MJ)ek+{T()Q-q zJ-x`Ct7&X8&Tebo<2%ZkTA>n4Y*zM}J3C=?K%^9fVxC=^S=*=3(1QPr*6>We0{ICq z4`QC6t70GGL$w6V2s-202$#^oErZCI_<%`1M&00s`JKk}=x!o^kQvsOZSNKlOV_;^ z$mNQu0-`*XHosb@!{PXf0o+O=9hgr`+dQSa=G6dMSVJmkp4iYk1;N&gVARPz>(QrL zw6$yfPB-X7?7nYhCZnH;TXJ15ty!AE7u?SWzd0d(hpmvntZv@F`fnQKBR`Xo0k7$! z@@w3{)(S46O+}^O!~f7d4sAjM{hb9fIno*bgYu67S!l-+1G``WN}`m4TL2be1}fpQFK)I>lAWD!a>ZiT=}oidv* zAPOJ{ptu03N})7#b~BdOhrAVE(3$;H*6oDX<5=E{2vo*@YQ#~Cp(V)m5>2o zG7p#dVgy)ADde3dwZt?X)D5|Z?&AT-(Y@m=uk)4<{1^{AenV5~m$I>?`Rl(=BPp4d zB_6~GlUKC_2o9D9T&@#n?tqgi)!JoO+;kSH<@H3z1OH4~Irp9R4qvioH22l-Hvdd6 zA2g*FQ6ed`H7EwFtt?5{p%>Ac4L)_~WZ4vEq%RT`cgAc7{AGPhw1|V`F-n@GbpIuo zUN!a0bsl=F$>Qf2)_BpDxQ`mxR{DkYSmT{3mw&}I>pwUsn^vTf2QUi{{fOoCO%)RW zYPVy!z}Nuu3u~xeP8Ev`)n`SGQTky&*Gtl7ZZKx*R<$|Yi8{W~w6YWNW zd4g4%Sc7UIT}Io6c6p4guh<9v%J2GX!;0*v5=x!{$fb;YCrhA#pdlP`Lx%)Yt!9q@ zeCY(ZpoR1)r}we3McWoVzA`dUL5%6rQs@bS=MW zuA^kKzkOJl=J{yZz>Hf)azV%Vfod7F5k%Bb>h%wv@GoVQ9~CZ)mS6JUOPE}PkcPVa z>d)tUtFeXEg0bO<*H`)TWXKxRq)!L<$-I28v?Pr8$PviJNd2>~f_MOtZzFIN=C)BL z?HfgMuclv1L3eIUGyD{+42R+Fg?51t4EqE1 z?@}%Z(mZL>CO@87F}0lJlf{;+vJx+`&mY{~0~|Uw+vDPy@C7Vc=(M zBjqby>F)!kAmBF{3gPFFkFqLZGB{qj@EaIh55r2KuMLUNgP&5Zh9#oWXQ#lENcVxk zq6#6#6b0y+0K`NK#SYrcGp1w&M@xlIS5dDrpxyY)4(;NMYX0BgvEciGw7$UMa5n%> z2!acS#Aih)(S=;bA3VAVN~)`Gih#Ry^=aIX0mFv$l^qv3 z7el%=Y>lgU3>8s-HUwM~)PUgpdPYhzIyt%GI$1yd`5R`qHzF5J>2iy3+SdcP)My>U7bug804#{4DGG z`~+}%#0_Nt!OeueQ8Zir=_!s3hg4+7iX)I3_#?-O70^Ecz2#L4iAi-Cgxx|Z-u(l+ z2j~aMXDX2z)a$K8F=&h(B7w+-xc0Km&5BqYsp5lP9wfEHwEc!)2Bu2vz5S)XZFy7CY;rH7@`5GA1`B24d}#5y8VG*o0HxoiRUu8oEVvV zq=)APDsSq?f3wctU)p#5FGY0u7}5XH5=74eL%h6q+0}o?R>WF6VXsNWdmcA<;*m+< zu!BH|?_sj-~$b26({ z-g{VMRpx`Nx^iL)Khjrqimd* z^`YnI*T%@voiUK;3xJvm|J(vjv_oS|h2-gjF8Nr=)HziM#Zq0-+8dg`z`W_s@iEu{ z^!GmwW?#~Qy4kXQIN{1Xk zK#O-RLxoaukq%f=5Y+g>tlr}{Bx+czmJLZpP;7p(*ZIM%^G3X(L9KjhzvX+ge{Ug| zTiHzY*3r|=$SD8HFg7Z+oQ)dvrwi8okQrldi{?>m96Gem2qjd4@+;wLtDPlr)^Y8T za(>}wMA4MEtvTkhLOJ*mo5yb^=GOE{FI7MOhXIQhSBN9P6j{;_ofuNQxMLFx> z8{b(bqf!xT1+}c%EGlRI=w!)9Y=W@z=u4S$*93^AWsOq?_N*h zy% zBPrA0PXne0!q*I0v(AmkfiS^$Ie7XEr`y+NV&B_E15G0DQpSLcsq~f!#irk_*X`ds z*iuI3(FKU)hpwM(YPgIXPcy!(Q(+a+>J3j%i@(gjwIjpZ2J$j>Xi;Xmk+6 zK$lUgza~P1^r4dXO-Bny)4^W0IMJ6dQHKmIutBe2YC!x7jsSJ!=gsf=(fZ93g}$;; z16-URl6{sDxQg>G)sY$uJYK~&!Y$;GdfUmYqkz~Y-6=f-uvFQ(`(e2zR1k4%Qjn+i zr8F|-hQTQFiynOocN}J22Jq;dbxNg{s*tTR@%PcPct%C@e2>{6vmBNs@_xfq;rF<$ zhXkctG()T9mh?il@>A8+U%Ej_RWm_6m_^T#og2|En!|#%YO7npzLRERcI*9r;L`K%$Y-e;L76#3`G`KRRCa2hIz%~_4LBMK=ga<4oZ|78HR}o2 z{JQi&puXWmeIs%&bOAXio^qFR)Q<6bFC*=%L~rG1siYamZCIWNEV9I%C#&N7 zd0k3p)RRuxv1OUQpRAFM{Rbdbh&12mw5vz||{w)I|D0y{y=*`)O9_jQ@hn#ozua zl2kU}!(jg2EX;lfg2@4Bg}<^CJDL#NVNF7Cj9^>b$z2e!RzNEB3K=KzyhhcY{>H^W zxl!^pXl*iS_{)f?a{NyBX$sh5U^zz7;WJM7TAc?N8XCN z2a544z(GSQI&^VP#~~U0dz%UtO$H%{Gnta<(e7GeJgLCg_2QUX@9=th)-NlT)KVm(=Jz ze(YzVe`#vRaHOD9AZq(<{fIn}^_%zPG(uDn`nmb6^eKb#`g#y)Ka7kDLz@0L8n0I0 zoLEit6I=%M@r%P+J0@~5LQt!3cBPS;GuqLsX2_y7B>?+v5;1Iga1X%mu=1WQ+fQ7PU>{N1-uX54L@GK0B2b1M!GJ0<)?{OXyjJtoB(HGiy z?Pt^{Unp3py-&sbU<3Q=F?tv)eA;;xmRs|xQx|*}O0ZDgT}vf>|J`l&fJ!p3ufmBe z?K&D|(+Cw?Dz0$@g;wLQmdGPL&eH23D|$IFeiFgNC6WAP+o5Z}_uMN!v4s(JMBn+{ zTeL5Pm7hxK%4(G&I?M#MEs1Jll#dj*CN=bGfK6 zJG!)_UF&Gr#970l)NFe6aF68MD1U+sm894bQ`JTslUV;mACeLv(hjF=2HQ{TY9mvR zi%804{zDy!c8H77t5W#P4nf?V6@(fp@vtBbK1n6F`Ra9kJ@-p==YjN4%k=0IflEXv zUlJMV)D$+u?aLcRugIAG1A!$)$Pgh!aaHLqopI>r%Ime*F&GIMD$}l=$}y zSAT-0I4uW?;_;>*1U)Mz!^`sEnH-1NL2`a8JzCEe2RCe<@ZIO6S|_s~N>3{g*&08Y zBa|6_l=A(XzA(&Dwb$9nhdq&GF#ol8rDg@#n4`lw{dmRaoW)OtH2X_}Nl5AB_>jQA zlX?x`_Mb63n2#s;n4EqyY^DT}GQb`?lPT+$Pi%nMGJEgNN3J2GDdi_hrYU}I(p^c~ zKy4W44DYPl;p!|McA(C~1i`=$6Oa;tytRV0k||h}y?_xurY=J>lNac6_WXEo{Txl% zDQq*+q~P$Sh94kVf3}GGpvKmtE#ElX%6V!+*oaZ!Dw80cPp`p!pZ^=R;h z25JCaFBec*4VHJ-+mNePcaD*XX=p2Z9nbZWE=iOjf1Xcm3-O@*G*B4v6`G)R%b`g5 zW#s!!`k7N8hX1tt^oj{~OgB@wDc1(oCC!+O@FTcsIyqR!unzrC((FL8fE=YN-t3-W zuOVA`;5iM%J44jPu_d;f9i1n0sFyX@Ms0JZ-d zti|499>cXP`Vp=~z+$1kKR|I<7+v{u{5Jrsf%&#y*bA9-a>6>R`*t{w}755Qbh9})ijaGs0WIYj&U3| zletX(ktH2DEW(SP6_Ov$|8bKyZKozZiVNpP`xD`&+BeLXH!Alea4M*uZanKZy^x*^ zRuDf81M%$%I+yS%g}WYtsP0Vy`|5gg=Z;VO5&^+JRypV-D_SE$r*~p&AG{{R7kL|I z32Jl9lhyLgX+~69`mO|^N#ll=FYERZDr7!AudGEk<`uzlr~5J9>ztc6&^SuW*2HPm z#_zk{&_PD`lfBI2lV72PtBtxMj#tTut84yjt@gwAWJUZ#QvyzHPv@Q3Ug!M*d2N0P z_^i1W)&ctjU0aK!y~STe|)Z(3Q;QAH<}tlSr$X+;hJK`o@DiG3o!NDU#_|izHj& z)u{BpVu9E9c_43SYYvbtFx`;v*x2KgNme|)AKEHO?N7$9Uw&*%f(!s?!w>ZnGs>R^~p6E)e%2?YZ6@+lVq^`?GNi4F=B~_ixSuX}QpuTzj#ufr5 zwh8*k0B`cLb1Z7WJy@aYX`YZ*o(8T66FMJ+@0AbUd$qKO+O>R^#Exk}lztP0MD=q# z{3Q@iY}zvhdrYpVgsl)nWxP|LX~LxPrp&W)eidjI>AIuHc-5;yLi@y`uCEY}+3dx- z11@*VSm(a)%I(l|7`iRJ`b@dO3zbbEwfgFmV`nG>PIn6a`m3m-4N`ICEqyjZ>pEx7 z=d=gV8z@i;a>m6!Yuem!fc;5y5r;@=Wd9_m(spr%-a4j|utoy==TBYLDS(t7=ge!g zKaTEt^_-gf%|ug8w3o*Rr`MTS1;TozrEGoY4T!w&lAF6^F}+3C122vFf}VH1ULJL* zEui9`b0qEWnO78hG?hniQ zw_*x>L5B$fx=16%&m`UIbq0Lq%jsdX)~?F(3pLcDmb+RjACgsiKJH^Ngu_1V&q|8Y znIrh_an$^hJ1eS)JswjVNS_EM^!)j8km~chaGIR88ji{%V32zMQu>UrFYUf!%0Q4KzNSett(`4@EZa{+a{-KCDtu}?DJ}wW2~!N)UD8|F=scBQ>t5lj%hP# zFvf*_VW1wB(Fil5Mq#3s1ogk%)w}BolTCdSpr_rIUV6CeUh!{ez3vpYKP~tp?0?$I ztL1uNf3tddytI15Q))hwla+1EJyf{rRv!4HyifjJp_4V5qEs58R&urb?sdy^LP=EyMx*O4!q4|z zB3#xPiS0J>3E3JpQuIH0iw~I{9$IkMiYZ+Ug1s9O^9!5{{N;vQrhk3r#1DG=nY?Mv zIDVf0oj3?I!-X`sMq*IWudev|hJ}Un&zNhv9Wu*90-5#B1(bv7HZxYTPC01=w{fl6 zwtX?}&X*V(85B{6@EMOxsaL+dvsW3MB8Ec1I7Un9SC!|OQvvhh9J2|sCwir~$C1;0^0cpIIjuLiXqH0ut-LWY7B-+ObkB9tK#ld zkruN5Q-^hKu`Q8(l=faiL5u@3n(R}seT^;GZVeWD$Ek`f|1(c%uawct|N|gAA&Fy>L z#1$1xQS04`#95P1=tcbB_xpVIRdU6-X2*z)ENMoMM$Kk@BLZq z6<_D$8GS{;(;ro6_<{RJ{b#5WqMS^spy9bkhW@@x%CXuv!n)<+zVJQl)o!+otJgPown0GL zUbyhQ;B|XawkM!DBivWokD(ghW0z@DY6+ArR2g347nDo@)l)Zuc@~`&EV>KD{nSb} z)Kb~LcSJ~Fabpw8$2WdK!-M4HlbS}$2nI(23C9n{55{;KMt^0E_YRqu2%qH*GU9|)A~jNW4pw9BRRsC~Pa$YZ$2>(=OF$UWwD=-&R2Bsg}h#3HFJ zZ-Eq5R*9}IJE#Nq=72=&%bCY4I^hA~)Hd?sw%OUT#0Dt`5!l zK7_4g=%I{u-v?1My(6FkZ;n)KxaQR5`ZgH{{UI~#bL^6izcOI(%vD)DX3GjZzN`vS zw=u78UnH2!w&SjrUDg|+&Z2{)27SGnoubb3I5md&jq|Ox+;cu8f8(aJ2pCFY{~ov_ zOW@QqOyFG8oa%L2*WGq;xNM^2f7RNgY5%MHgz4dURt4hz;FssQ&ymM}uIpWJc{~4Z z-KAoco#LH?A;ht%Jh*4F{yu)=m%z=ODu~6VA;8Mm>g}`Vr=7Pe+|5B2OFx0xT%COx zmldit4i{=xD^N!v$JN*K(cmRi_dNap=Ph*v!s{}ci~{7^H@+g_e{+k?5YlhxaFz@Z z1Sjmtn&Iw#aL6PLlmue?8XV?+E!5~O)fQEY9^V^sQw(E}G@(!_UAyrJQVJmOsUIV* z7R>mZ^u=`~c0mD(y&zQRMVxA zi+!m`dvl(%f`7D{gw?2!6awgw4Tx(SiTF+ge-EEDPWy&T{hex9%lW~*dA-=!A@x!> zcGHb_U7e`;s;YSu|4SUQM(hbY)7hUm@Y)B*mb1u=TkmX;77TC&@mFMMb=%Gc3`7PP6PW2HIo)*G5} z$Jc+Zd6O73xYFSzw}9ygARMbYtgh5m&JkR3iXS%d9VhE@E#wGY9(OolNz~Gp*+(;UX&rX_yKstSuxEm|(lZ%U0Aqs3u0c zDkpZlvRpy_>*{;g+hpUgRyZK|y-L1!8M5XeIu_U0G~*bY-m;wFTP;MV*|iob6(W0k z+U7PYnz*w1d|dlu&l$4#v5gw8XvVYN`Kub!*06_P%?5#vh_fBiLAuI;2h5WSD958| zKg^SP{jc?#I?0pJ2u8}ZQfpi7T0<)@gn7L)%QhOA$i=p))~_;Y9RmZHp&uNEQ;(Lb zgVkKk@%zheN(GOOw(-+XQ*Ra&pWj{S=(MqP8u(}j?vpc@1 zD~tFZ)VOfiZLmP2L1yZ0CgGrR9`|WiHP2Hca`IU-W4$5L!oIaIc|WV2E)-)*U$TDZ z=mHgYkx|r<9|MVp7kFs&vcJEd!IX7iX0!1~`u?JDbNGy2@JA8J_QvZ(k=sDZVFD$O zldtA&C+5%HqZ)h8C5`vDw}wiA(#yz5aIeV?CUh|zu!ngu5X?OKd!uR&Sh)CxCVKE~ zM!6vZH!nyEiwH@VdTd^9yZd^!H}>0@>^`dPdTD^rx@VT*2;kx#5)i+(YLO9`f`P<7 z)5+vpSzrZ!FEPO$T6YnR7wj3<$*RlGtqmQeDlWh+({PE;F2dL7mjd)*L>&IV*xmNb)8Es#0j)v}AE;s+%~$^YS|BhFhd257M2! zwMgfb&8|}~x!F&^9VRgkJwDgJTe*-PMnfCh5gv@fpg#R|mHc`m0ZZb&K~ytiA}wQO z>|&C0G{HN~u2uii>y~iuqK1X;KK1TLE_2GC`1F>8QC#9HI+0!D(l3+UA6bqL;Bln! z5?Pk`zG%hLD7uXX{#2?iDnpGXw$#*vss**AaAr5;@GmwLt$6p@>l)V`y3`!Q)6lt^ zCH1j=BGo3C=xA#<{Z3sigVS}<_Yx>n95iI3l=%CwSj~=*-SCGMN+@L@Kz86W9!xAk zx#b1ig5gs?FJI6-i%M7f;xo8{Uy?7~GuMQ~B1# zi^D*t{sE{K5H`x`st~6VAc=(j8qZw3P&hs3v>%jQsQ(jP0!dINoMeJovSAepWBgs+ z5wGGWkQkVGu8BKHS#tPJQg$BXHWBh$Z7}e5+ac@FA_g2(*;zUMh+8%|dC_q(zDKk( z>?h!PtFBh7bk@6?!iL0TYnnB(in4G;+u^SwRU&O&urza^wma=Sw(DF)alj}wYL(R+ zIC=Z|`^ic@QkyvIJ2`YNWX?#Q0}RqPSMqfM&%T}`a<(N3+#B7+ewR!7lXv&?f*At| zFvECe?=_;XqPXUkCgPTB+`ArkDV>U3!+d773hN~TP13?2NZqVBLfFlJe5Ac1AsC9e zL?SmrG|pmggB&j^P|Z*$q8!Qk%tLI(vm+<8#E?WB=}&a-2=|(zh{QLXzhPs64XX|w zX|K+|jG2^6RBe%*m&nkcrXlWsXR9~ikZZY%6V}>YliP1ew#PZ6t3}r-ct}Eoy;YRe7iBfvgNo--6#+RCabrUN5lCGrZOlw@5J0^l<-)Rx&Ygg&_&R zX@N^^;LO4yU<0Pe@#c8-BH<*|$YO8}-}+q!ZY7>dj9MsKiYZ7OJHRMFL{5AX0H z{_LVm{HNt*S`o9u;tfE0DNO>Y@dYKptKdo2R;;oo3{sL*AWh>dBZ>Ns;O8N4LjzjE zHz7a8W+%{e-d@4JZ$qC`HA{V_apW9V7B;oD?>)P z_u@zlTI37ys`CE&t4MT9sw6*#;0KY`(r#~;R_(Oq3bDAq#zk<bHGK)fg}Gd^49 z2}^_{=@aQ;dz6v~`D~@p&7j6F;tR1cThtPi+iq$~cFe_lECzCpc~x@o`V||?aZbus z?s^?^D=Jbz0QOd}%zrAw*RE3tD2D&>u0=7lSUmIQkRMZGTdRocVfgLk&j(b$h%T8E zI>|gx7FJg8h4gjq)L9);%!efeB)NZ^VL7UEa;J+hnEeJHuDD*4mxIK4X2YA6`CWlS}ews zvZqPROkaUGXjq;ssq4e<^%(lV}w97&NEHpQ#jf|;Dt>s|ApSZfYE`F zYnip0&JOIj?*aL0-EU=UABMaLJ}KWsodjIoOG^TwXCLlKp3#Mg0%d8&d&dm2)LsRQ z-WZ?DE48$(nyRuNGO^OgSROpk^<&|tFWB6?y5m$=CRh?N@4KDSXnKABP$OS`%_#`u z)pl}NThfl^&Y<`n%9$M>GK9t^{bqo}t_J`*x3G>30R$N7{!d#Jz>iy2?{7!{=oy_;6xFS;6nGzXJS7h|7`}vLmGr*CtP z0g_V6QT|P)&D742mG>rjj?4wrJ}#C>dN_^Z^)S5*wZy zwGxIF>*8B8g8_H#u93PI%V3cZoQcJ*>3>nR?ic>9kL{p_-ng|wqDfw`p=t(`*G;~u z?LcQ(oqSJHQU6S;K_i{%i5W$V&j6x!+!n09MlARfE_UeZS*Y3Z2(Pfged9a9mt#}Q zP;K@MEm6s6LUW(o=aNU^j<&2;snzV(8RIEj&&FV_piW_}8f|0H7M5x+f)8AI9Q9w5pH$LZ86rC+pP>ASuRHSN^L1XOz#-(KKGt8Z!3p3@MD$iiprOLyn=5; zV{^T_-X42ma$#FqD5R{`mvg2QCk$X3yhlz65u8K`I+bxjCj6&F21GCNyAoVfJ5(Y6 z?a1)ny`3fvF8U~S%C*()`L73|{1W~hVj)5|NE}dBx%qMHP~8Y^lZG5IQ!PnRkB0TD z#GRdE`97NZ5K3Q;MH}-^WZN z6%!K*7=W0te7<*z>E+UJ)R}jzfC4m%zN@!3BR~Q*bNj0590|?b) zv8`R?yb2X|0*ev6r6^oDXB5P2g6Sp_1J6b8CF(PHH&5YyP6{~F+bC!)R1k^X?t+bQvC98jn5rC6N}qB z-L6VYDrkS?*R=8Nd`y2fcs;KApwtt3^Lt!A|-i z{GubeF-oo1ieg2f^Q(@oU1+L_)seLl7ip|LM*g?>03zqp{k;*9k&&)|pc|ncL+_8; z5R$y|_V@qnw7*?50OrMCuo(Llnfn{WIa~8w1Wp?jEO0*i^N?3I{eN>J=qQ{vRun@UFD+VRb;GW`Bi)vb&|Ln6+aR! zSW%u7AvAjLM7!`53+2_k>)|UU8C96ivsmONiQ~a36p^w}-TXmEmaV}o;0L$Wt79DJ zg^t1dZAbb>EVTmAYCx=&Pt-fd1>f;KtkrrqBw|OC2AQE!iova^9a(39y*$? z7}{=CDxQ21Im)B)x2LT(P8IfkGt;h)Pa3Z6z9XS$`^- zq|u0>2sBNwd(3x96*$fNjfAn>e(~M6ad!KiVH0mh8;dvj1!Y@rxPJkVl#pmoOFO99 zJcG_^lG_J)oQaRv5l!Zpfa@Bg8h^2>4Unumk4%3$OkKR0G_wk$~Um+s>e@ z8yf%d0+1Sqech0{N#c|Xl#*xCDLXr(6EP}z)Dfn8E2PpTUnqIzuJx!nD;b>^bw&?M zbE%|RjE~@O#-bY^h*2JQ&n@70)^us}y?m%(abO1|KoUGvnPLnj5fTwK`?XRtzC$R? z`kx1{ZHEyokiH1Z|4MYjVjM-C9n#tlt4n3c7AU!2j={c<7%sg6BJYRiHbi^P@v+N- zIAXqZe6~TfSWkOB(2FB$ovc@K6k9h*7*=Wi?_6)Nj-we;6PUv|Ids=x5-6+K!GEUz=&6p7BK{dG7Ws)Qg^ppj>hiLGv02dAd7Vw+md*2&n+7iH- zN9NjT=hkOiy}h?eKRVAa^BXM`$T77Qw&Y_e68aB>!B>d2QsD8-Kc_(@Of$7PYgd z=HsL9wp8%M2u17%B6G|5U6nWbdkbOVvw?00{m%hA;XeIo!6v*6sZyy}nq*Y7nf!&% zPALsp{)Tl0Tmpwlxp#3+Mx6kFx_}O3@0TZ6BJ{rOW;{Wd_o`a>qX4 zEJE%o=0j3*aI-cTM?(zgK;+IE|Wi2SvjlCahC4ZDr<8_eAWXx{wut?&$!IW$M9VZOL z$Xukva8NL~Ah>^mw+AX0w6!Ho{c79x&#Cn{8c4Js(EdHcbYlQvz(HUMAa?XX2fN2) zn}FQX5d$u@%9j&ZvTB5&vDA%5FPVPangY2eqqk2`=d&Pp1AYvhf91_!FlwkASI$Yf zJZYKAi_+p;Abj{ED=@w{NKO~6{$a0G*W_Dh!XHLVJW!BHz_w=;-{WUg?#K0!EUY6UjjJ4ikt@a^+v)l;k+#}UXC&R_1iJK%G7 z$P)5xI#pSkkRCC(D;ekl9y=`VsWiZTm*enZP2)~KfVVKfZub*z50w761A@k^?I zeGE+OegEiM(42|m^IguUp>wsP)we~#rfgdjW}_v>`~v74p#X;$1cxhU0=xgeOB@R> zl>_151$ovlZSaJ1Ywc6}fCYRt7YPHcV1a*p#vdd4 zBH`5;}rA+PT=2L~ci1CbBTX|sq%QPdJ*qiYqeo9I0Y--rtwyP- z@qDP>P(_3g^Gp05z$rsIqph6Y{NWjfL0+qF%JgaOm@6TNegQGftWgup&0)k8EqyQC zALIV4C#w4F+Uy@Wbg)pRIc({1non&kwd!G%2`K$)EB2&ZG-pZ#gnw!+iyfyr)BbV% zr3Yq2Gx4i@^^d!F^>4i2h(_9VJKl5zyBKppuzz785dT?QC2BxlX~0|2N~&_}$nSm> zncMWf#a1>!3b7sw4|Ky??g(mH_rEc9$Us;Ja}pZt4}Ns2rIi9%-a}dWtQXfI?^mpt zkHnx%?0x+R#U~4f1$BkNed}W0O{Z)}&gRp7gTv@-HOc5gf78!3=ruGahw8*izli$97X`3(G{g zw5DlQ1mmdWY#okEPw2CYkr|d;U+ExhsXL>$l!~gr3N=M6(*OBz>DWqEW`i0wn^7(0 zecC)~>21=Ng8NdRe;GRwuLd6Vbdx3+CVaZtL_TWR(sevQDMeiX4%@tKWv?_9YktKy z2v{1qCfV#T;wdX9HDo(|t(1%(`K?a4Hn2py-%DQGs13M^oI3?(|c;@$gT~WBR8SFy9T`9vb8y8|8^EItXbD9l_e3DGL!lmhFFOuwAc1YQ_Ag5Gw+~foe(j!2vOF+Vv5w zVl9za?~#C57%^}q@MZ%fzV12n0!V1&dtlc=#L@P=P%J6&00U{XS#@hT@~QJ-S0><+ zy0B}&J%O2w$$JSAvm)s~m{^bfah+J0kcKf*`!-nxZ+a`5E%@BN5@KY3d{qIk@QI^u zXMABN?j^m3KW=17P;36VL|#%V4cd2I=uJj;@65J@Y!H%K0{bXaU}~McADQ;KESbx? z16WFph|stt#CZTrvUWcRP`JJ<$#5Zidhb3D6CvVkCguGDw zCxaE^Q}r9*A8T)3xgk*`0m7OwI})$ndMMxP?M>Q(^Mgk}A=)FWBOc|(4B|%lha#Q> z+#S?T;D>$qFQ4osadl&u$4T+*#*tY&n=IPcWD<)cTyMHKOUljY*cpSRib<( zzjUx+4K9wE2A_$nJ|2jz67*ya-r6``hd`47Bgc}y-4^O=fmjkxbgnMn^f&+#y;*j7tTRig;6$X!fzNAa7b0!&a4rc=t z5s?$Da;Qeu66+(|L&ayA6QO(I6!_H5^)bYdgYf`ZT=6);rw%AafcSzA15erycyvqE zJ%}IMX*Vgd*rq-`J#DBTt_Ks?2;nqB&T)^yLPRfA+MlIqKc~pq}E`scFk}xVp4z@!i^LRWqZJ zPGFjAr1AE_QMSWa995Atag9kq<4K^x87S86?>Kc@!;i%D>$Ek~BxYLlsVZa5r-?D} zpggFvI+>m+3;Wb0N=TpR4N+n-Zhc((O2asaN`^GOZm?02VDB780HS;xleMk1qcEvD zI#zUCIS-}8TnJ4*&u;T#ZL};-0IXUO z)vY=a&v+^y6-LQwvN!w(@~c^FCb!EuqlRZO&!29!3Y$6Z*?z7rfUigWnP>-KKOW_U7Jev%yW7<# z_qcHxIr2LF_DGV%TZ9V<@+ih|K|jAiNZ0=$6@UQ8Mu6 z(mmedFE8QFsN3_YMWYFr5iH@bY4L?N2=Mjp3%B_<#1)rQxUCqe z9jWR@0LJCu>{qdbhbyW*#j!WWx3Xv1tAo8aIzzG?rl~otu!L6$f9_w(iu7I2W-Q%4 zF^ibk)^y1!=^w(6@iG|aU-kA_RKg?b&8C+om(NY!04q}SP|7emefJ)^b+B%Hf1=K2 zP>2TKdN9|q;`*PPH|Ye@%iCDh_s9cDOSx=-%3Q_q51jS@BM5O zS;cP=Np2Zy_klBgPQmEKB-;$QSi>(3eRit&cYyPNRkY@}t#PE@rHyh|vqr>N_nYtw z_xY&;@k8X>5z!w7vVQDd@#+jlrXITXbq&lTVUgcRSZ8U?yvzfmz;8R+$g6L9IXh#{ z7t`lO6=jV6w`=PAc`c1IU35RwmKzk?-Zp$%NlD=Up+Ra9pQgwM4f|IQ5Lg$;$P#yhILC5jH{7~{k{vXbqQhs}s*#Af~UV$mORQ*2MMz~ALN zN6k?#j5c@@xVAlhxNRtxphVd0yz;Dl4O;XV0rWIenLSI@McXPPwB=GV;de)a8i7t^ux=eWs=qMIo;1oFL+N{CcC?yW(E&h#(>*g?*MkC%j^tPjztMbc$Z@s@6 z`AGyQkhvdCcktbv6LSW})59qx1R8tZ`@ zfjV}sIPdz(sett$uCZ95j3I}2srs6-^-hsOqc&Kqw!D2yxXsQuXIOX(^mLT>l_E^8 zrbZns**j=x{l~8CSxP7>_*>UMuQfKP+rC`w|1C}#`mZ=;?Cr^PNFauR@W<0ag|5Yy zj5)VM8ZBbvHaG|aHV#}YDsnk{Q1-%gYX(bRtaqU0UprXQ!VX4$u2;>Qbb9L}5gF?@ z0#s0K)g{{n#By*OSbM6J z!FktnkgCzKy(k!z>Fv9#=_`|@N{?NsHl3=h zXFnd|0u%G@-RiiK<4(i7u=^1Gkv^ON-+xo-6uEn_YV2WUU; z^C0}~5Oy*63vH8#84;79#Jc$TMROR{(YVsR#oi@cA-}RhP71SZQ4vKDzO>*)DJPo^ zf>ytdvmrr^+2sKBG8FO4UKG&?slvVE&Y!v*_O^4Ly0Xfdres4`+gZcZN+n(2MIzH^ z8{RwkXa`O^Je*Y$Jc4IxQ$n^`h|nt4=#{5XeF@%2xU44SeHRJ7?w#D^O36THOAc0Y zk`8GQc}St0VcTrug+|N+rG`!db)U{kW!1vm9*(y57wL!@5f`D&VNl%UjiG^oLCNyv z__qTmKIff<eN6B6P!Gm<|C;xS}?m?85+RIOeolgy;uH&6efrW4bfg#jz5_UH7igP_Blx)AZ=WE>sg& zT%txys-#5j`mJ;EcO5*tV?4Hxk*(W`{AMj)>=q4Icm=<;M3s1@pQk+H%guQIA7-e{bu^;2F(A&U>k*5iMR|+945Z1n+6xetl6Jx zO6(yN+2;}spolQpC2b`&Xa?JPguDl%e1Ea}Dhf?p)c>6X;aS9DAMj9XRxTpm;Q>Dx zYvEs#fbf(?wh23evYf)|lN%iW=+_v|%2+>B3y(>`LlgX0j2Z>0i#oW!mGu7A5z4^g zlLZN4_Hapt%)b%N);yumTEFv%Eg5HFd0J{+QTm!uHt8((lM%};PHdR6`(j#Y~gl2BRv z@g!?*EgJr4!Fh;i3z7uXV9qL-%X)L(_BX${CuckJ4rXGe7D%I^S?JNL>nkeRE?ddA z&FYi%VLDCw-r+{4BLSc{eeJ)Wt(Vsm>}E!GSEr`?eZQPlVDkpuU%ur3C};0S9mK;W zi*eZ4;_11yn#hjv(#d%nCO?;D4a2QRb41)=IE{=+=r6!iv?EF-d0TX%Ofa?TROE_f z<@3F;%()!S8~^V(3{i6fp@l(T09inszfG793-tKA&5vl8Gi|}>+mPM2FtrTb|iyEl)Eu-G#%lLQir#-?ZSJ3OT=SWSND#0d35_SS*RuIz^i ztmmyXHzYPE5*=aD+Lcs~oTqrkkl5*9ofJ9@lDcRvK1%jO@ecN&R%p+>Uii72UiuJK z#h(lySO{w9r=f3$GvKz>s7AadO4&xE9PivTwEr2kXzoo7DzmpWmTBvXalR1v< zVqGnKHi-KSkErEOGf0oO+?W^=z2RMFP%Zw$Br}^D;lw9{Q+Ff??fZ!I6qmQ|%P-1k zUl6i=`sT$H;>v$!0|3ASHc)6g9`NrEzaoH}Cp3Jnx15*!%NrCIIFy*<9$bb)!J>M% zG<=GRg+x%Mwz$}`b9o8t9+gNm0ZC>V`~{7fg)%Lg()UTF^qR;@n z9{H0Yhy?$9>*f#=ff7nlDjLpifaupjv|tli(evLCR=5}W+z*{2c5%thP3Br)*!$~@ivB$ zRJmAL+~aFN4!uT}^MpdO@G!e5AJ*Ah-%d)Rqt(`q}U4*Uv)`itLTs| zJ1ZPUh+>Lo4y+*>_eCH1OHo&p8u3Y?=Uf4}i||JB;;bL3N{pRcfgJ*WPQ)+@g;BJB zxR@lN?L;|V$HcUiR5{U7c04~HR9*lH6fARnRj_7iw@PQF3cW>9NjKgWbT!&760t$M7kS1EpWl^ygBOQ_>bTM8anzPOdwjAA@kpVGX@AfCXNALc1mcj@;jN# zzMAE^%p9m7PRC`!&TCM?5=W1`Z!L?M?S3Wv@F#79F zuq)a1$Y=Y^zWZLFEs$XOxZTIT-RO)WW>*3{<{hg#?@1O5YDp7hsFeu3&0xE@#0FjTkum=gP>5S@NEO|Bfg) z*BhI_d=TS~15x9A8OXRh;4?LWKf93r$n;;{6(Z@w4*E6V0!tW1?|HSXc=>dpdp^dbdydSs z2o>%Kpr1=*8Cbj|!@AL8w9t!Jlnf^y4;C8Mp(bIN;t29EnL`gKO3WmYAZ)rmVR(NN zTRKZS9xH8-EPVahhFK!*ecuUtRHz8|PH0<-yBKXh+FgEqUhnCQ?1cGL%(%xaIE9DS zU?!a4>#`VRM;1Htem+g#N00*mnitH}`1Rs7vSJ2A#JVq1mdSOUuPql^u;3h~c4XbO zn5pf)5@?oDQT%3E*8U7l&^=MVer$8|{B-u(5^3wM>__nRm6F5GLEFdXuSB*M0qRu~ z((3+)x$}Ql0KJWv{-RXHeY!7Q)+wVxHw}X!LYN0t08^{UASvYEECOrN6o$Gk{pXu^ z)-#qT$5IfP;Fua|*xlIGJO+k__#OK}@BWx>;$`?cSl!4$B5Ij>I#)+=^a#24%fY47 zg6_y{UM}z!jURo^w_RAu(LCuBMNEGVj$ahWpY2f)wxNJ+6hWEKQ7x%dnX*?tFub*QwJkzN|la5XnR-$1-m*()AqzR9V=qwbP zYOrQ)Xkb>fvlu$9OQUm~qATXy2O~Jf>&GaDSD#U0S^kciOW*u4PwFaEas~cFcRNr+ z>tez7P{&=QFsnRgY%~|u`>p|`7);UfI+RRzP|y*J395vJL_U34n?TtdROAw)yhUV! z9ufV5p-pMa@>Q5p`7PV&P$lD##r8!VdqH#F>X!yJ_VX82P3{-O2hqCz~C=r{sCky!{c3 z2cux&(1YTLp;u1VzsybyPE}KObd5&62qn_q6Hnk=8KY?jPccKQt&p5~-#rJ6)-aW2x& z$k6)*p5WIn`Gfq3;0{PZ`w;>Jq?#f_5k>qfM-PqcwleEha~}Src()QRCxj2=0hNst zd#ZPe#a#X_)j1Du#*u;yjmiMJ%+Tsu?&D?CES8h)59no_YHZWWlGUI?MKdTw8x*ZK zrH-Leegan~9B!Ym;_gfND~pDO(Hb&8032==?XUCwPlLb$b-^=o#iNFhVX_~>#xyyO zFyRAXLG@&%<;h=V#Ugz4N*PQtSfo1#*4i>yf|`6FNLJt8oy)d&!o4@s+Z)T`%467Z zNHveIpD!wlWM_+EcK|MRXFh2XG?e&Pk$sU{MDzVYBRjSlmH1+1FY9}&tB$xJgI=uP z)?H~>*wAWM>9P%&IP^T;5YaoEw0RZhe1rrQL<4A!T3vQrC zGM3*wG0`0d4<)!oAfY>%G=w~J@uq`JRj;6r?4d7exPA(F&ic)Y(oNIZ!BLGmb7@mw z+@l*~Pway-y@VFpY?q8%EOKn&6#4gpB@A5g@InV3kO+R(f0iZCLZFVl3A#6}4UW>s zcn2(GWe?8Gayo|tpq|mBdZXLCK3j}!sVCF3GmQrp;j997Ah*tV97`7VvKf+ZxFR|^ zp61=LpWNnAvsBSkI(yg5A81w(JpAn3zmyer8kJ%l>jRJ$}=7p9sBgL6MOpNKrxlZv2963l%Vc@KWJ zN3c92m(@2@NQ|^13TIH&!t)dbqkuCr=enTq;``{jibT~&x^kWFPVT9_pK~wD_8R_! zkf$@Q2u#ecUoqOa`I6R!t2l7oF~cGa(<0~&rF+MC7Q78yPDcz)Tt*=Rx>O{1;iYep zKcH(ud4z{hi}lYSd%)Z|5pvYSJvr=sZ2-yg$;(ghObAsQp80FLgCZwkmJs%bmle48wpRe%Qpju7Rx z6>KvGS_A4{2bR_$F%KbO2ANNiwCj=Y@8qbssD|k^v!zvW4ae!b%tb=P`HkLn4kJiH ze5!rpm;BawgwQNV1=}1Zhv*#0HxP2+|9ypQVflLe^?uhylNe>!vzk!E4`4XWT5VRm7l8a64H zLjWBtPQt5L;N!E3XJ$n+D|cNc^YVZ-&3ioPV1qOVX!I!$Zb3x_ee98uI#S&Nrzcvd z1JYV9S>^o^9*bfO*2GY^{Uh~s2nc?QAqnIM;t!(*6<5WJE~Bdf1%R?#@MWX0W~4$1 zoLtptc4j)KDV_VvYt$EXQ*%Jr(!Eaa;{|c#BkVC@JbJc5y*E1g))PMOP`)K_;)i6& zZnTH(uL{jjvY976+Jqd$$P@XFfrMJKKNXy+ub>faa~U_qb%H-I(|ca4d7Ja+TTfUyR#kpZxkEg#?NeD1%6`>n>We@cQb;Oz!R<`X z`CFr`a?`xQuV~xt>wGi;$R><`t_k5k*W{8Bfb}oGlTPZu)jPPANuWFSo=lYQ$d)Oz zz$0k9`RG*u)cO)X1Bs4(Ad_j)Zw;FWo3zY=GGN;zQT`~1Zm(hRCV6n3SQlnd5{%9N zNAS=Ukf$@6QYNDNn8Z1lrrz^#jqp-fHaeft zDeUo3&PUW{c*84$X>h z&kHR9i;2ez3QLaS==C`4^n}G@IUI-UJ@*atFoZ5r#x{Y_MYpZzw9eCdx-Ea82}U=Q z=PP}d&A)t=<&^OL>%GVTZu-gouM49fq??~iWMvol*>_>!4O5tTsmvpLe+d5w#JYmj z+10*!x*Z9D-2voA%HWR-PwgtoF;7+qhUi~#9s&?qzA{$o<&f@X*1C_BywP3#WX}FB zdaT7pfuOQ3oTT0R4)&`_AS*DXIEXxIxf3t(TZ4(lVSDN>(+-Aj%FePO*;^nVM+a)g zKzo>k-(@}V7W~yHwqb$SM-0giW5$zvUwGIcV*vRo~At3?#vU^MtMD01Lg0!*h z$4&B3RilP+Q;C8f-#U5|@lFnGG$7+S*~9FW-|!p#n>Ne=4Nr+OnplYDZWu-6-e>XG z*s-FY=@<6F(Ks5wFyO#;)fYhxtmI!mY0&!V`>{}zMKwisZz!r`D+@(4ab%uxVc3JI zAD?X>cph|GF3^@mdCT_tJJ8qeh6MOcC?SI?18i$_BQFzMo9*a_r;~`kuI#Uy2oRd- z5otm_5x#|<141(q@o!1!j%~`NclHk&I97ZS*T`V8uCZNdS<@JAS^7AoXO`^#oOqKo z13tK}T5QpQ_nN8awK;3dYP3D`e!9K4uKzIl-VNWd1M#1B!xRf*3I1QqFb*T2P0US# z77MK#q=JA>Wsn+z`1> zxIasEYhX^dp+bpvJX-fET+*M1*6eG$vWT$@P)5OjI7TSRxwqds8?ASfog@vCiIq!g zs;&;_lJ*g8MuQy@562j;DzC^G>c3ar@FCscW7&%6(IkJ>EqBW-4&qq8!b+L^ei_i5 z@@1*$By)Q7fPtG#o1nuyfz2@wO9Dqx{syvC$Y^RDIEV&ISUbgi-E#_SLO%OQlkvDj zwb|$TD~)fMYGF9Y%U%tX21zJ{f!5%;^>aP9NQyg2E^C_1DR8hbShW1y17=Hhle*Tc zgqbvz68`uBnub{E-+RLS0`N_l;K96MEakWmIgV z9Z8{T|L!4_03R}fvy~7ChA6|`Fu`E` zn2{g)o8kg}d)Ix+PE<*j$Thygz6SUYo_UqKH@jIcrnhv-Puk*ciDjH?I=EIn!agN^ z<(~|ma&x*Xs#fo?z%uA>oF4Db%j?J@=LKHs+Zypg0R%PQgnHA6L4rE#qNvzm#gq|a z+`=j}k?UmUzISaZ+!W4nl6ny8Gi=}%A^y2oblgZ6bdXA5JevPyx6m|)Yo(hmD!Lxx zoBlOiYT>f15G@(plb4`E7iCHQK0Ali=S*RxQVLpV5Hp)hF^HObIrZ^lvIy(IT!}Gt?DvM(}?FXa`<);=@BStWp`?1w&q5rUPFO@{cRJ*x@gLW%=d7q{%iD>xb4tb znVOxSEq{Dz&RJeMQcR|_(&f*Cl|de|K78SNpeZow9&MxH=U_u5$!Zwm*e>}lZr})N zO92Jl*i=*Cl%Iir`|h$LZt!}BU+v_jd@1;7`RZ5-(G=6~kaUG9fFikm%35r5m90|0 z-DyU03!r`tbz^3m_OrSv8S!kL0SBwnFgDPnS8{}95Xu9D>Y6y5;yf*G-u2q>-c}?G%3?6llo!k~+6kh_3e$U(-H0$Q^LzzEO#2U@8NEwBLhSo%0m?37Cnjnc6#Rd6o%Ipi{72saE!2D~bpu zDUm_$3?mo<7kvOEF}Kmc$fkEH^@g<}QjFFAk{QF7i#zQH5<@C~J?I~LNVr;5`ER@Z zqk-%ldY}}!Wm4E8VH{U{{t}wq!tf7ab7UL|*aS-$hzPLg^?>SxS;z&53giM=0tw~Y z-C^y0k!lM}C#|mUD7kMADO2Tk`f&51K9-><^^0Onwft-q=u~6n-{A(?>m`VyqH8K71R)#a+2-a9X9(0aw95EhlXrj%Lxc4MOZyD= zV&k}2bx>c%J?%%9wy&v7V!ZDQ96Qf3J@K2|PAc3!uW*E7-hGoBN2W~A#GLsjI_2LZ zs)1N93u=Z#{`~!+n+gC0;Ld~X$0375q+KLi=Cw{C0z!>?zWGRod3=x3BE{?FKZ>Rl z%|5)R>Xk`YC_^dub6YQkb08XQn0SKMM6M5b2i%|?*!X$x)m!@VqVoj0!&P3M@*cG5 zg{`adkuO)MkI_`m8=O7wqCMkQzB=erwbd?9dITAJT*+iKjcU8hufU(RQy29UU!g{j zrxd*f$0k$NYGN&_qvoFdJlZ_-5EmZwl-=v&4y(B+VZ=GcO&Fu&whK^e=&Caa&?#v? zM=D}k`7MK7CCMTy6sR0v5c^0nkVB+uL1~>dJ@vU(+9HUK4Qm_6Rh&=wTDba$cov7P zlL*X?b+~siALbvk1g5>2w~aW(cyfAXbJC0FLq}-;V@W|XTBMh@$ysVA5u6vvm3Ba( zJ`GGSAxb`5l8TS`P}XdB4jwHU{c{xhvie(}yyK*Ij^pVaIg9k0f*ML7F?6ie>2ISb zBIDLhZ6WvAE3?zqMhVP-2ZsU2vo91aJTfwli(hSS0ik5kOWQ*vO)wbS_dJ*n4orVL zs(8o=3G zGY(oOsHI&^fz|8dia3wo8=0)&{yDqsjTMZUIB}fcaV|yZMeMKd$n^Si{o*!2S%)tU z`r&V8&#idGji&OL=3UCS5N3f5Pf@>CGbCXUw0%Q`NU@=^xa4%TT-iytFrLHVrEb*) zixG@iZAU8`ENruGf9$WpreKK!o8c(l_F4hO_aSS}c&uGk>rPeXY9JnC8_wU$hi{gGlf+0%y=m$s4v3P?@nj6_502Z>d7yC&-ABu+ zIB9NLQ|b;yN~3Pns$_k%zbGt7@4_%fQ3ca3Z<*&&uOsq%MUOQIyIPE&#@Tm9r!)_{_s~keJ{Eyg(Me7z08W-=`^(`L3tuyK+v^G(p$jxN_h1^f)Nhhi*w30 zX-ynQW~&fm`f*NK)xqy$|BT}*K2S&;*NpHhmjI!x231ax-%EiG)Li%y$4Dnvt@;_Y zCQ-Pg$5Ls1)o?muk0)^6Ga`}`79Mg&T10WUYQ+r{9!{~J195}suUq*f58SjH$0Ni8 z(c3`H_QR4Ry1m^IZUHY|+=3F8@_AK*)Li5{vXTJg@tEI$77|`0_kD2gWh4?EA)ksi z73Gf&T(XQ>|@Vo+Ga%1D`)&{Z}{+0Sr+70Ss6UMSK31 zvd!PZD2h7g_nDIvkJz&!-dsqCdgx&$ zs?+cX&q0EMn%tt@IHplaYX7vBqJ`2v;tmB>B~_CF4AYO~{e^;+s^n*o=$<-jhh1~V?AO^B-{>Ryio>n=NIJCl{bA?#oB$h- zFH@J+x(fCRW0zmESuBouktADg7HobG`1Jr$4D=W@VO%__u~F|9|d*gdh!c|Pa31=*Re#I+B~5BFq0tT z0InO-2%S9SJRW85Z5^G+K4c5jv%aX>8UO@!rROcC`aa!^-@3j335_z4!Z{ zbI>7$wiahpQ0{n%Cd4=l`_T*jA~>%}#`>j}x^N6r2Js;Pc-i`1F^gs+kr9AX0O;*d z$*z3SaV0M42eJ=$;2^B3`NgE4ld$(ES`}Vo_`|9+;d_=4sz`Kj{Shs+Eh~8iP_Oe{ z7IbFpGChTn*S`cUyL=n9n?gZYsPz{kJEYE>DjSRd*wdDO4ZNMbEp%G;tS77qFS@QJX^(}vnqou32+e&>U#JY*?&V!6w5k|&8)ci}yB zn%bq7KYv^-71*6Niu)u*{CQ;2qMUUQNYq^~b+Wu`S@C|ymC*+g{*Ou2bvo_?sj(7v zAl}O`yQHV*agq1Lsb!zF@ie$7iY1@pT$S*JCY(HXdZRvwMe%)$!3cPR_o^YzsuCN$ z(eIg@mHcO`PEGvDp|EY&ehlgh%-~$=$@;;P^wZ`s97d)1<1Ru`HZA43ah<)dYS4w~ zSNWUC-MYz9GA*IaYV`l(2iyCPA1q#5P1;Ezz0)mnBHgu#L91~o;xV>ybd0GQ3PJzg zwbASK#qDi%ps}sEE1LfegMhP{Uiu3u7vwSFN&x&8{F~SKkD<7p754snFnQ2&YgPPx z10e70u#zE%%$7E&pNveXKy$<}nN8Qo)+NW}VyxjU;rRj&cy1?y7T*g}(fCOcBO3ZW zI?1N@1ewJ)AWFDBI}CB>LzJr&hxG|j&%4m(E#HmMM7yAN9fgjJ6)oyys%HS3F?Eu!ko_3C+VDUdqCU%~c!DB|b;CCG!jQQ|B7G<=9kPUgo>lT-=g zYu+A6_-SM14nx%<4LC~}u!W6z`1=!cT;(R164-WNpmpd%+l71Y%k5ilMfbSn!bf0& zGWY+uCU5mkbUw}x&+excUDZeX86?PK;G3eMcY_gUB=lECxkH^vC+6Hk^`@S(niDPM z(Zq?2z0bti>lmFL-x;T6pa(1;HPkd>m{7;2lSheG@>lkl?q6=< z3sV@;JH4o6k7+*C&&rjNP52wh{h`G-V}T#r8-b)a4iY~2V@kaA1bA&wQpKXNS4O^` zZO}_r@hBTsPJO%5aDfz4OtR{U^DK@vn`ac=s}J^RUu zX7ocbJCI`(DoE^G96A0ecCxql3V3gx<+bz{JOUoo9P_NrI!B4PhBY4kJm?&~y7SVLKf!Agy;CAXc1pYLQ-{lBI)mrkxVW2rpMP) zwu*nc9AanL%BVMFn3_A}G|aibqDFQ%qg%^x62l!mz~9xe8E)>hq;k!#>|Ec~%qgn& zqWjKdq<3h2kqrhoT330%2*}(pF)@i1%{jQL4 zH~iR_U1VU#MmuiKSF;`WtXi~ThkQ{|8)5B-fi5|mYg7Dk!f^0??UqWn!q3VYN1&ja z?#zlRChkZ7M+2W6ie&BERh@I8f1O?;Aj_1cIf7iqf9bCGupnPPsB;k0oK4WPBuN9z z^1ckc@aNCp5c-4C5#JNR@A0juJ-^ur7pN3s=bZyp`0c9jF)su70 z6hZ5qYLx^i3=|`DZYfA6&ARi2ryo@qig0;sq%E2dhRQcZB%6j)|EU~9C6=Qdz7I#R z+Vy0$NZk-~p~jkKwR|T&LPLfsZ|<#6T&w3W)pDbLeyeGhZLhve&j3_J6gMilH`f)~ z9+cgV^8rV91&b~d0FRv%KMYj(Mzf8}y)9?(30>DcX1k|OA2T-Ik_FEel7bdBkC#>N zx{b-k^$GPECB}tSR3cw+$3h>(ajHxJA>#9t&ILncxegrUD^kftSPWXN_NC76FH`8E z@I(Qe*Kk^Fc83JP@PaYjK)#+dUkNYc@|o1#jByUy4FliYxctFIroZ!UQcTtn63oAOz%Cwj0J|wv=#$ul-#tR}kT1 ziqMbBm@=Q>_eT@dcmLPN=laXqkY?7PAkF~lM$;yzgKOJ!w$GKu3F#xKA$ z+OhRy{c|JI4TZx@Y9EH*k4dh%KtIx7Ony@_zg=QWOG}?R1%HBDE8Srnoihd?Ns@*1 zYmAXqBG1~$L2fnCI+C_jqZe_`jJv6BBGoiaI_uh#Cm;0pC!8-o_iAZ@1SN^B!^nqd z--*cZcSFT;ia~Mel8e%B|KZNuVN(NF(ZUo5X7o%K#o|SlS`kG(r!9$=jJ}f>gB}!Y zo*fDfzS2rS%kk#ia<9IhzF_;*IRfsgd@q4|r78WQzG!WDs`=Msd{L-H08N z6h=s|B501wwvKSd>mu3}FkBYaMQ18199ES^WsSv3>mo%!zA_?Ih1XI>i|I-tM#UmLNY%(-3=YtStnKN zWaqQ;TDd`;1fR|eP^5EYQVhN39JA}`0zTfjv(J^IoveUuR=L;})SkOuWo-;B2IsnB zXDX9tIVPhk4zx!T+YkS+axccgL-VkGL?c?pl6j)ECC$qg5`8AZvw)A>Uh`s~{sYf(LNz{G&fUk>@7>eCz)PL=*JPT*hEdTvS?Ax z{cQ0^pN@OSz&G8|>j%4U+c9@7bPhL!Heazg#AJqP<=IL)T&fA47{%8#z8b}!Gt9;c z+y^^+fV9q#)Q)HSV{(IdrGGbi2Xt)@MpjYv$!{ z8^kb5+f9p)V$nqp!NPMuTw_Es=wD+_uAqc22oKiSlUlEgsl5q~6>OGo54z-jb{zR>M*KPjGY=is%F+wi=!)zz~UuHX6R-^6qONEfJ zn=EH#!CzTA2Ps5bVsjj=l=@fv3n|5r{9RL+yj5XT<$&r-wMGfl02zsTtYr1ug5h~f zsY;YQc=Q5!pinRg0Mw7^Bt>Z4uk+9c^zB%A&tir?gP9ojNt`oXnGr%DOF`{t?A0h< zkapiQa=ZTYLsA=p_7R!S_R+YQD31kx4KcYUIs$c#jNei1W_p3VD9F+=KL`pt8oUDu zE?iP?mN5(wS-35KL073{3fGF3h;)GQ3A;>`xqHCwj^`P`w|(MsRRek4#<9VJjz0T{ z*DKsnPgoK)fjL6cnZ=J^mX}4%4gDuFoPJBvAJKFlQ%LQ@@BTTzew}4V@LulY_6jueqjfv^W?sbgGP%i-O$GC}+pPa?TBjm?G*mEnB+X@pr=Q!eS*&mI4OF zrD$LU8-bcFBSDaZ81Rr|`MiDnwD$k)n#5nblgHmJtv{+Eu>6-MIf$G^hz!F0V`anfC!N?li>o%~HpNClQ2ypG zg2XvY(z1)f2WBrqz&Do^Dp2pGrHjSWo z45=QgFS~s|gM?nuK(cIUX}K5~+D)!4?#(qcjtO)Q9g{M*I3Q>o`f&@5{IwU^>hSBi zj&efOI9PCAT9PIJC$$;uPhwK|n#{mFcQ5ec@$yj{GP&H6#o6z4wuvDdE7p{Kj0w|l z{=dG8Jj|pab@6ncBFAe z`mjE&d)=3QxES3PIndn2p!}It@dTsy53g06o<0oJG9;rIex+(L<|V>YMnE;1W&1c$ zoc3xtPcJ>bYYA)nRT6?XHKviHVxw3VPlfmx1Ik~a^jg|kVCupUUGrWm4kA=34m|s* zSwzGD@*G6ywO-Ue38G`kja}kNTt;N#@55#F%3QkkCx7mc2sWT*(H2zY&VCY(K)MCt zz9?!uIr0-Tlh9rkJnLm5U@`u!@oz$-iYJu?ff(ivOKB}%JU%&t?Ajp%1@Z$$x(P2l z4sO`_%seVy(%4*gk=Vtys&bt`&3?A=IDzJMFQ>9IUL1qZ!e`aKx%LRJPK{poiE>56 zGQwWF2y_f2ya~5>#R6O0+khoT9F_nCz}m`rGma6 z<=hpI8Z`G&Q`N98_luvE?FI**{o(z&Vi7YvT~q&2RdxO!wUU|*>oxbKV-mT@lvK*` z+QsJ63NF`2Nlndh|9=@Jo{5uYpZ0WiX89l3k3TLQyc>KN#J8LM#UlE{lK!#sE&cp` zW^=7qOT)nP{bTBaY3czdY6z35t*oM=)<<6TD^fEL+cTN&UGpaz69+is)_Ul8vUl?H z5Zzq={P=Rei>;ZYa-P{7qK2}eY9u}z@RtND1T?h7AbcR{`0XLo zg6N}Z7#y-1G2LZ4c zs*&qqtcqE$1jhOV654O@7m-h}T^VVtEO7<}hW{O9rVA53->&lh64I#g7DCa8(0>^5 z+03h>k^9DM!MU8g{2oKKH0^#Yx_&HUNC>K@Z1UtK=#CK67 z@F>aS9D0*(a8YSI?d^f7gnq;n;jKa4!;e8MaB zdAIBKhbSDnDdMxnt*X1S*!&72FusR5Qq8IgECI;A%lh|IY-8|x!(Vxy4t+dbeTV{o zutA<$#QPZDjYK#xUjp7dBtwKKSQA_56m>b+bj$IZY&85=(SbQ`vPJ3h=#(8rcwp5g zj9@Hrj9^r8SBDgCe=WxgP2S7)HFim}BjtuHLZVPGXQ~byUm#nwmxGgGn^e2Ma3dfNI+`1qt}q@5`=-Y9 z5F}T!8z^+WhK7gP|9(AEB?gT!7hLc$S*J}2aqQFO0y%@l;a%gw+$Yc3^uASj5m#e- zTc_|ZD(=~}Rb(ioP&(zeJV$xq^BL;=Un?b)Xd;PQMBB^tcE1#z{X%&9sg9p6rzEui z(~k%lDjb>z4`d#ma2&E>DX1X&FquFe!v>K()z*bxLv-JYxbEr}P0!Pb8X_{~cn+Wa zun{v)>yIF5l<6=Og#7OnsYJhmmT5R)Hq!a$$|&OnzB8EFvX*sB>$EHWpnkQX3ll&@oeo%7 z^c17DyIsWt*t0)p?_~UxQ}w1O#<(v|Py!wr?k)g; zFpdU~IZA+RbkeSa7z;{6j7f?8V3zD$i>-EnbHG-86A(e=nT=hYcoCUCS9wHpseC5lTMMax}tYjKUfbo8=%+FICI&(~m*tBnrdiHcVNc(ea`Z;dd z>!nv~jp4I~3lqiMo2VknUaW9fB`v&8k~u6)^P6V;(wV2^vl58rGPjQLXiJQ~O?t8< zs*n-{ukf(dBpS?n5zeH zox}bKx1?OKde8-g4#EBBRJJj!+~BV|{{Ow9gA`Y{2hmv;SkEeT-0L=wyeV(_`Kn#O zUtW2wG$BLg@r~7(8>482W<;5^ivF?I_Y}Tb!1rrqP63xx6rqy=o~JX#)~x#S_K=tn zOb9&&-l{)iexeZ8*hB*O0J70P!GKl3Veny`VdN4pA)llKpn)`Hx)@}%M|ePpX>np! z-=gS7>OSuvH*rHsRQw`IGT5llhX!`UStLD|3plWU8ap$qc`!SxOYlu!ymMe5N(O{z zgWgknGG~bE=P{h^28|Idxk4C0cVI@2gy%-%1LK?^5G@iTo?_M2qN|GOfpkNHwJ15Y zy)N4Ez42Cl8O|JXu%9W)zpb(3GZ+#Qx=`>*tu3pdDjun^2dfBNj4#Bf{Ja~Tik`Dt zsOAVWDHFG|73j*-?y4qTR%+=xI(1loD4gDgq84w0I$o z=MMc<12Tf=WG#^odD>2xf9v|Yo=y#V0$-*%b+C~MfDypcc}!#IjDc*6+`x{fHO2_Z_u+cR;)lWJ za(KMnQjAWDPQhdW;@d$H!L)e5tXDhqW~g~jxfxSM9`9D|Q~=6&3KaV%PRB25J^UEU zmR*;Q`U{OTV)` zP&x<{^#*q6j6Yt3Q&e}IW4kXIVOTOAFbV}&Un2hkTjg;usr<^4oqn=-zEMhLvj#{G z@lj-R8WisJ(V}%AP7^jN8Ez)hjD6y zpiT9`Jil0tQHF_%L`B$}`{GXhGhON%=|UV4Ma4Wp@+aZ|a}-w-kOL9h;%15=5(dn) z2@5yO|C~g_mtHK&se()&DxrUcv@f>M9yTC|P?aCFW|Wf92%8vbvKYvYAOTP&x%J06 z+-#_B3cGupGTCUUnwG{AIm1%Gp2E|G;lUC}ImvCFO&m2{+|VfNtF0TO;2`rOUvshZ z+H3mhHO1vWR)03b+CwF5k;|QXTm>fFoK!_@qauXnkCuKjO5Ut-23!InW~{`sil~mxU7b@ z`l=3UMT}**#XF}*vQNs;qz3n=GCJmRY*s!Q5lv$ubCQdhgZkS!a*7(^O@GTnBM@UW zGD(hmk!+;ntADV!aa(y{Ld*pN<;R@vc6wWQIB8{99dADYKf6+0WM0sUCXZ_#X@R8zcFo3)@Hiry{|KxZ< zNG@_x4yJloajkPRR!JnO`2|(v*|u4l=|8Wg3upt_dp*&DRIL5WBY>BTTO2y(H}o&L zXEOTu-tDzAUu1#JFtc@&&LyelpPdt* z>$nca&8Spz;I}(9M$#DKn6i>gCB&e=XbaH}0sM8IVsGh>4^%s8n{D#tcFnGO7+wug z?gIA7MQ&2@PC#xTOZZ5AI=g6`2-N)To3PJ_pl_?7FN(EBTm}nfyTeJO%ocW9McR*& zr7^K2XVSSfQ*RKG{o0n3;svg=X>P0AlH{hygncw0WXdYlcnBnTv|+4PHdu*@d0LW_ zGj2MwkWMlRRSBuYHz8|(Yc+(20ERtb(p@Woz0@0w)nvWmt&K>jH)&5}(RZ;}mjp4? zKq|B(bee5Xmgr|c(s};+t>AmS|jX(cHCrhyaI*LxF z5uoFK#65~Q#?t*2Cl+$%G}u0iuHny-&ll*c#TQe$^FkuPPl(w-(P2k{GQC`hIg%_k zx0EBeMdLuy1mopIv=CX+_d+6RCo8$ijlM_@+jqT(%_81-3Z^Sv2pcB#6)`md*pNA~ zDBIMF1h*trBl$rhFqMfox7slo;}ejL{a9eLyN4;8G=}Ch`Aw?07<8d3h`^d9lZG__ zM1_Y3*l|`VV!3bo$F$+;*7fE*CDq5?_2B>{WR%SMX zLzoVY{c+*1jOv0?I}KDMBkaL4Nt6Kp53Ji zyUz1V`cP6)R**HrFkVQ|i&SOIZgYZ4YOPjdAB(?rDd*JB(A8-zZc<57Y1U21!W)AF z0p*ctC<#Z_dN`RSy3UfBN&2WiVgc!W+TSM{V;QPhC#KybK3Uwxo64I4O+jiRC!hEN z^NHcjhk-+ZoP7kJ`X0VUO=p;k^S-M}QgY)1YOldL$3C4dcL-YrZX0fk*3NqG~%E9B0X-eWbi06+Qab zCPa}WV^Xs-D!TV*xAS^R-;!prIeykwI7%SwqPC4VCfOykSBP!mWxr4>)_x(-oslH>---M8{@;R48v-y82>mzuNprTo_ zJ3Oy{K1DabQgP0U?m;f}ywHTIS;~X+{nomh?W!gD^q=4tKyCb!<2grBacuIYvOW8Kq zHq_Q72a%voLAnp>b;x}5N2mRtb`A>oNueb`C zUw_TBFuD#gKLB@F^Z1dG!94k14dz*vC1w0?FG3iOYW^RpRk7P&#K=02w7i(`;yCr> zSG2R=i;uYm{ncbQpNr2AxWH1mrC#Xhv|8AmqpquIV?Yr5)Y|5+Aln4(A>?f>G9&6Fz zL#W5tA9ByXGv!N6<D6uC<*B&x zOA>f9uTj3tq|@Y=w8Y^9q^d+gtbfsK&FSDL>o4OfXo8WtQl*iU-L>wJi6J)dp^c%f zA$b-*vT)z8&K@ap62gb44D~ z#=pqokt&UxLS0yfxA;ihXwDT$x0gkLJ#>=BY%X-Skd_d~ zNw-XwhFcyJag@qm{Z}|XSB#zp?JBwiCJ;IfGilXn%=6cez}QNh?`G;f-&Hq{8iepd zi%|(QSd*dj`vCeak%T7CQMWVTu+bTH_fZftn7i+Z+HRHirnEKo{3&WT7{MGrDhu9D zY%k^|#r<|!0G+uoch_1y3@1MYH!*stI-3F}cCn6FG{JS{t#mwqwqPo}*ys0;bF$+$ z%qL;xYBZdhyZzC&lNhAh^?Fl1-ln)>G(1!Bu%fj9VKqBf8J#HXyAn z0o$A9!}Yhdp6(^T=ihkX#jJ+q9^Yne%V44qm}H4V5=85l_XB$oYYM-KjYhVj$s9u0 z8oNjs@z38=WTS8m>A)*|yjeZV;P9`@5#dG-zFuy!Rfe*A_cC`czN2m80b3sb&7{BN zF^p%yr>wE+{v|%!3YeV;?-I|Q3%PXXw64F^j3wv{NIS2$3aRt&_UNx|x ztq1fx_Wrc7^KRgJ-j8aD&lzhUal|jK$|Mn|)ZarJvU|9EdHCg){_b=jCPd8TwTsf3w2yYN0Mjv`7mGK5Tf=PTwp?1Ya^iQ5Zf~-SVv~xx`9-%@h+>E`d=k zalMNN(|`n?O1X3AH5yyRjCQa?nlCATRN5Q0y^dZ=pJuY&pOVK*qEp0^gBXXQ*A^=k z<_xq3k7k|1<3$GNlo%3C5m-huBKt4oR-NqFF8HqxXcu(@l|AnkMw?326v&Y@-jom4 zm1KQ;L#|`PMF(h~)A`NRAM?t8EPE7k z+|sHT>6@m<>G|J1nyei>P9-LQD29%lygYJaM|M?aeevm(>!yMD{Yl=_ZK*v_Yk z*!IJ0NBu!2@OAxO$oA-mjB+F?xSooIK2-)LX@=kawT)Nk?d1XLlKxaqG=M??)9&i(Q6%_J#JBlH|rLG=0iZsk(mdD%= zAScqk!c1ZE$o?F--zY^P`1KzxX+3Z`DU zw=*>1FnAH>cKojR(9YD7wW4PCdwqquCNdgZM04|C&GvVIeA>dYs4t_pUWUeaPv;=c zNV$?{-Bb?m!0(w{yy{a4y&p3njr2|)nVl9v_Yxzs3wrgNzbBH0n_P!Y83K=!lhZ1j z@OD1-)p86hhIQFQrA;^DtvslZf7_ajOeGqyEAqH|amapJexW+OoBDq7d4Z~J!0-9B zA8)5sjmdKDSio>>btplQdfIU3A}+-_@1=~J$Gc7eWy$sAWdQ>%Ue+$1cd428Z`O&g zSf=!lt0AY0?f^L+>wbbX!C7Y|r`fAo1v3hBO5(4=IL(%x%oOqms-;6-xEYqLu zGk;X8k(K6fJqdLZ@jXQ@HgD&IH#ZwLJ|vVxG(%>)US&t0gE^xP4@7xwB3YS!OCC!d zhf;fdz6OS;B2Db28C{Hq^i~{^5R}>HBE}{C9nf=tHY(8)B+)F<<5ahr`F^ZO2ffrm zK8yN6k4-tonh-1y|1mEKaE>QJXD}8cE|3zNv%S)N`jb1QSqYC3g(%HiQ!%1YQ@~tJ z{B13eXR~(T@zG8DdA@-zL`jc^!7OKp4DQ+kLW6i$_g5Nvjt3%4L2ZU=r-wu&KRFdp z@4TG43pcLUGwRC_+r>TB`JYmMSeNyciwu#iVHEl1#2BSD1|duBKtU8Fqleh3j2Eai zOlnkeg>qigwYV>VC%Qn!21yQ{6}yiuudFO1)qdtbESQ)UGY|zDT~jQ27W{@7g? zH7+u&fuFgBzBv5hDxTUiTg?|gH1Jl?xvql8hj_f z8qw~%C!fez8mJ#;MoZ$T{&um|Txz+TwU4J+bidC;U^bC6j*o^Hr!!5_D)Ue}37Jmia;&T zxj)L!Zl>=Tz0lXUdaS@%?xb^HZV)PEFz99i>Y4v#DW1+3)@L^^!3M)I*ta~h_nZ#T zUu1>bj(2W0v)A+@I?=48>a4gGp(tq^GIK(g$Gjs|1$GPly9sRw`|<_ZA^1=Qeqb6; zCLWa}S~I{Q9(Sw|k%Xa38{b0rm{y`38SIt|D!qs?-foxQdkF^gDTiM5T3O^z?2Ct2 zE|9!imG0C15_?9c0W>v+@(Qxgm7we}4U^9d0%HBnp@=iYZR)pCedUeLWL}Szh*V(x z;*sB1dxa08#kJ^jGmCGbBnantNS6T42q=@el?9<}LQNr;cc#Xn45!dDHUv$nQ&%19*1I5{tYK3<0cFQ@`PSEGU3!-aQ_1f_u! z^IT1j$^E*VPPt{gEX0AsqF?SE1dqMtQm48fEc6=GH=(7Q>2;&Be@;TE%j&B54YCt= zZhb#n)7i;B&x|fvuC?51zCpn4AW5qX@3s#14qZ;)=k=sV@aR- z@l`}F*K!~{uI>!ZyX~}Do)Q$3Ym#A|@3qCxHz0NX+DpvL+-#d^-nJLk{`_m(QO$1L z7w`VQJA9+yFafl8*4c55chE69Yz?7jzT4=@?JS{zPnG--5z~CB)Xk>;KH0MWN5e2LrY9s#t@GXLHML z>WTHj-_+u6%lx$)&IRFtZr^8RHSSb53#rkR+7|wfxc;{WbO5z+yp) zBHZ8QZ=kqS+aD+Xm!cPy|N5mLHg0$SGZe%ng%oTQrM_}|p}-Rvxq}H%Qxdk$W!5pJ z28+g-xkeY5vPvp+sniO*lf!BVg@%f`%Px(K2D>V0&tnc?iE~|f@aDDqk(%yP z2tA}sMDLrOf2cEOhnvDZ*kQ60;!5ESIc$nNf;dA6$5ag5RFsa{=#Y%KwLF!u{l%Z! zKi_=XVDwdJms&;FA=hWtfEA2&ix*RskTVY9x!>)%^$z4@k$o@lU3IQ`>SlJ5PiSKf zVjFSufAGk~Nfmn8^uAAsh#R<3e$@8lxCa#4hwmAOb>T1i*p*>z$}7nc=!GHJ6EBj! zx0aAu)V}lnp4(j1SR5U~&3qm4k0{1e7;#AHx1>^ilvwUHsn3 z0oDn*ceKv`97kFWAzf5^w~N6m4NuvqkkHgM>&E^-p=v^Pvr5mWZ$j{U>l>cV%xdI* z^1ouzAL$?YZ%z8Ax_>Mwk>RsavanbVh>YIwjcUL<_9a(|Lx^)x>8M&&*=Z)bnafsi zSbEzOZ$F7UMaWZ7PWy$=n1I|bP!*ajyB$ltxMt8r;zNwb~A(8E=hKAK zqR50}1bMo|xzxCj=q=dimZ+SiKmZzpuMEJL)^&|+2TSEMDC4zo8Bvr4hMg1zUDrht zhlW)1Mj?#JvkKvv| zdE=v{iyJe_oTqIju{;s#GpYNk${&-l{e=>PI!^15Vz9 z!)prGV~f{dmeC}$!VAl9C*4!cQam%X{36HqzHOvOGrDfyaXalh$kFSVRmdtyByi`8tsR*d&j!&{waRk| z>Dw~YYpy&nu+)VZLe0Y}yvyMKyrr-Mszx#yX`B#Cm#ep|<}<7<7$vt14}=w$zaMqj zqMJ+kO89!TJvp2vsCRt$y9rZ{Et>b3ORrI{SuDjgpXD;PU~0YF-S7KOR0Zdns*xnm zJafKWe0=|ZX03rp=n$YDB2{7>Px-;^!&9nGqv2lHuk2E2_6hc_qN%^*CNJ9MQuE~d zl4!6gK8N$1#}nnwaeG|t6QT6${f4v)4@DWEae0v>G9y$|)JQ5X>?b9<&HDPP*W8Gs z3Q_@aAoCNyvqJKP6_KKaJei%D%wMG9$Pvh0DEoHTO!f}?Uc)59%X1QyW%rXJFh_qV z#Zo=3eFvhhTeY5r3U-fbRV-r0f0kkG|`-8 zYvJY4(?>Uf(jgB&NGC`1DN3bVkO z(O;hKONc|Ky%A_K=(;L7wtJ_MTTL|Rflv&1F?o&i|-J=}HM z#rjTVKBy5Jg_NpPKKZ{`l)i~f-dO@}7JSv2;G>DZt3Pj*J8xx>&LSOO5`V0+D%k