From 4f5d32af367abffc83baecdcb9a429414102f975 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Tue, 27 May 2014 13:50:48 +0100 Subject: [PATCH 01/16] Disable ADC debug output --- src/drivers/adc_common.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/adc_common.c b/src/drivers/adc_common.c index 0d380b0113..e554693724 100755 --- a/src/drivers/adc_common.c +++ b/src/drivers/adc_common.c @@ -15,7 +15,7 @@ extern int16_t debug[4]; uint16_t adcGetChannel(uint8_t channel) { -#if 1 +#if 0 if (adcConfig[0].enabled) { debug[0] = adcValues[adcConfig[0].dmaIndex]; } From f74a31f8002d36467cb2b669874773b9d7fdca13 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 26 May 2014 19:54:30 +0100 Subject: [PATCH 02/16] Update Failsafe.md --- docs/Failsafe.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/Failsafe.md b/docs/Failsafe.md index 5b5089ec0d..bf76a6dbc3 100644 --- a/docs/Failsafe.md +++ b/docs/Failsafe.md @@ -42,7 +42,7 @@ Delay after failsafe activates before motors finally turn off. If you fly high ### `failsafe_throttle` -Throttle level used for landing. Specify a value the causes that aircraft to descend at about 1M/sec. +Throttle level used for landing. Specify a value that causes the aircraft to descend at about 1M/sec. Use standard RX usec values. See Rx documentation. From 49c283fe59f47933c22560d55ba979e5454bf5b1 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 26 May 2014 19:59:21 +0100 Subject: [PATCH 03/16] Update Failsafe.md formatting. --- docs/Failsafe.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Failsafe.md b/docs/Failsafe.md index bf76a6dbc3..5dc64e4239 100644 --- a/docs/Failsafe.md +++ b/docs/Failsafe.md @@ -2,8 +2,8 @@ There are two types of failsafe: -1) receiver based failsafe -2) flight controller based failsafe +1. receiver based failsafe +2. flight controller based failsafe Receiver based failsafe is where you, from your transmitter and receiver, configure channels to output desired signals if your receiver detects signal loss. The idea is that you set throttle and other controls so the aircraft descends in a controlled manner. From f7c38af7fc04360edd457382b8c67bc38a616ce4 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Tue, 27 May 2014 00:33:28 +0100 Subject: [PATCH 04/16] Initial commit for implementation of autotune. --- Makefile | 1 + docs/Autotune.md | 46 ++++++++++++++++++++++++++++ src/config.c | 2 +- src/flight_autotune.c | 71 +++++++++++++++++++++++++++++++++++++++++++ src/flight_autotune.h | 9 ++++++ src/flight_common.c | 21 +++++++++++++ src/flight_common.h | 4 +-- src/mw.c | 27 ++++++++++++++++ src/runtime_config.h | 2 ++ src/serial_msp.c | 4 +++ 10 files changed, 184 insertions(+), 3 deletions(-) create mode 100644 docs/Autotune.md create mode 100644 src/flight_autotune.c create mode 100644 src/flight_autotune.h diff --git a/Makefile b/Makefile index ab782e43ad..1df8475281 100644 --- a/Makefile +++ b/Makefile @@ -112,6 +112,7 @@ COMMON_SRC = build_config.c \ drivers/serial_common.c \ drivers/sound_beeper.c \ drivers/system_common.c \ + flight_autotune.c \ flight_common.c \ flight_imu.c \ flight_mixer.c \ diff --git a/docs/Autotune.md b/docs/Autotune.md new file mode 100644 index 0000000000..305e212096 --- /dev/null +++ b/docs/Autotune.md @@ -0,0 +1,46 @@ +# Autotune + +Autotune helps to automatically tune your multirotor. + +## Configuration. + +Autotune only works in HORIZON or ANGLE mode. + +Configure a switch on your transmitter to activate the AUTOTUNE and HORIZON or ANGLE modes using the auxilary configuration. + +## Using autotuning + +Launch the multirotor. + +Flip the autotune switch on your transmitter. + +Observe roll/left/right a few times. + +PID settings will have been updated for ROLL/YAW. + +Disable the switch while still flying. + +Enable the switch again. + +Observe pitch forwards/backwards a few times. + +PID settings will have been updated for PITCH/YAW. + +Disable the switch again. + +PIDS are tunes, fly and see if it's better. + +Land. + +Verify results via an app while power still applied if desired. + +Cutting the power will loose the unsaved pids. + +If you're happy with the pids then while disarmed flip the autotune switch again to save all settings. + +A beeper will sound indicating the settings are saved. + + +# References + +* Brad Quick for the initial Autotune algorithm in BradWii. \ No newline at end of file diff --git a/src/config.c b/src/config.c index 0043eb9672..0913206277 100755 --- a/src/config.c +++ b/src/config.c @@ -58,7 +58,7 @@ void mixerUseConfigs(servoParam_t *servoConfToUse, flight3DConfig_t *flight3DCon #define FLASH_WRITE_ADDR (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG)) // use the last flash pages for storage master_t masterConfig; // master config struct with data independent from profiles profile_t currentProfile; // profile config struct -static const uint8_t EEPROM_CONF_VERSION = 69; +static const uint8_t EEPROM_CONF_VERSION = 70; static void resetAccelerometerTrims(int16_flightDynamicsTrims_t *accelerometerTrims) { diff --git a/src/flight_autotune.c b/src/flight_autotune.c new file mode 100644 index 0000000000..46a8e27d84 --- /dev/null +++ b/src/flight_autotune.c @@ -0,0 +1,71 @@ +#include +#include +#include + +#include "common/axis.h" +#include "common/maths.h" + +#include "flight_common.h" + +// To adjust how agressive the tuning is, adjust the AUTOTUNEMAXOSCILLATION value. A larger +// value will result in more agressive tuning. A lower value will result in softer tuning. +// It will rock back and forth between -AUTOTUNE_TARGET_ANGLE and AUTOTUNE_TARGET_ANGLE degrees +// AUTOTUNE_D_MULTIPLIER is a multiplier that puts in a little extra D when autotuning is done. This helps damp +// the wobbles after a quick angle change. +// Always autotune on a full battery. +#define AUTOTUNE_MAX_OSCILLATION 1.0 +#define AUTOTUNE_TARGET_ANGLE 20.0 +#define AUTOTUNE_D_MULTIPLIER 1.2 + +static pidProfile_t *pidProfile; +static uint8_t pidController; +static bool rising; +static float targetAngle = 0; + +static angle_index_t autoTuneAngleIndex; + +float autotune(angle_index_t angleIndex, rollAndPitchInclination_t *inclination, float errorAngle) +{ + if (autoTuneAngleIndex != angleIndex) { + // Not tuning this angle yet. + return errorAngle; + } + + // TODO autotune! + + if (rising) { + targetAngle = AUTOTUNE_TARGET_ANGLE; + } + else { + targetAngle = -AUTOTUNE_TARGET_ANGLE; + } + + + return targetAngle - inclination->rawAngles[angleIndex]; +} + +void autotuneReset(void) +{ + targetAngle = 0; + rising = true; + autoTuneAngleIndex = AI_ROLL; +} + +void autotuneBegin(pidProfile_t *pidProfileToTune, uint8_t pidControllerInUse) +{ + autotuneReset(); + + pidProfile = pidProfileToTune; + pidController = pidControllerInUse; +} + +void autotuneEnd(void) +{ + +} + +bool havePidsBeenUpdatedByAutotune(void) +{ + return targetAngle != 0; +} + diff --git a/src/flight_autotune.h b/src/flight_autotune.h new file mode 100644 index 0000000000..b3aa65c380 --- /dev/null +++ b/src/flight_autotune.h @@ -0,0 +1,9 @@ +#pragma once + +void autotuneReset(); +void autotuneBegin(pidProfile_t *pidProfileToTune, uint8_t pidControllerInUse); +float autotune(angle_index_t angleIndex, rollAndPitchInclination_t *inclination, float errorAngle); +void autotuneEnd(); + +bool havePidsBeenUpdatedByAutotune(void); + diff --git a/src/flight_common.c b/src/flight_common.c index 8fc3618819..398321a0bb 100644 --- a/src/flight_common.c +++ b/src/flight_common.c @@ -12,6 +12,7 @@ #include "sensors_gyro.h" #include "rc_controls.h" #include "flight_common.h" +#include "flight_autotune.h" #include "gps_common.h" extern uint16_t cycleTime; @@ -55,6 +56,12 @@ void resetErrorGyro(void) errorGyroIf[YAW] = 0; } +angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH }; + +bool shouldAutotune(void) +{ + return f.ARMED && f.AUTOTUNE_MODE; +} static void pidBaseflight(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim) @@ -77,6 +84,11 @@ static void pidBaseflight(pidProfile_t *pidProfile, controlRateConfig_t *control } else { // calculate error and limit the angle to 50 degrees max inclination errorAngle = (constrain(rcCommand[axis] + GPS_angle[axis], -500, +500) - inclination.rawAngles[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here + + if (shouldAutotune()) { + errorAngle = autotune(rcAliasToAngleIndexMap[axis], &inclination, errorAngle); + } + if (!f.ANGLE_MODE) { //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID AngleRate = (float)((controlRateConfig->rollPitchRate + 20) * rcCommand[axis]) / 50.0f; // 200dps to 1200dps max yaw rate if (f.HORIZON_MODE) { @@ -141,6 +153,11 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa // 50 degrees max inclination errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination), +max_angle_inclination) - inclination.rawAngles[axis] + angleTrim->raw[axis]; + + if (shouldAutotune()) { + errorAngle = autotune(rcAliasToAngleIndexMap[axis], &inclination, errorAngle); + } + PTermACC = errorAngle * pidProfile->P8[PIDLEVEL] / 100; // 32 bits is needed for calculation: errorAngle*P8[PIDLEVEL] could exceed 32768 16 bits is ok for result PTermACC = constrain(PTermACC, -pidProfile->D8[PIDLEVEL] * 5, +pidProfile->D8[PIDLEVEL] * 5); @@ -205,6 +222,10 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat errorAngle = constrain((rcCommand[axis] << 1) + GPS_angle[axis], -((int) max_angle_inclination), +max_angle_inclination) - inclination.rawAngles[axis] + angleTrim->raw[axis]; // 16 bits is ok here + if (shouldAutotune()) { + errorAngle = autotune(rcAliasToAngleIndexMap[axis], &inclination, errorAngle); + } + if (!f.ANGLE_MODE) { //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID AngleRateTmp = ((int32_t)(controlRateConfig->rollPitchRate + 27) * rcCommand[axis]) >> 4; if (f.HORIZON_MODE) { diff --git a/src/flight_common.h b/src/flight_common.h index 31b2576cd0..f5767a16b6 100644 --- a/src/flight_common.h +++ b/src/flight_common.h @@ -27,7 +27,7 @@ typedef struct pidProfile_s { float H_level; } pidProfile_t; -enum { +typedef enum { AI_ROLL = 0, AI_PITCH, } angle_index_t; @@ -35,7 +35,7 @@ enum { #define ANGLE_INDEX_COUNT 2 // See http://en.wikipedia.org/wiki/Flight_dynamics -enum { +typedef enum { FD_ROLL = 0, FD_PITCH, FD_YAW diff --git a/src/mw.c b/src/mw.c index 0d5f359a8a..b738c7bdee 100755 --- a/src/mw.c +++ b/src/mw.c @@ -22,6 +22,7 @@ #include "failsafe.h" #include "flight_imu.h" #include "flight_common.h" +#include "flight_autotune.h" #include "flight_mixer.h" #include "gimbal.h" #include "gps_common.h" @@ -78,6 +79,30 @@ bool AccInflightCalibrationSavetoEEProm = false; bool AccInflightCalibrationActive = false; uint16_t InflightcalibratingA = 0; +void updateAutotuneState(void) +{ + if (rcOptions[BOXAUTOTUNE]) { + if (!f.AUTOTUNE_MODE) { + if (f.ARMED) { + autotuneBegin(¤tProfile.pidProfile, currentProfile.pidController); + f.AUTOTUNE_MODE = 1; + } else { + if (havePidsBeenUpdatedByAutotune()) { + //writeEEPROM(); + blinkLedAndSoundBeeper(5, 50, 1); + autotuneReset(); + } + } + } + return; + } + + if (f.AUTOTUNE_MODE) { + autotuneEnd(); + f.AUTOTUNE_MODE = 0; + } +} + bool isCalibrating() { #ifdef BARO @@ -603,6 +628,8 @@ void loop(void) cycleTime = (int32_t)(currentTime - previousTime); previousTime = currentTime; + updateAutotuneState(); + #ifdef MAG if (sensors(SENSOR_MAG)) { if (abs(rcCommand[YAW]) < 70 && f.MAG_MODE) { diff --git a/src/runtime_config.h b/src/runtime_config.h index 2d8b37aeb8..e64c8b5a35 100644 --- a/src/runtime_config.h +++ b/src/runtime_config.h @@ -22,6 +22,7 @@ enum { BOXGOV, BOXOSD, BOXTELEMETRY, + BOXAUTOTUNE, CHECKBOX_ITEM_COUNT }; @@ -46,6 +47,7 @@ typedef struct flags_t { uint8_t CALIBRATE_MAG; uint8_t VARIO_MODE; uint8_t FIXED_WING; // set when in flying_wing or airplane mode. currently used by althold selection code + uint8_t AUTOTUNE_MODE; } flags_t; extern flags_t f; diff --git a/src/serial_msp.c b/src/serial_msp.c index 847bab7ab9..f19b289627 100755 --- a/src/serial_msp.c +++ b/src/serial_msp.c @@ -139,6 +139,7 @@ struct box_t { { BOXGOV, "GOVERNOR;", 18 }, { BOXOSD, "OSD SW;", 19 }, { BOXTELEMETRY, "TELEMETRY;", 20 }, + { BOXAUTOTUNE, "AUTOTUNE;", 21 }, { CHECKBOX_ITEM_COUNT, NULL, 0xFF } }; @@ -367,6 +368,8 @@ void mspInit(serialConfig_t *serialConfig) if (feature(FEATURE_TELEMETRY && masterConfig.telemetryConfig.telemetry_switch)) availableBoxes[idx++] = BOXTELEMETRY; + availableBoxes[idx++] = BOXAUTOTUNE; + numberBoxItems = idx; openAllMSPSerialPorts(serialConfig); @@ -513,6 +516,7 @@ static void evaluateCommand(void) rcOptions[BOXGOV] << BOXGOV | rcOptions[BOXOSD] << BOXOSD | rcOptions[BOXTELEMETRY] << BOXTELEMETRY | + rcOptions[BOXAUTOTUNE] << BOXAUTOTUNE | f.ARMED << BOXARM; for (i = 0; i < numberBoxItems; i++) { int flag = (tmp & (1 << availableBoxes[i])); From 4c764aacf4b9a35179736946459938d02de18219 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Tue, 27 May 2014 14:37:28 +0100 Subject: [PATCH 05/16] Autotune phase changes. Add an additional phase to allow previous pid settings to be restored, in flight, after auto tuning. --- src/flight_autotune.c | 261 +++++++++++++++++++++++++++++++++++++++--- src/flight_autotune.h | 6 +- src/flight_common.c | 5 +- src/flight_common.h | 3 + src/mw.c | 13 ++- 5 files changed, 262 insertions(+), 26 deletions(-) diff --git a/src/flight_autotune.c b/src/flight_autotune.c index 46a8e27d84..f21e1ddb70 100644 --- a/src/flight_autotune.c +++ b/src/flight_autotune.c @@ -1,38 +1,68 @@ #include #include +#include #include #include "common/axis.h" #include "common/maths.h" +#include "drivers/system_common.h" + #include "flight_common.h" -// To adjust how agressive the tuning is, adjust the AUTOTUNEMAXOSCILLATION value. A larger -// value will result in more agressive tuning. A lower value will result in softer tuning. +extern int16_t debug[4]; + +// To adjust how aggressive the tuning is, adjust the AUTOTUNEMAXOSCILLATION value. A larger +// value will result in more aggressive tuning. A lower value will result in softer tuning. // It will rock back and forth between -AUTOTUNE_TARGET_ANGLE and AUTOTUNE_TARGET_ANGLE degrees // AUTOTUNE_D_MULTIPLIER is a multiplier that puts in a little extra D when autotuning is done. This helps damp // the wobbles after a quick angle change. // Always autotune on a full battery. -#define AUTOTUNE_MAX_OSCILLATION 1.0 -#define AUTOTUNE_TARGET_ANGLE 20.0 -#define AUTOTUNE_D_MULTIPLIER 1.2 + +#define AUTOTUNE_MAX_OSCILLATION 1.0f +#define AUTOTUNE_TARGET_ANGLE 20.0f +#define AUTOTUNE_D_MULTIPLIER 1.2f +#define AUTOTUNE_SETTLING_DELAY_MS 250 // 1/4 of a second. + +typedef enum { + PHASE_IDLE = 0, + PHASE_TUNE_ROLL, + PHASE_TUNE_PITCH, + PHASE_SAVE_OR_RESTORE_PIDS, +} autotunePhase_e; + +#define AUTOTUNE_PHASE_MAX PHASE_SAVE_OR_RESTORE_PIDS +#define AUTOTUNE_PHASE_COUNT (AUTOTUNE_PHASE_MAX + 1) + +#define FIRST_TUNE_PHASE PHASE_TUNE_ROLL static pidProfile_t *pidProfile; +static pidProfile_t pidBackup; static uint8_t pidController; static bool rising; -static float targetAngle = 0; - +static uint8_t cycleCount; // TODO can we replace this with an enum to improve readability. +static uint32_t timeoutAt; static angle_index_t autoTuneAngleIndex; +static autotunePhase_e phase = PHASE_IDLE; +static autotunePhase_e nextPhase = FIRST_TUNE_PHASE; -float autotune(angle_index_t angleIndex, rollAndPitchInclination_t *inclination, float errorAngle) +static float targetAngle = 0; +static float targetAngleAtPeak; +static float secondPeakAngle, firstPeakAngle; // deci dgrees, 180 deg = 1800 + +bool isAutotuneIdle(void) { - if (autoTuneAngleIndex != angleIndex) { - // Not tuning this angle yet. - return errorAngle; - } + return phase == PHASE_IDLE; +} - // TODO autotune! +static void startNewCycle(void) +{ + rising = !rising; + secondPeakAngle = firstPeakAngle = 0; +} +static void updateTargetAngle(void) +{ if (rising) { targetAngle = AUTOTUNE_TARGET_ANGLE; } @@ -40,28 +70,221 @@ float autotune(angle_index_t angleIndex, rollAndPitchInclination_t *inclination, targetAngle = -AUTOTUNE_TARGET_ANGLE; } +#if 0 + debug[2] = DEGREES_TO_DECIDEGREES(targetAngle); +#endif +} - return targetAngle - inclination->rawAngles[angleIndex]; +float autotune(angle_index_t angleIndex, rollAndPitchInclination_t *inclination, float errorAngle) +{ + if (!(phase == PHASE_TUNE_ROLL || phase == PHASE_TUNE_PITCH) || autoTuneAngleIndex != angleIndex) { + return errorAngle; + } + + debug[0] = 0; + +#if 0 + debug[1] = inclination->rawAngles[angleIndex]; +#endif + + float currentAngle; + + if (rising) { + currentAngle = DECIDEGREES_TO_DEGREES(inclination->rawAngles[angleIndex]); + } else { + targetAngle = -targetAngle; + currentAngle = DECIDEGREES_TO_DEGREES(-inclination->rawAngles[angleIndex]); + } + +#if 1 + debug[1] = DEGREES_TO_DECIDEGREES(currentAngle); + debug[2] = DEGREES_TO_DECIDEGREES(targetAngle); +#endif + + if (firstPeakAngle == 0) { + // The peak will be when our angular velocity is negative. To be sure we are in the right place, + // we also check to make sure our angle position is greater than zero. + + if (currentAngle > secondPeakAngle) { + // we are still going up + secondPeakAngle = currentAngle; + targetAngleAtPeak = targetAngle; + + debug[3] = DEGREES_TO_DECIDEGREES(secondPeakAngle); + + } else if (secondPeakAngle > 0) { + if (cycleCount == 0) { + // when checking the I value, we would like to overshoot the target position by half of the max oscillation. +// if (currentangle-targetangle<(FPAUTOTUNEMAXOSCILLATION>>1)) { +// currentivalueshifted=lib_fp_multiply(currentivalueshifted,AUTOTUNEINCREASEMULTIPLIER); +// } else { +// currentivalueshifted=lib_fp_multiply(currentivalueshifted,AUTOTUNEDECREASEMULTIPLIER); +// if (currentivalueshifted= 0L; + + // stop looking for the 2nd peak if we time out or if we change direction again after moving by more than half the maximum oscillation + if (timedOut || (oscillationAmplitude > AUTOTUNE_MAX_OSCILLATION / 2 && currentAngle > firstPeakAngle)) { + // analyze the data + // Our goal is to have zero overshoot and to have AUTOTUNEMAXOSCILLATION amplitude + + + if (secondPeakAngle > targetAngleAtPeak) { + // overshot + debug[0] = 1; + +#ifdef PREFER_HIGH_GAIN_SOLUTION + if (oscillationAmplitude > AUTOTUNE_MAX_OSCILLATION) { + // we have too much oscillation, so we can't increase D, so decrease P +#endif + // decrease P + //currentpvalueshifted=lib_fp_multiply(currentpvalueshifted, AUTOTUNEDECREASEMULTIPLIER); // TODO + +#ifdef PREFER_HIGH_GAIN_SOLUTION + } else { + // we don't have too much oscillation, so we can increase D" +#endif + + // increase D + //currentdvalueshifted=lib_fp_multiply(currentdvalueshifted, AUTOTUNEINCREASEMULTIPLIER); // TODO +#ifdef PREFER_HIGH_GAIN_SOLUTION + } +#endif + } else { + // undershot + debug[0] = 2; + + if (oscillationAmplitude > AUTOTUNE_MAX_OSCILLATION) { + // we have too much oscillation, so we should lower D + //currentdvalueshifted=lib_fp_multiply(currentdvalueshifted, AUTOTUNEDECREASEMULTIPLIER); // TODO + } else { + // we don't have too much oscillation, so we increase P + //currentpvalueshifted=lib_fp_multiply(currentpvalueshifted, AUTOTUNEINCREASEMULTIPLIER); // TODO + } + } + + //usersettings.pid_pgain[autotuneindex]=currentpvalueshifted>>AUTOTUNESHIFT; // TODO + //usersettings.pid_dgain[autotuneindex]=currentdvalueshifted>>AUTOTUNESHIFT; // TODO + + // switch to the other direction and start a new cycle + startNewCycle(); + + if (++cycleCount == 3) { + // switch to testing I value + cycleCount = 0; + + //usersettings.pid_igain[autotuneindex]=currentivalueshifted>>AUTOTUNESHIFT; // TODO + } + } + } + + if (angleIndex == AI_ROLL) { + debug[0] += 100; + } + + updateTargetAngle(); + + return targetAngle - DECIDEGREES_TO_DEGREES(inclination->rawAngles[angleIndex]); } void autotuneReset(void) { targetAngle = 0; - rising = true; - autoTuneAngleIndex = AI_ROLL; + phase = PHASE_IDLE; + nextPhase = FIRST_TUNE_PHASE; } -void autotuneBegin(pidProfile_t *pidProfileToTune, uint8_t pidControllerInUse) +void backupPids(pidProfile_t *pidProfileToTune) { - autotuneReset(); + memcpy(&pidBackup, pidProfileToTune, sizeof(pidBackup)); +} + +void restorePids(pidProfile_t *pidProfileToTune) +{ + memcpy(pidProfileToTune, &pidBackup, sizeof(pidBackup)); +} + +void autotuneBeginNextPhase(pidProfile_t *pidProfileToTune, uint8_t pidControllerInUse) +{ + phase = nextPhase; + + if (phase == PHASE_SAVE_OR_RESTORE_PIDS) { + restorePids(pidProfileToTune); + return; + } + + if (phase == FIRST_TUNE_PHASE) { + backupPids(pidProfileToTune); + } + + if (phase == PHASE_TUNE_ROLL) { + autoTuneAngleIndex = AI_ROLL; + } if (phase == PHASE_TUNE_PITCH) { + autoTuneAngleIndex = AI_PITCH; + } + + rising = true; + cycleCount = 1; + secondPeakAngle = firstPeakAngle = 0; pidProfile = pidProfileToTune; pidController = pidControllerInUse; + + updateTargetAngle(); + + // TODO +// currentpvalueshifted=usersettings.pid_pgain[autotuneindex]<>AUTOTUNESHIFT; +// +// // multiply by D multiplier. The best D is usually a little higher than what the algroithm produces. +// usersettings.pid_dgain[autotuneindex]=lib_fp_multiply(currentdvalueshifted,FPAUTOTUNE_D_MULTIPLIER)>>AUTOTUNESHIFT; +// +// usersettings.pid_igain[YAWINDEX]=usersettings.pid_igain[ROLLINDEX]; +// usersettings.pid_dgain[YAWINDEX]=usersettings.pid_dgain[ROLLINDEX]; +// usersettings.pid_pgain[YAWINDEX]=lib_fp_multiply(usersettings.pid_pgain[ROLLINDEX],YAWGAINMULTIPLIER); + if (phase == AUTOTUNE_PHASE_MAX) { + phase = PHASE_IDLE; + nextPhase = FIRST_TUNE_PHASE; + } else { + nextPhase++; + } } bool havePidsBeenUpdatedByAutotune(void) diff --git a/src/flight_autotune.h b/src/flight_autotune.h index b3aa65c380..69cc01f7d2 100644 --- a/src/flight_autotune.h +++ b/src/flight_autotune.h @@ -1,9 +1,11 @@ #pragma once void autotuneReset(); -void autotuneBegin(pidProfile_t *pidProfileToTune, uint8_t pidControllerInUse); +void autotuneBeginNextPhase(pidProfile_t *pidProfileToTune, uint8_t pidControllerInUse); float autotune(angle_index_t angleIndex, rollAndPitchInclination_t *inclination, float errorAngle); -void autotuneEnd(); +void autotuneEndPhase(); +bool isAutotuneIdle(void); +bool hasAutotunePhaseCompleted(void); bool havePidsBeenUpdatedByAutotune(void); diff --git a/src/flight_common.c b/src/flight_common.c index 398321a0bb..a2e53abf9a 100644 --- a/src/flight_common.c +++ b/src/flight_common.c @@ -135,6 +135,7 @@ static void pidBaseflight(pidProfile_t *pidProfile, controlRateConfig_t *control } } + static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim) { @@ -155,7 +156,7 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa +max_angle_inclination) - inclination.rawAngles[axis] + angleTrim->raw[axis]; if (shouldAutotune()) { - errorAngle = autotune(rcAliasToAngleIndexMap[axis], &inclination, errorAngle); + errorAngle = DEGREES_TO_DECIDEGREES(autotune(rcAliasToAngleIndexMap[axis], &inclination, DECIDEGREES_TO_DEGREES(errorAngle))); } PTermACC = errorAngle * pidProfile->P8[PIDLEVEL] / 100; // 32 bits is needed for calculation: errorAngle*P8[PIDLEVEL] could exceed 32768 16 bits is ok for result @@ -223,7 +224,7 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat +max_angle_inclination) - inclination.rawAngles[axis] + angleTrim->raw[axis]; // 16 bits is ok here if (shouldAutotune()) { - errorAngle = autotune(rcAliasToAngleIndexMap[axis], &inclination, errorAngle); + errorAngle = DEGREES_TO_DECIDEGREES(autotune(rcAliasToAngleIndexMap[axis], &inclination, DECIDEGREES_TO_DEGREES(errorAngle))); } if (!f.ANGLE_MODE) { //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID diff --git a/src/flight_common.h b/src/flight_common.h index f5767a16b6..3d50aff4d0 100644 --- a/src/flight_common.h +++ b/src/flight_common.h @@ -98,6 +98,9 @@ typedef union { } rollAndPitchInclination_t; +#define DEGREES_TO_DECIDEGREES(angle) (angle * 10) +#define DECIDEGREES_TO_DEGREES(angle) (angle / 10.0f) + extern rollAndPitchInclination_t inclination; extern int16_t gyroData[FLIGHT_DYNAMICS_INDEX_COUNT]; diff --git a/src/mw.c b/src/mw.c index b738c7bdee..3d87f7c382 100755 --- a/src/mw.c +++ b/src/mw.c @@ -84,7 +84,10 @@ void updateAutotuneState(void) if (rcOptions[BOXAUTOTUNE]) { if (!f.AUTOTUNE_MODE) { if (f.ARMED) { - autotuneBegin(¤tProfile.pidProfile, currentProfile.pidController); + if (isAutotuneIdle()) { + autotuneReset(); + } + autotuneBeginNextPhase(¤tProfile.pidProfile, currentProfile.pidController); f.AUTOTUNE_MODE = 1; } else { if (havePidsBeenUpdatedByAutotune()) { @@ -98,7 +101,7 @@ void updateAutotuneState(void) } if (f.AUTOTUNE_MODE) { - autotuneEnd(); + autotuneEndPhase(); f.AUTOTUNE_MODE = 0; } } @@ -231,7 +234,11 @@ void annexCode(void) f.OK_TO_ARM = 1; - if (!f.ARMED && !f.SMALL_ANGLE) { + if (!f.SMALL_ANGLE) { + f.OK_TO_ARM = 0; + } + + if (rcOptions[BOXAUTOTUNE]) { f.OK_TO_ARM = 0; } From 0280e96a9a0644bbbf1aa88a0db0100255017332 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Tue, 27 May 2014 17:57:06 +0100 Subject: [PATCH 06/16] Replace unused runtime warning beep code with autotune beep code. --- src/buzzer.c | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/src/buzzer.c b/src/buzzer.c index e2cd71699e..dfba21ed06 100644 --- a/src/buzzer.c +++ b/src/buzzer.c @@ -39,7 +39,6 @@ void buzzer(bool warn_vbat) static uint8_t beeperOnBox; static uint8_t warn_noGPSfix = 0; static failsafeBuzzerWarnings_e warn_failsafe = FAILSAFE_IDLE; - static uint8_t warn_runtime = 0; //===================== BeeperOn via rcOptions ===================== if (rcOptions[BOXBEEPERON]) { // unconditional beeper on via AUXn switch @@ -88,8 +87,8 @@ void buzzer(bool warn_vbat) beep_code('S','S','S','M'); // beeperon else if (warn_vbat) beep_code('S','M','M','D'); - else if (warn_runtime == 1 && f.ARMED) - beep_code('S','S','M','N'); // Runtime warning + else if (f.AUTOTUNE_MODE) + beep_code('S','M','S','M'); else if (toggleBeep > 0) beep(50); // fast confirmation beep else { From 2cf686b36b808ce6cfec0068472ae0fe2811e712 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Tue, 27 May 2014 18:00:42 +0100 Subject: [PATCH 07/16] If auto tune was used, and the user landed the aircraft, then before it is used again it must be reset. Otherwise the first flip of the switch would start the next phase which could mean that PID settings were restored. --- src/mw.c | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/src/mw.c b/src/mw.c index 3d87f7c382..85b5beaef1 100755 --- a/src/mw.c +++ b/src/mw.c @@ -81,14 +81,19 @@ uint16_t InflightcalibratingA = 0; void updateAutotuneState(void) { + static bool landedAfterAutoTuning = false; + static bool autoTuneWasUsed = false; + if (rcOptions[BOXAUTOTUNE]) { if (!f.AUTOTUNE_MODE) { if (f.ARMED) { - if (isAutotuneIdle()) { + if (isAutotuneIdle() || landedAfterAutoTuning) { autotuneReset(); + landedAfterAutoTuning = false; } autotuneBeginNextPhase(¤tProfile.pidProfile, currentProfile.pidController); f.AUTOTUNE_MODE = 1; + autoTuneWasUsed = true; } else { if (havePidsBeenUpdatedByAutotune()) { //writeEEPROM(); @@ -104,6 +109,10 @@ void updateAutotuneState(void) autotuneEndPhase(); f.AUTOTUNE_MODE = 0; } + + if (!f.ARMED && autoTuneWasUsed) { + landedAfterAutoTuning = true; + } } bool isCalibrating() From bc84f6d5d469525a956c84e32028260fd53f676b Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Tue, 27 May 2014 21:20:29 +0100 Subject: [PATCH 08/16] Update autotune so it now actually changes the pid values. This commit also fixes a few missing const keywords after the map file was inspected. --- docs/Autotune.md | 27 ++++++---- src/flight_autotune.c | 121 ++++++++++++++++++++++++++++-------------- src/flight_autotune.h | 2 +- src/flight_common.c | 2 +- src/flight_common.h | 4 +- src/serial_common.c | 4 +- src/serial_common.h | 2 +- src/serial_msp.c | 2 +- 8 files changed, 105 insertions(+), 59 deletions(-) diff --git a/docs/Autotune.md b/docs/Autotune.md index 305e212096..3fc1b12376 100644 --- a/docs/Autotune.md +++ b/docs/Autotune.md @@ -4,31 +4,38 @@ Autotune helps to automatically tune your multirotor. ## Configuration. -Autotune only works in HORIZON or ANGLE mode. +Autotune only works in HORIZON or ANGLE mode, before using auto-tune it's best you setup so there is as little drift as possible. +Autotuning is best on a full battery in good flying conditions, i.e. no or minimal wind. + +Configure a two position switch on your transmitter to activate the AUTOTUNE and HORIZON or ANGLE modes using the auxilary configuration. +You may find a momentary switch more suitable than a toggle switch. -Configure a switch on your transmitter to activate the AUTOTUNE and HORIZON or ANGLE modes using the auxilary configuration. ## Using autotuning +Turn off the autotune switch. If the autotune switch is on while not armed the warning LED will flash and you cannot arm. + Launch the multirotor. -Flip the autotune switch on your transmitter. +Turn on/hold the autotune switch on your transmitter. -Observe roll/left/right a few times. +Observe roll left/right. A beep code will sound on the buzzer. + +Turn off/release the switch while still flying to stop this phase of tuning. PID settings will have been updated for ROLL/YAW. -Disable the switch while still flying. +Turn on/hold the switch again. -Enable the switch again. +Observe pitch forwards/backwards. A beep code will sound on the buzzer. -Observe pitch forwards/backwards a few times. +Turn off/release the switch while still flying to stop this phase of tuning. PID settings will have been updated for PITCH/YAW. -Disable the switch again. +PIDS are updated, fly and see if it's better. -PIDS are tunes, fly and see if it's better. +If it's worse, flip the switch again to restore previous pids that were present prior to arming. Land. @@ -36,7 +43,7 @@ Verify results via an app while power still applied if desired. Cutting the power will loose the unsaved pids. -If you're happy with the pids then while disarmed flip the autotune switch again to save all settings. +If you're happy with the pids then while disarmed flip the autotune switch again to save all settings then flip it back so you can arm again. A beeper will sound indicating the settings are saved. diff --git a/src/flight_autotune.c b/src/flight_autotune.c index f21e1ddb70..b6cd98d891 100644 --- a/src/flight_autotune.c +++ b/src/flight_autotune.c @@ -24,6 +24,14 @@ extern int16_t debug[4]; #define AUTOTUNE_D_MULTIPLIER 1.2f #define AUTOTUNE_SETTLING_DELAY_MS 250 // 1/4 of a second. +#define AUTOTUNE_INCREASE_MULTIPLIER 1.03f +#define AUTOTUNE_DECREASE_MULTIPLIER 0.97f + +#define AUTOTUNE_MINIMUM_I_VALUE 0.001f + +#define YAW_GAIN_MULTIPLIER 2.0f + + typedef enum { PHASE_IDLE = 0, PHASE_TUNE_ROLL, @@ -31,6 +39,11 @@ typedef enum { PHASE_SAVE_OR_RESTORE_PIDS, } autotunePhase_e; +static const pidIndex_e angleIndexToPidIndexMap[] = { + PIDROLL, + PIDPITCH +}; + #define AUTOTUNE_PHASE_MAX PHASE_SAVE_OR_RESTORE_PIDS #define AUTOTUNE_PHASE_COUNT (AUTOTUNE_PHASE_MAX + 1) @@ -39,6 +52,7 @@ typedef enum { static pidProfile_t *pidProfile; static pidProfile_t pidBackup; static uint8_t pidController; +static uint8_t pidIndex; static bool rising; static uint8_t cycleCount; // TODO can we replace this with an enum to improve readability. static uint32_t timeoutAt; @@ -50,6 +64,19 @@ static float targetAngle = 0; static float targetAngleAtPeak; static float secondPeakAngle, firstPeakAngle; // deci dgrees, 180 deg = 1800 +typedef struct fp_pid { + float p; + float i; + float d; +} fp_pid_t; + +static fp_pid_t pid; + +// These are used to convert between multiwii integer values to the float pid values used by the autotuner. +#define MULTIWII_P_MULTIPLIER 10.0f // e.g 0.4 * 10 = 40 +#define MULTIWII_I_MULTIPLIER 1000.0f // e.g 0.030 * 1000 = 30 +// Note there is no D multiplier since D values are stored and used AS-IS + bool isAutotuneIdle(void) { return phase == PHASE_IDLE; @@ -61,6 +88,11 @@ static void startNewCycle(void) secondPeakAngle = firstPeakAngle = 0; } +static void updatePidIndex(void) +{ + pidIndex = angleIndexToPidIndexMap[autoTuneAngleIndex]; +} + static void updateTargetAngle(void) { if (rising) { @@ -75,19 +107,26 @@ static void updateTargetAngle(void) #endif } -float autotune(angle_index_t angleIndex, rollAndPitchInclination_t *inclination, float errorAngle) +float autotune(angle_index_t angleIndex, const rollAndPitchInclination_t *inclination, float errorAngle) { + float currentAngle; + if (!(phase == PHASE_TUNE_ROLL || phase == PHASE_TUNE_PITCH) || autoTuneAngleIndex != angleIndex) { return errorAngle; } + if (pidController == 2) { + // TODO support new baseflight pid controller + return errorAngle; + } + debug[0] = 0; #if 0 debug[1] = inclination->rawAngles[angleIndex]; #endif - float currentAngle; + updatePidIndex(); if (rising) { currentAngle = DECIDEGREES_TO_DEGREES(inclination->rawAngles[angleIndex]); @@ -115,16 +154,18 @@ float autotune(angle_index_t angleIndex, rollAndPitchInclination_t *inclination, } else if (secondPeakAngle > 0) { if (cycleCount == 0) { // when checking the I value, we would like to overshoot the target position by half of the max oscillation. -// if (currentangle-targetangle<(FPAUTOTUNEMAXOSCILLATION>>1)) { -// currentivalueshifted=lib_fp_multiply(currentivalueshifted,AUTOTUNEINCREASEMULTIPLIER); -// } else { -// currentivalueshifted=lib_fp_multiply(currentivalueshifted,AUTOTUNEDECREASEMULTIPLIER); -// if (currentivalueshiftedI8[pidIndex] = 0; startNewCycle(); } else { // we are checking P and D values @@ -152,7 +193,6 @@ float autotune(angle_index_t angleIndex, rollAndPitchInclination_t *inclination, // analyze the data // Our goal is to have zero overshoot and to have AUTOTUNEMAXOSCILLATION amplitude - if (secondPeakAngle > targetAngleAtPeak) { // overshot debug[0] = 1; @@ -161,16 +201,12 @@ float autotune(angle_index_t angleIndex, rollAndPitchInclination_t *inclination, if (oscillationAmplitude > AUTOTUNE_MAX_OSCILLATION) { // we have too much oscillation, so we can't increase D, so decrease P #endif - // decrease P - //currentpvalueshifted=lib_fp_multiply(currentpvalueshifted, AUTOTUNEDECREASEMULTIPLIER); // TODO - + pid.p *= AUTOTUNE_DECREASE_MULTIPLIER; #ifdef PREFER_HIGH_GAIN_SOLUTION } else { - // we don't have too much oscillation, so we can increase D" + // we don't have too much oscillation, so we can increase D #endif - - // increase D - //currentdvalueshifted=lib_fp_multiply(currentdvalueshifted, AUTOTUNEINCREASEMULTIPLIER); // TODO + pid.d *= AUTOTUNE_INCREASE_MULTIPLIER; #ifdef PREFER_HIGH_GAIN_SOLUTION } #endif @@ -179,16 +215,16 @@ float autotune(angle_index_t angleIndex, rollAndPitchInclination_t *inclination, debug[0] = 2; if (oscillationAmplitude > AUTOTUNE_MAX_OSCILLATION) { - // we have too much oscillation, so we should lower D - //currentdvalueshifted=lib_fp_multiply(currentdvalueshifted, AUTOTUNEDECREASEMULTIPLIER); // TODO + // we have too much oscillation + pid.d *= AUTOTUNE_DECREASE_MULTIPLIER; } else { - // we don't have too much oscillation, so we increase P - //currentpvalueshifted=lib_fp_multiply(currentpvalueshifted, AUTOTUNEINCREASEMULTIPLIER); // TODO + // we don't have too much oscillation + pid.p *= AUTOTUNE_INCREASE_MULTIPLIER; } } - //usersettings.pid_pgain[autotuneindex]=currentpvalueshifted>>AUTOTUNESHIFT; // TODO - //usersettings.pid_dgain[autotuneindex]=currentdvalueshifted>>AUTOTUNESHIFT; // TODO + pidProfile->P8[pidIndex] = pid.p * MULTIWII_P_MULTIPLIER; + pidProfile->D8[pidIndex] = pid.d; // switch to the other direction and start a new cycle startNewCycle(); @@ -197,7 +233,7 @@ float autotune(angle_index_t angleIndex, rollAndPitchInclination_t *inclination, // switch to testing I value cycleCount = 0; - //usersettings.pid_igain[autotuneindex]=currentivalueshifted>>AUTOTUNESHIFT; // TODO + pidProfile->I8[pidIndex] = pid.i * MULTIWII_I_MULTIPLIER; } } } @@ -254,30 +290,33 @@ void autotuneBeginNextPhase(pidProfile_t *pidProfileToTune, uint8_t pidControlle pidProfile = pidProfileToTune; pidController = pidControllerInUse; + updatePidIndex(); updateTargetAngle(); - // TODO -// currentpvalueshifted=usersettings.pid_pgain[autotuneindex]<P8[pidIndex] / MULTIWII_P_MULTIPLIER; + pid.i = pidProfile->I8[pidIndex] / MULTIWII_I_MULTIPLIER; + // divide by D multiplier to get our working value. We'll multiply by D multiplier when we are done. + pid.d = pidProfile->D8[pidIndex] * (1.0f / AUTOTUNE_D_MULTIPLIER); + pidProfile->D8[pidIndex] = pid.d; + pidProfile->I8[pidIndex] = 0; } void autotuneEndPhase(void) { - // TODO -// usersettings.pid_igain[autotuneindex]=currentivalueshifted>>AUTOTUNESHIFT; -// -// // multiply by D multiplier. The best D is usually a little higher than what the algroithm produces. -// usersettings.pid_dgain[autotuneindex]=lib_fp_multiply(currentdvalueshifted,FPAUTOTUNE_D_MULTIPLIER)>>AUTOTUNESHIFT; -// -// usersettings.pid_igain[YAWINDEX]=usersettings.pid_igain[ROLLINDEX]; -// usersettings.pid_dgain[YAWINDEX]=usersettings.pid_dgain[ROLLINDEX]; -// usersettings.pid_pgain[YAWINDEX]=lib_fp_multiply(usersettings.pid_pgain[ROLLINDEX],YAWGAINMULTIPLIER); + if (phase == PHASE_TUNE_ROLL || phase == PHASE_TUNE_PITCH) { + + // we leave P alone, just update I and D + + pidProfile->I8[pidIndex] = pid.i * MULTIWII_I_MULTIPLIER; + + // multiply by D multiplier. The best D is usually a little higher than what the algroithm produces. + pidProfile->D8[pidIndex] = (pid.d * AUTOTUNE_D_MULTIPLIER); + + pidProfile->P8[PIDYAW] = pidProfile->P8[PIDROLL] * YAW_GAIN_MULTIPLIER; + pidProfile->I8[PIDYAW] = pidProfile->I8[PIDROLL]; + pidProfile->D8[PIDYAW] = pidProfile->D8[PIDROLL]; + } if (phase == AUTOTUNE_PHASE_MAX) { phase = PHASE_IDLE; diff --git a/src/flight_autotune.h b/src/flight_autotune.h index 69cc01f7d2..1f2b53ccf7 100644 --- a/src/flight_autotune.h +++ b/src/flight_autotune.h @@ -2,7 +2,7 @@ void autotuneReset(); void autotuneBeginNextPhase(pidProfile_t *pidProfileToTune, uint8_t pidControllerInUse); -float autotune(angle_index_t angleIndex, rollAndPitchInclination_t *inclination, float errorAngle); +float autotune(angle_index_t angleIndex, const rollAndPitchInclination_t *inclination, float errorAngle); void autotuneEndPhase(); bool isAutotuneIdle(void); diff --git a/src/flight_common.c b/src/flight_common.c index a2e53abf9a..2d4e60579d 100644 --- a/src/flight_common.c +++ b/src/flight_common.c @@ -56,7 +56,7 @@ void resetErrorGyro(void) errorGyroIf[YAW] = 0; } -angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH }; +const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH }; bool shouldAutotune(void) { diff --git a/src/flight_common.h b/src/flight_common.h index 3d50aff4d0..083b86c1e6 100644 --- a/src/flight_common.h +++ b/src/flight_common.h @@ -1,7 +1,7 @@ #pragma once -enum { +typedef enum { PIDROLL, PIDPITCH, PIDYAW, @@ -13,7 +13,7 @@ enum { PIDMAG, PIDVEL, PID_ITEM_COUNT -}; +} pidIndex_e; typedef struct pidProfile_s { uint8_t P8[PID_ITEM_COUNT]; diff --git a/src/serial_common.c b/src/serial_common.c index 222043fc8a..6896303dce 100644 --- a/src/serial_common.c +++ b/src/serial_common.c @@ -78,12 +78,12 @@ typedef struct serialPortSearchResult_s { uint8_t startSerialPortFunctionIndex; // used by findNextSerialPort } serialPortSearchResult_t; -static serialPortFunctionList_t serialPortFunctionList = { +static const serialPortFunctionList_t serialPortFunctionList = { 4, serialPortFunctions }; -serialPortFunctionList_t *getSerialPortFunctionList(void) +const serialPortFunctionList_t *getSerialPortFunctionList(void) { return &serialPortFunctionList; } diff --git a/src/serial_common.h b/src/serial_common.h index c698871223..24a4e0afb7 100644 --- a/src/serial_common.h +++ b/src/serial_common.h @@ -113,7 +113,7 @@ bool isSerialConfigValid(serialConfig_t *serialConfig); bool doesConfigurationUsePort(serialConfig_t *serialConfig, serialPortIdentifier_e portIdentifier); bool isSerialPortFunctionShared(serialPortFunction_e functionToUse, uint16_t functionMask); -serialPortFunctionList_t *getSerialPortFunctionList(void); +const serialPortFunctionList_t *getSerialPortFunctionList(void); void evaluateOtherData(uint8_t sr); void handleSerial(void); diff --git a/src/serial_msp.c b/src/serial_msp.c index f19b289627..04dc0af44c 100755 --- a/src/serial_msp.c +++ b/src/serial_msp.c @@ -316,7 +316,7 @@ static void openAllMSPSerialPorts(serialConfig_t *serialConfig) } while (port); // XXX this function might help with adding support for MSP on more than one port, if not delete it. - serialPortFunctionList_t *serialPortFunctionList = getSerialPortFunctionList(); + const serialPortFunctionList_t *serialPortFunctionList = getSerialPortFunctionList(); UNUSED(serialPortFunctionList); } From 342aabeb5d2e154aff2fb614d57e01a92545b19a Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Wed, 28 May 2014 03:41:06 +0100 Subject: [PATCH 09/16] Latest binaries with autotune. --- obj/cleanflight_CHEBUZZF3.hex | 8739 +++++++++++++++---------------- obj/cleanflight_NAZE.hex | 9023 +++++++++++++++++---------------- obj/cleanflight_OLIMEXINO.hex | 8034 ++++++++++++++--------------- 3 files changed, 13048 insertions(+), 12748 deletions(-) diff --git a/obj/cleanflight_CHEBUZZF3.hex b/obj/cleanflight_CHEBUZZF3.hex index 97153b977c..2de864d9c0 100644 --- a/obj/cleanflight_CHEBUZZF3.hex +++ b/obj/cleanflight_CHEBUZZF3.hex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diff --git a/obj/cleanflight_NAZE.hex b/obj/cleanflight_NAZE.hex index 1eeab3b58b..c669975915 100644 --- a/obj/cleanflight_NAZE.hex +++ b/obj/cleanflight_NAZE.hex @@ -1,8 +1,8 @@ :020000040800F2 -:1000000000500020C9110008791200089956000814 +:1000000000500020C911000879120008A956000804 :100010007912000879120008791200080000000027 :10002000000000000000000000000000791200083D -:10003000791200080000000079120008356C0008F1 +:10003000791200080000000079120008D16C000855 :100040007912000879120008791200087912000864 :10005000791200087912000879120008C12D0008F1 :100060007912000879120008791200087912000844 @@ -17,10 +17,10 @@ :1000F0000000000000000000000000000000000000 :0C01000000000000000000005FF808F1A3 :1001100010B5054C237833B9044B13B10448AFF341 -:1001200000800123237010BDDC05002000000000CA -:10013000D443010808B5064B1BB106480649AFF386 +:1001200000800123237010BDE405002000000000C2 +:10013000EC49010808B5064B1BB106480649AFF368 :1001400000800648036813B1054B03B1984708BD0A -:1001500000000000D4430108E0050020DC05002079 +:1001500000000000EC490108E8050020E40500204B :100160000000000081F0004102E000BF83F0004386 :1001700030B54FEA41044FEA430594EA050F08BF42 :1001800090EA020F1FBF54EA000C55EA020C7FEA06 @@ -287,12 +287,12 @@ :1011D0008A4200F01F80002100F004B81A4B5B58CF :1011E0004350043119481A4B42189A42FFF4F6AFA3 :1011F000184A00F003B8002342F8043B164B9A4209 -:10120000FFF4F9AF0CF0C4F80FF0D2FA04F03EFA94 +:10120000FFF4F9AF0CF0C6FB0FF0D4FD04F046FA82 :10121000FFF7FEBF114E124830601248016821F0FE :1012200070610160410201600F4C182020600F497D :101230000F4808600F48D0F800D040680047000011 -:10124000F04F0020EFBEADDEF843010800000020A3 -:10125000DC050020DC050020EC21002018100240F5 +:10124000F04F0020EFBEADDE104A01080000002084 +:10125000E4050020E405002094220020181002403C :101260000900000004000140140C0140000C014082 :101270004434434400F0FF1FFFF7FEBF2E4B2DE91F :10128000F3411B780546002B38D00024264627461C @@ -306,18 +306,18 @@ :101300005320322101F008FB9DF801209DF80030A8 :1013100003EB02232B809DF803209DF8023003EBA2 :1013200002236B809DF805209DF8043003EB022317 -:10133000AB8002B0BDE8F081F8050020F90500207F +:10133000AB8002B0BDE8F08100060020010600206D :1013400008B5134B53201B782D2108227BB101F0E7 :10135000D9FA31210A22532001F0D4FA2C210C228F :10136000532001F0CFFA53203821902209E001F0F8 :10137000C9FA31210A22532001F0C4FA53202C214A :101380000A2201F0BFFA034B40F209121A8008BD8D -:10139000F80500201200002037B5114B0C461A68E2 +:10139000000600201200002037B5114B0C461A68D9 :1013A000104B00219A4205468DF8071001D100200C :1013B00013E0532001220DF1070301F0ADFA0028DC :1013C000F5D09DF80730E52BF1D12A78064B0120A6 :1013D0001A70064B2360064B636003B030BD00BF3C -:1013E0008C010020001BB700F80500204113000805 +:1013E00094010020001BB7000006002041130008F4 :1013F0007D12000813B5062204466B460221182010 :1014000001F08AFA9DF800309DF801209B0803EB5B :10141000022323809DF802309DF803209B0803EBF4 @@ -332,17 +332,17 @@ :1014A000A821682001F038FA9DF800209DF801304D :1014B00043EA022323809DF802209DF8033043EA8B :1014C000022363809DF804209DF8053043EA02233F -:1014D000A38002B010BD000008B5642005F0DDFB5C +:1014D000A38002B010BD000008B5642005F02BFC0D :1014E00068202321F02201F00DFA10B9032005F045 -:1014F00071FC052005F0D1FB044B68201A782021EF -:1015000042F00F02BDE8084001F0FCB9FA050020E6 -:1015100037B5054619200C4605F0BFFB0DF1070352 +:1014F000BFFC052005F01FFC044B68201A78202152 +:1015000042F00F02BDE8084001F0FCB902060020DD +:1015100037B5054619200C4605F00DFC0DF1070303 :1015200068200F21012201F0F7F99DF80730D32B35 :1015300015D10C4B4E2C2B600B4B6B600B4BEB60A7 :101540000B4B06D05D2C08D0362C14BF0022402255 :1015500000E080221A70012002E0C022FAE7002099 :1015600003B030BDD914000899140008325C8F3DD7 -:10157000FA05002013B5062204466B4601211C2003 +:101570000206002013B5062204466B4601211C20FA :1015800001F0CAF99DF801309DF800209DF8021085 :1015900043EA022242F38D02042392FBF3F22280FB :1015A0009DF8032042EA012242F38D0292FBF3F2FE @@ -360,8 +360,8 @@ :101660009A4201D1002015E01C200D2101220DF12C :10167000070301F051F90028F4D09DF807302A2B18 :1016800001D01A2BEED1064A01202260054A626081 -:10169000054A137002B010BD8C010020001BB7007A -:1016A000CD15000875150008FB05002013B50222B2 +:10169000054A137002B010BD94010020001BB70072 +:1016A000CD150008751500080306002013B50222A9 :1016B000044601AB1B21682001F02EF99DF804209F :1016C0009DF8053043EA022303F54E534FF48C7224 :1016D000103393FBF2F32333238002B010BD13B514 @@ -369,12 +369,12 @@ :1016F00000209DF8013043EA022323809DF8022058 :101700009DF8033043EA022363809DF804209DF88E :10171000053043EA0223A38002B010BD08B51920AA -:1017200005F0BBFA68201521002201F0EBF810B992 -:10173000032005F04FFB0C4B16211A78682042F06D +:1017200005F009FB68201521002201F0EBF810B943 +:10173000032005F09DFB0C4B16211A78682042F01F :10174000180201F0DFF817210022682001F0DAF812 :101750003D210122682001F0D5F8BDE8084068204D :101760003E21012201F0CEB80000002038B5054628 -:1017700019200C4605F091FA68201521002201F08D +:1017700019200C4605F0DFFA68201521002201F03F :10178000C1F818B3124B622C2B60124B6B60124BDA :10179000AB60124BEB60124B0FD004D80A2C12D066 :1017A000142C0ED00BE0BC2C04D0B4F5807F06D1F5 @@ -383,7 +383,7 @@ :1017D0001D170008DF160008AD16000890C1793DFE :1017E00000000020064B1B7813B1012B03D070477B :1017F0004FF4006201E04FF48052024B1A807047B0 -:10180000FC0500201200002013B5062204466B469A +:10180000040600201200002013B5062204466B4691 :101810003B21682001F080F89DF800209DF8013000 :1018200043EA022323809DF802209DF8033043EA17 :10183000022363809DF804209DF8053043EA0223CB @@ -391,18 +391,18 @@ :10185000682001F061F89DF800209DF8013043EA0E :10186000022323809DF802209DF8033043EA0223DF :1018700063809DF804209DF8053043EA0223A3808D -:1018800002B010BD07B5232005F007FA68207521C6 +:1018800002B010BD07B5232005F055FA6820752178 :1018900001220DF1070301F03FF828B19DF8070080 :1018A000B0F168035842584103B05DF804FB0000F2 :1018B00007B54FF40053ADF8043002238DF807301C :1018C00004238DF806301C4B1C4A1B68934201D13F :1018D0001B4803E01B4A934203D11B4801A901F0B6 :1018E000A3F96B218022682001F00CF8052005F097 -:1018F000D4F919210022682001F004F86B21032299 +:1018F00022FA19210022682001F004F86B2103224A :10190000682000F0FFFF37210222682000F0FAFF74 :101910000E4B1A211A78682000F0F4FF1B211822C0 :10192000682000F0EFFF1C211022682000F0EAFF81 -:1019300003B05DF804FB00BF8C01002000127A00A8 +:1019300003B05DF804FB00BF9401002000127A00A0 :10194000000C0140001BB700001001400100002006 :10195000F0B585B00546FFF795FF074600283ED055 :10196000062102AB68200A4600F0D6FF9DF80B3036 @@ -410,37 +410,37 @@ :1019800086069DF80930174C03F001031E4306D06C :10199000012E01D1002317E0022E0CD113E00DF12E :1019A000070368200C21012200F0B6FF9DF80730E4 -:1019B00013F00F0303D1052005F00CFA05E0042B0A +:1019B00013F00F0303D1052005F05AFA05E0042BBC :1019C00001D1267001E001232370074B2B60074BE8 :1019D0006B602378002B14BF6E236F232B72384665 -:1019E00005B0F0BDFC050020E51700080918000847 +:1019E00005B0F0BD04060020E5170008091800083E :1019F00038B505460C46FFF745FF18B3124B142CBB :101A00002B60124B6B60124BEB60124B14D004D85E :101A1000052C15D00A2C11D00CE0BC2C08D0B4F544 :101A2000807F03D0622C05D102220AE0002208E068 :101A3000012206E0032204E0042202E0052200E085 :101A400006221A7038BD00BFB118000847180008F8 -:101A500090C1793D01000020044B03EB4000427827 -:101A6000034B33F8120080B2704700BF4E160020BF -:101A700048160020F0B5404E404C042340493370D6 -:101A800023780D683F495A1CD2B28D4291B07370D1 -:101A9000227004D105210233B170F27023700378F3 -:101AA00023B13371237873710133237036480CF0FE -:101AB0008BFC364B00250593354B33480693237832 -:101AC00005A9022B089334BF2B4680230A934FF4B9 -:101AD00080730B934FF480630C9320230D934FF48A -:101AE00000530E93079509950F950CF0E5FC2648D9 -:101AF00001210CF00CFD23782648012B94BF002215 -:101B000001228DF8042001228DF8052069464FF44A -:101B100060220095029203958DF810300BF000FEC4 -:101B200023786F1CEDB2AB421A4807D916F815108E -:101B3000FAB203230BF045FE3D46F1E701210BF01D -:101B40001CFE144801210BF00FFE12480BF01EFE84 -:101B500010480BF020FE0028FAD10E480BF01FFEB3 -:101B60000C480BF021FE0028FAD10A4801210BF0A5 -:101B70001FFE11B0F0BD00BF4E160020FD05002075 -:101B80008C010020001BB700080002404C240140DB -:101B90004816002000240140324B2DE9F0411C88FA +:101A500090C1793D01000020044B00EB4000184488 +:101A60004278034B33F8120080B27047DC16002036 +:101A7000D6160020F0B5414C092291B0064600214F +:101A800020460FF0BFF9042323703D4B01251A684F +:101A90003C4BA5709A4204D1052325716571E37012 +:101AA000022533782BB10123EA18E571A371237263 +:101AB000D5B235480CF08AFF344B00260593344BE1 +:101AC000012D06930CBF334680230A934FF4807395 +:101AD0000B934FF480630C9320230D932A484FF40B +:101AE000005305A90E930796089509960F960CF0DA +:101AF000E5FF254801210DF00CF8012D94BF0023CE +:101B000001238DF8043001274FF4602321486946F2 +:101B100000968DF80570029303968DF810500CF026 +:101B200001F93A46A3199B783BB1551CEDB219480F +:101B3000A15D03230CF047F92A460336092EF1D1A3 +:101B4000144801210CF01BF9124801210CF00EF988 +:101B500010480CF01DF90F480CF01FF90028FAD1BD +:101B60000C480CF01EF90B480CF020F90028FAD1B3 +:101B7000084801210CF01EF911B0F0BDDC16002060 +:101B800094010020001BB700080002404C240140D3 +:101B9000D616002000240140324B2DE9F0411C886C :101BA000314B0A265A89B3F91250A41A1A89ED0248 :101BB0005443B3F91420E413224495FBF2F2224477 :101BC000DA615643A2F57A6202FB02F4B3F90480AB @@ -453,23 +453,23 @@ :101C3000B3FBF2F35B001A12524340F6DE34624308 :101C40000B4C08365C43241404EB224202F6CF62AC :101C5000361103EB221300B1036001B10E60BDE841 -:101C6000F08100BF2E060020040600202806002078 +:101C6000F08100BF32060020080600202C0600206C :101C700043E3FFFF114B07B51B781BB9104B1A88C4 :101C800001321A8001ABF6210322772000F044FED6 :101C90009DF805209DF80430120242EA03429DF8A7 :101CA00006301A43074BB3F92030C3F10803DA407A -:101CB000054B1A6003B05DF804FB00BFFE05002071 -:101CC0000006002004060020280600200C4B07B563 +:101CB000054B1A6003B05DF804FB00BF0506002069 +:101CC00006060020080600202C0600200C4B07B555 :101CD0001B781BB90B4B1A8801321A8001ABF62115 :101CE0000222772000F018FE9DF805309DF80420B0 :101CF00043EA0222044B1A8003B05DF804FB00BFE4 -:101D0000FE050020000600202E060020064B0021C4 +:101D0000050600200606002032060020064B0021B2 :101D100093F82020054B9201343219707720F4217A -:101D200002F0FC0200F0EEBD04060020FE050020DB +:101D200002F0FC0200F0EEBD0806002005060020CF :101D3000034B00221A707720F4212E2200F0E2BD1E -:101D4000FE05002010B54FF480400BF06DFC01281B -:101D5000044605D14FF480400BF074FC014B1C701D -:101D600010BD00BFFE0500202DE9F0476B4B8CB085 +:101D40000506002010B54FF480400BF06FFF01280E +:101D5000044605D14FF480400BF076FF014B1C7018 +:101D600010BD00BF050600202DE9F0476B4B8CB07D :101D70001A686B4B05469A4200F0CA80DFF8C0A192 :101D80009AF80080B8F1000F40F0C480654F4FF41E :101D9000005902261023384602A94FF480448DF8DA @@ -477,9 +477,9 @@ :101DB000384602A98DF80A30ADF8084000F034FF2B :101DC0000E213046C7F8109000F067FF0126082367 :101DD00004A804948DF815308DF814808DF81660E1 -:101DE0000BF0E8FB28238DF80C3003A80F238DF8A7 -:101DF0000D308DF80E308DF80F600BF035FD14208E -:101E000004F04BFF32460DF107037720D02100F09C +:101DE0000BF0EAFE28238DF80C3003A80F238DF8A2 +:101DF0000D308DF80E308DF80F600CF037F8142090 +:101E000004F099FF32460DF107037720D02100F04E :101E100083FD9DF80730444C0322552BE375228443 :101E200018BFC7F8149073D1D12132460DF10703C2 :101E3000772000F071FD9DF80730772003F00F0246 @@ -496,10 +496,10 @@ :101EE0009DF82D3043EA0223A38241F270738AF8F1 :101EF00000602B8046F678136B800C4B6B600C4BAC :101F0000AB600C4BEB600C4B2B610C4B6B6101E03D -:101F1000002000E001200CB0BDE8F0878C0100201B -:101F2000001BB7000010014004060020311D00080E +:101F1000002000E001200CB0BDE8F0879401002013 +:101F2000001BB7000010014008060020311D00080A :101F3000CD1C00080D1D0008751C0008991B000829 -:101F40002C0600202DE9F04F504A514E1768738936 +:101F4000300600202DE9F04F504A514E1768738932 :101F500084463089A7EB032785B0039187FB0001F6 :101F6000B288CB111404C209F08842EA416287FBAF :101F7000000114EB020872884FF000054FEAC234EA @@ -519,19 +519,19 @@ :10205000010B114B1A68A2FB0A0102FB0B11420D86 :1020600042EAC1224B15B2EB080263EB0903D00B25 :1020700040EA4340BCF1000F01D0CCF800000398C7 -:1020800008B10099016005B0BDE8F08F340600206A -:102090003806002024FAFFFF3006002007B5002193 +:1020800008B10099016005B0BDE8F08F3806002066 +:102090003C06002024FAFFFF3406002007B500218B :1020A00001AB0322772000F037FC9DF805009DF876 :1020B0000430000240EA03409DF80630184303B0A4 :1020C0005DF804FB08B5FFF7E9FF014B186008BD98 -:1020D0003006002008B5FFF7E1FF014B186008BD8E -:1020E0003406002077204821012200F00BBC772025 +:1020D0003406002008B5FFF7E1FF014B186008BD8A +:1020E0003806002077204821012200F00BBC772021 :1020F0005821012200F006BC444BF7B51A68444B46 :1021000004469A420FD0434D02234FF400568DF8F7 :1021100007302846102301A9ADF804608DF8063079 -:1021200000F082FD6E610A2004F0B7FD7720A02147 +:1021200000F082FD6E610A2004F005FE7720A021F8 :1021300001220DF1030300F0EFFB002863D01E2104 -:102140000122772000F0DEFB4FF42F6004F09AFDAF +:102140000122772000F0DEFB4FF42F6004F0E8FD61 :102150000025A5F160010026022201AB7720C9B25B :102160008DF804608DF8056000F0D6FB9DF8042022 :102170009DF8053043EA0223274AAB520235102D61 @@ -543,132 +543,132 @@ :1021D000F7D101311029E5D1C3F303332F439D42D9 :1021E000D78101D000200EE042F21073238063807B :1021F0000A4B012063600A4BA3600A4BE3600A4B61 -:1022000023610A4B636103B0F0BD00BF8C01002065 -:10221000001BB7000010014038060020EF20000826 +:1022000023610A4B636103B0F0BD00BF940100205D +:10221000001BB700001001403C060020EF20000822 :10222000D5200008E5200008C5200008451F00084B :10223000F8B5134B04469B890D461646EEB115B111 -:102240002F78013500E0FF270D4802210BF062FADC -:102250000028F9D00A4839460BF057FA08480121FE -:102260000BF058FA0028F9D005480BF050FAC0B22C +:102240002F78013500E0FF270D4802210BF064FDD7 +:102250000028F9D00A4839460BF059FD08480121F9 +:102260000BF05AFD0028F9D005480BF052FDC0B222 :102270000CB120700134013EE0E70120F8BD00BF41 :10228000003800402DE9F0474FF4804088B001212C -:102290000BF092FF4FF4804001210BF0A5FF344D6D +:102290000CF094FA4FF4804001210CF0A7FA344D71 :1022A00018238DF802304FF42043ADF80030284653 :1022B000032369464FF004082E4F8DF8033000F0D9 :1022C000B3FC4FF4804328466946ADF800304FF424 :1022D00080564FF0100A8DF8028000F0A5FC694688 :1022E0002846ADF800608DF802A000F09DFC38464D -:1022F0000BF0AEF94FF48273ADF80E304FF400736B +:1022F0000BF0B0FC4FF48273ADF80E304FF4007366 :10230000ADF8163007230024ADF81C304FF001095A :102310000223384603A9ADF81230ADF80C40ADF8F1 :102320001040ADF81A40ADF81490ADF818A00BF0BD -:10233000C1F9384649460BF0DCF99F238DF804308B +:10233000C3FC384649460BF0DEFC9F238DF8043081 :102340008DF805408DF806408DF8074002A86E61B3 :102350000DEB08014246FFF76BFF2E619DF8090067 :10236000B0F1EF035842584108B0BDE8F08700BF14 :10237000000C0140003800402DE9F047974C2068E0 :10238000B0F814C01FFA8CFC5FFA8CF3DD0736D569 -:102390000388012123F400631B041B0C03800BF052 -:1023A000F1FF8F4B00221A708E4A1D4612788E4B19 +:102390000388012123F400631B041B0C03800CF051 +:1023A000F3FA8F4B00221A708E4A1D4612788E4B1C :1023B000C2B18E4A117819B98D490978FF2911D116 :1023C000012111708B4A1278022A05D122681188E6 -:1023D00089B241F4006111801978206801220BF064 -:1023E000EBFF21E11978206800220BF0E5FF804B1C +:1023D00089B241F4006111801978206801220CF063 +:1023E000EDFA21E11978206800220CF0E7FA804B21 :1023F0001B78FF2B00F01881FF232B7014E103F0F2 :10240000020202F0FF01002A3BD0BFF35F8F794B3D :102410001A78012A16D1734A12789AB1734A12783F -:1024200082B100210BF0AEFFBFF35F8F2068012166 -:10243000038B0BF09BFF704B01221A7020684FF446 +:1024200082B100210CF0B0FABFF35F8F2068012168 +:10243000038B0CF09DFA704B01221A7020684FF448 :102440008061EFE0028BBFF35F8F1A78022A09D117 -:10245000644A127832B1654A12781AB100210BF041 -:1024600091FFDBE01B78032B07D15E4B1B7823B178 +:10245000644A127832B1654A12781AB100210CF040 +:1024600093FADBE01B78032B07D15E4B1B7823B17B :102470005E4B1B78002B40F0D2804FF4806101222C :10248000D0E003F0040505F0FF08002D67D0554BA0 :10249000DFF864811A78012688F80060534B002A1F :1024A00047D01A78002A44D0524B4D4D1B78534FD9 -:1024B000022B23D90BF066FF2B7820689A194FFA6C -:1024C00083FAD7F800902A700BF073FF314609F8B1 -:1024D0000A0020680BF04AFF2B7820689A193F68A1 -:1024E0002A7088F800605DB20BF063FF4FF48061E2 -:1024F0007855324620680BF051FF2BE031460BF047 -:1025000035FF2B7820685A1C3E684FFA83F82A70F2 -:102510000BF04FFF2B7806F808005A1C20683E6825 -:102520002A705FB20BF045FF2B78F05501332B700A -:1025300010E01B78012113B9314B1B782BB10BF044 -:1025400015FF274B1A78013203E00BF003FF274BEE +:1024B000022B23D90CF068FA2B7820689A194FFA6E +:1024C00083FAD7F800902A700CF075FA314609F8B3 +:1024D0000A0020680CF04CFA2B7820689A193F68A3 +:1024E0002A7088F800605DB20CF065FA4FF48061E4 +:1024F0007855324620680CF053FA2BE031460CF048 +:1025000037FA2B7820685A1C3E684FFA83F82A70F5 +:102510000CF051FA2B7806F808005A1C20683E6827 +:102520002A705FB20CF047FA2B78F05501332B700C +:1025300010E01B78012113B9314B1B782BB10CF043 +:1025400017FA274B1A78013203E00CF005FA274BF3 :1025500001221A7022681388D805FCD464E003F0C5 :10256000400303F0FF071E4D224EFBB1234B1F68B3 -:102570002B785A1C4FFA83F92A700BF01AFF95F941 +:102570002B785A1C4FFA83F92A700CF01CFA95F943 :10258000003007F80900327803339A4205D12068F9 -:102590004FF4806142460BF001FF2B7831785AB23C +:102590004FF4806142460CF003FA2B7831785AB23E :1025A000914241D10E4A013313703DE01CF0800F7F :1025B0003AD02A7853B2591C26D012490132096800 -:1025C0002A70C95C0BF0F3FE327895F900309A421C -:1025D0002AD120684FF480613A4623E0600600204B -:1025E000640600205D060020650600204A060020E3 -:1025F0004C0600204D060020550600205006002005 -:102600004B06002058060020134B2F7019780BF052 -:10261000CEFE124B1B780BB933782BB920684FF4E0 -:10262000806100220BF0BAFE0D4B0E4A1B7892F926 +:1025C0002A70C95C0CF0F5F9327895F900309A421E +:1025D0002AD120684FF480613A4623E06406002047 +:1025E0006806002061060020690600204E060020D3 +:1025F00050060020510600205906002054060020F5 +:102600004F0600205C060020134B2F7019780CF049 +:10261000D0F9124B1B780BB933782BB920684FF4E3 +:10262000806100220CF0BCF90D4B0E4A1B7892F928 :10263000002001339A420DD10B4B00221A700B4B34 -:102640001B7823B120684FF440710BF0A7FE084BB4 -:1026500000221A70BDE8F0874C0600205D060020BD -:102660004D060020640600204A0600205506002082 -:102670005C060020FFF780BEFFF77EBE2DE9F0412B +:102640001B7823B120684FF440710CF0A9F9084BB6 +:1026500000221A70BDE8F0875006002061060020B5 +:1026600051060020680600204E0600205906002072 +:1026700060060020FFF780BEFFF77EBE2DE9F04127 :10268000484C86B04FF440651C2380460227204604 :1026900001A9454EADF804508DF806308DF807704D :1026A00000F0C2FA1423204602A9ADF80850C6F87B :1026B00000808DF80B708DF80A3000F0B5FA2561B6 -:1026C0000825384CA3685B0503D40A2004F0DAFA25 -:1026D000F7E74FF480670A20676104F0D3FA013D01 -:1026E00027610A2004F0CEFA15F0FF05E9D14FF476 -:1026F0000068C4F814800A2004F0C4FA67610A2054 -:1027000004F0C0FA27610A2004F0BCFA4FF44063D9 +:1026C0000825384CA3685B0503D40A2004F028FBD6 +:1026D000F7E74FF480670A20676104F021FB013DB2 +:1026E00027610A2004F01CFB15F0FF05E9D14FF427 +:1026F0000068C4F814800A2004F012FB67610A2005 +:1027000004F00EFB27610A2004F00AFB4FF440633B :10271000C4F81080ADF80830022302A98DF80B3000 -:1027200020461C238DF80A3000F07EFA30680BF04A -:102730006FFD02A80BF0F4FD2A4630684FF440719B -:102740000BF02CFE4BF6FF73ADF80E304FF48043C8 +:1027200020461C238DF80A3000F07EFA30680CF049 +:1027300071F802A80CF0F6F82A4630684FF44071A0 +:102740000CF02EF94BF6FF73ADF80E304FF48043CA :10275000ADF81430154B306801210293ADF80C50E0 -:102760000BF0ECFD02A930680BF06CFD4FF4A0609B -:102770000BF070F822238DF80030684601238DF8A5 -:1027800003308DF801508DF802500BF06DF82123C5 -:1027900068468DF800308DF801500BF065F806B0F2 -:1027A000BDE8F081000C014060060020801A0600A0 +:102760000CF0EEF802A930680CF06EF84FF4A0609F +:102770000BF072FB22238DF80030684601238DF8A0 +:1027800003308DF801508DF802500BF06FFB2123C0 +:1027900068468DF800308DF801500BF067FB06B0ED +:1027A000BDE8F081000C014064060020801A06009C :1027B00037B5224C2068838A9BB20193019B13F4A6 :1027C000706F02D01E4B01221A70019B13F4E06F50 -:1027D00028D04FF480610022038B0BF0DFFD019BBA +:1027D00028D04FF480610022038B0CF0E1F8019BBC :1027E00098051FD42068038899051BD4058805F433 -:1027F0008075ADB265B10388DA05FCD401210BF018 -:10280000B5FD206803889B05FCD4FFF737FF09E07E -:1028100001210BF0ABFD094B4FF4407118682A46BB -:102820000BF0BCFD2268938A23F470631B041B0C1D -:102830009382044B00221A7003B030BD6006002062 -:10284000540600205C060020FFF7B2BFFFF7B0BFC0 +:1027F0008075ADB265B10388DA05FCD401210CF017 +:10280000B7F8206803889B05FCD4FFF737FF09E081 +:1028100001210CF0ADF8094B4FF4407118682A46BD +:102820000CF0BEF82268938A23F470631B041B0C1F +:102830009382044B00221A7003B030BD640600205E +:102840005806002060060020FFF7B2BFFFF7B0BFB8 :1028500070B54000204CC0B220702048204C017060 :10286000204901200870002121701F4C23601F4C5B :1028700023601F4B1F4C1A701F4A204B107020689A :1028800019708188164611F4007F1D460ED1038809 -:10289000DA0505D403889B05FCD401210BF05AFD11 -:1028A00020684FF4407101220BF078FD47F230535D +:10289000DA0505D403889B05FCD401210CF05CF813 +:1028A00020684FF4407101220CF07AF847F230535F :1028B000327812B1013BFBD100E04BB9104B2068DC :1028C0001A88013292B21A80FFF7D8FE002070BD3C -:1028D000287880F0010070BD650600204C060020BD -:1028E0005D0600204B060020580600205006002000 -:1028F0004D060020600600205C06002054060020E3 -:102900004806002007B502AB03F8012D0122FFF7AE +:1028D000287880F0010070BD6906002050060020B5 +:1028E000610600204F0600205C06002054060020F0 +:1028F00051060020640600206006002058060020D3 +:102900004C06002007B502AB03F8012D0122FFF7AA :102910009FFF03B05DF804FB70B54000204CC0B2CF :1029200020702048204C01702048002101700120B7 :1029300020701F4C23601F4C23601F4B1F4C1A70CC :102940001F4A204B1070206819708188164611F4B8 :10295000007F1D460ED10388DA0505D403889B0548 -:10296000FCD401210BF0F6FC20684FF440710122E9 -:102970000BF014FD47F23053327812B1013BFBD11A +:10296000FCD401210BF0F8FF20684FF440710122E4 +:102970000CF016F847F23053327812B1013BFBD11C :1029800000E04BB9104B20681A88013292B21A80CD :10299000FFF774FE002070BD287880F0010070BD44 -:1029A000650600204C0600205D0600204B06002036 -:1029B00050060020580600204D060020600600202A -:1029C0005C0600205406002048060020014B1888B1 -:1029D00080B270474806002007B5002202AB03F81A +:1029A0006906002050060020610600204F06002026 +:1029B000540600205C06002051060020640600201A +:1029C00060060020580600204C060020014B1888A5 +:1029D00080B270474C06002007B5002202AB03F816 :1029E000012D1E200A210122FFF796FF28B19DF834 :1029F0000700B0F148035842584103B05DF804FBAA :102A000037B50622044603216B461E20FFF784FFDC @@ -682,16 +682,16 @@ :102A80000DD14FF48053ADF8043002238DF8073098 :102A900004238DF806305E480DEB030108E05D4A23 :102AA000934207D104A94FF480435B4821F80C3DC1 -:102AB00000F0BAF8322004F0F0F8002111221E20B4 +:102AB00000F0BAF8322004F03EF9002111221E2065 :102AC000FFF720FF012160221E20FFF71BFF64207B -:102AD00004F0E3F802A8FFF793FF00240A25274635 +:102AD00004F031F902A8FFF793FF00240A252746E6 :102AE0002646022101221E20FFF70CFF322004F0AF -:102AF000D4F802A8FFF784FFBDF90820BDF90A1039 +:102AF00022F902A8FFF784FFBDF90820BDF90A10EA :102B0000BDF90C3014449142B8BF0A461E449A42A3 :102B1000B8BF134613F5805F0F4409DD3C4B013D00 :102B2000DA6882F01002DA60DBD14FF0010801E0D0 :102B30004FF000081E2000211222FFF7E3FE0A25B5 -:102B4000022101221E20FFF7DDFE322004F0A5F84D +:102B4000022101221E20FFF7DDFE322004F0F3F8FF :102B500002A8FFF755FFBDF90820BDF90A10BDF91D :102B60000C30A41A9142B8BF0A46F61A9A42B8BF6E :102B7000134613F5805FC1EB070707DD244B013DCA @@ -702,8 +702,8 @@ :102BC00001461848FEF732F920F00040A8600021C5 :102BD00070221E20FFF796FE012120221E20FFF703 :102BE00091FE1E2002210022FFF78CFE642004F0DB -:102BF00054F8B8F1000F04D14FF07E532B606B6096 -:102C0000AB6004B0BDE8F0818C01002000127A00B6 +:102BF000A2F8B8F1000F04D14FF07E532B606B6048 +:102C0000AB6004B0BDE8F0819401002000127A00AE :102C1000000C0140001BB7000010014000406F464F :102C20000400002001C05E462DE9F0410F8800231A :102C300047FA03F2D2072BD58A7803F0070512F082 @@ -719,18 +719,18 @@ :102CD0008DF80430254B0222B3F900306D20C3F18A :102CE000B40393FBF2F38DF80530FF2101ABFFF73E :102CF000AFFD012334E0012B1DD10A2592FBF5F035 -:102D000079230021B4225A308DF8043001F098FF65 +:102D000079230021B4225A308DF8043001F0A2FF5B :102D10008DF8050096FBF5F00021B4225A3001F041 -:102D20008FFF01AB8DF80600FF216D200322FFF716 +:102D200099FF01AB8DF80600FF216D200322FFF70C :102D30008FFD022314E0022B13D164238DF804309D :102D400000284FF0010318BF18468DF805308DF8A4 :102D5000060001AB6D20FF210322FFF779FD002360 -:102D6000237004B070BD00BF660600208E200020D6 +:102D6000237004B070BD00BF6A060020322100202D :102D70000E4B0F4A9B68128810B51A420D4C03D0B7 -:102D800003F060FF20600BE003F05CFF23689842D3 +:102D800003F0AEFF20600BE003F0AAFF2368984237 :102D900006D9094AC31A12683B2193FBF1F3136069 -:102DA000064BBDE8104018680AF04CBC000C01400E -:102DB0006A0600207C0600207806002070060020AD +:102DA000064BBDE8104018680AF04EBF000C014009 +:102DB0006E060020800600207C060020740600209D :102DC000FFF7D6BFFFF7D4BF2DE9FF412B4B2C4FA8 :102DD0002C4C2D4E2D4D40B1012811D102223A80AC :102DE000226018803070072209E04FF480721A8048 @@ -738,17 +738,17 @@ :102E00001B884FF01008ADF8043001A902232048B8 :102E10008DF807308DF80680FFF706FF3B881C48C9 :102E2000ADF8043004230DEB03018DF80630FFF7F5 -:102E3000FBFE31780120FFF730FF20680AF002FC2A +:102E3000FBFE31780120FFF730FF20680AF004FF25 :102E4000236802A80293012400238DF80C308DF82A -:102E50000E408DF80D800AF0ADFB2B780D4A59B26B -:102E600003F01F039C40490942F8214003F004FF8E -:102E7000094B3C38186004B0BDE8F08168060020BA -:102E80006A060020700600206D0600206C060020F7 -:102E9000000C014000E100E07406002038B5044653 -:102EA00003F0EAFE084B19683C3188420BD31860E6 +:102E50000E408DF80D800AF0AFFE2B780D4A59B266 +:102E600003F01F039C40490942F8214003F052FF40 +:102E7000094B3C38186004B0BDE8F0816C060020B6 +:102E80006E060020740600207106002070060020E7 +:102E9000000C014000E100E07806002038B504464F +:102EA00003F038FF084B19683C3188420BD3186097 :102EB000064D074B0B201C602B88064C236103F04A -:102EC000E1FE2B88636138BD74060020680600208F -:102ED00078060020000C01402DE9F843C3794278C0 +:102EC0002FFF2B88636138BD780600206C06002038 +:102ED0007C060020000C01402DE9F843C3794278BC :102EE000002B044614BF0223002302B101333B4AE6 :102EF000002552F82390A8462F462E4639F8053073 :102F00004FF6FF729342D8B266D0E27812B1821EB9 @@ -764,86 +764,86 @@ :102FA000FA7F5FFA88F1E389704402D900F0E2F811 :102FB00001E000F0F5F808F101080AE0052B08D15E :102FC000074BF9B203EB0010A289238A00F0FEF848 -:102FD000013702351C2D91D1BDE8F8839019010805 -:102FE0000C1A0108074BA1F57A7153F820304FF401 +:102FD000013702351C2D91D1BDE8F883941F0108FB +:102FE00010200108074BA1F57A7153F820304FF4F7 :102FF0007A701A689B884B4393FBF0F39BB2138063 -:10300000704700BF84060020024B53F820301B6835 -:1030100019807047840600202DE9F04F474D044683 +:10300000704700BF88060020024B53F820301B6831 +:1030100019807047880600202DE9F04F474D04467F :1030200028788E4691460C26421C87B02A7046436B :10303000724620684946019300F072FFA2686068FA :10304000ADF808204FF0020A182202A98DF80A20D4 :103050008DF80BA0FFF7E8FD02A8256894F80CB0E6 -:103060000AF0F7FD7022019B354FADF808200122D0 +:103060000BF0F9F87022019B354FADF808200122D2 :10307000ADF80A20ADF80E3000224FF4807307EB54 :103080000608ADF80C20ADF810A0ADF81430BBF177 :103090000C0F2BD8DFE80BF0072A2A2A102A2A2A3D -:1030A000192A2A2A2200284602A90AF0CBFC28461F -:1030B00008210AF003FE19E0284602A90AF006FDDD -:1030C000284608210AF002FE10E0284602A90AF06C -:1030D00041FD284608210AF003FE07E0284602A920 -:1030E0000AF07AFD284608210AF002FEA37B1BB1F4 -:1030F000206801210AF0CBFD206801210AF0BBFD08 +:1030A000192A2A2A2200284602A90AF0CDFF28461A +:1030B00008210BF005F919E0284602A90BF008F8E1 +:1030C000284608210BF004F910E0284602A90BF06D +:1030D00043F8284608210BF005F907E0284602A925 +:1030E0000BF07CF8284608210BF004F9A37B1BB1F8 +:1030F000206801210BF0CDF8206801210BF0BDF80C :10310000237B0C2B14D8DFE803F0071313130A13E7 :1031100013130D13131310002368343307E02368CF :10312000383304E023683C3301E023684033BB516B -:103130004046A8F8049007B0BDE8F08F8006002054 -:10314000D406002008B5044B53F820301BB10B28DF -:1031500001D89B68984708BD84060020044B53F8AB +:103130004046A8F8049007B0BDE8F08F8406002050 +:10314000D806002008B5044B53F820301BB10B28DB +:1031500001D89B68984708BD88060020044B53F8A7 :1031600020301BB107289CBF1B681980704700BF27 -:10317000B406002010B50C460649B1FBF2F292B23B +:10317000B806002010B50C460649B1FBF2F292B237 :103180000821FFF749FF044B43F82400034B8360F9 -:1031900010BD00BF00127A0084060020E52F000851 +:1031900010BD00BF00127A0088060020E52F00084D :1031A00010B50C460649B1FBF2F292B20121FFF7CD :1031B00033FF044B43F82400034B836010BD00BF72 -:1031C00040420F00840600200930000810B50C466C +:1031C00040420F00880600200930000810B50C4668 :1031D000054991FBF2F292B20121FFF71DFF034B6B -:1031E00043F8240010BD00BF40420F00B406002089 +:1031E00043F8240010BD00BF40420F00B806002085 :1031F00010B50B4B0A46D8681C78017B2CB95A8055 :1032000001221A700068022206E05C889A80121B74 :103210001A8100221A700068BDE8104000F090B8D2 -:10322000640700207FB5044601A80D4616460AF043 -:103230001AFD0123ADF808302046002301A9ADF89E -:103240000450ADF80660ADF80A30ADF80C300AF065 -:103250008BFD04B070BD0000F7B5144D144F06018E -:1032600074193846002110220DF0CAFAA368E27BD7 +:10322000680700207FB5044601A80D4616460BF03E +:103230001CF80123ADF808302046002301A9ADF8A1 +:103240000450ADF80660ADF80A30ADF80C300BF064 +:103250008DF804B070BD0000F7B5144D144F060191 +:1032600074193846002110220DF0CCFDA368E27BD2 :103270006068ADF8043001A902238DF807308DF89D :103280000620FC60FFF7D0FC7059217B0022FFF77D :10329000C9FF20464FF6FF71012200F063FE204671 -:1032A0000021044A00F01CFE03B0F0BD0C1A010816 -:1032B00064070020F1310008014B1889704700BFF6 -:1032C000640700200E4A0F4813881180C91A038032 +:1032A0000021044A00F01CFE03B0F0BD102001080C +:1032B00068070020F1310008014B1889704700BFF2 +:1032C000680700200E4A0F4813881180C91A03802E :1032D00089B240F68C2399420B4B1A7807D9032AFE :1032E00003D90A4A117801311170002205E00B2A36 :1032F0009CBF074820F8121001321A70704700BFB7 -:10330000760700207407002014080020150800200C -:103310007A070020034B1878034B1B78C01A18BF9C -:10332000012070471508002078070020024B1A780A -:10333000024B1A70704700BF150800207807002064 -:103340007FB5044601A80D4616460AF08CFC012301 +:103300007A070020780700201808002019080020FC +:103310007E070020034B1878034B1B78C01A18BF98 +:1033200001207047190800207C070020024B1A7802 +:10333000024B1A70704700BF190800207C0700205C +:103340007FB5044601A80D4616460AF08EFF0123FC :10335000ADF808300023ADF80A302046032301A958 -:10336000ADF80450ADF80660ADF80C300AF0FCFC86 +:10336000ADF80450ADF80660ADF80C300AF0FEFF81 :1033700004B070BD10B50F4B03EB00108278C3682A :1033800032B9012282708180197B186802220CE018 :103390008288C1804478891A074A89B222F81410B9 :1033A0000022018182701868197BBDE81040FFF788 -:1033B000C7BF00BF940700207A0700202DE9F34122 +:1033B000C7BF00BF980700207E0700202DE9F3411A :1033C0000D46164F16492A014FEA001808EB07046C :1033D0008B1801265D708E54DC60A368E27B606808 :1033E000ADF8043001A902238DF807308DF80620CE :1033F000FFF71AFC58F80700217B0022FFF7A0FF17 :10340000204632464FF6FF7100F0ACFD20462946BB -:10341000044A00F065FD02B0BDE8F0810C1A010815 -:103420009407002075330008F7B5134E0701134BBE +:10341000044A00F065FD02B0BDE8F081102001080B +:103420009807002075330008F7B5134E0701134BBA :10343000BC1900251D70DC60A368E27B6068ADF8F4 :10344000043001A902238DF807308DF80620FFF71C :10345000EBFBB859217B2A46FFF772FF20464FF657 :10346000FF71012200F07EFD20462946044A00F04B -:1034700037FD03B0F0BD00BF0C1A0108940700200F -:10348000C5320008014B33F8100070477A0700205E +:1034700037FD03B0F0BD00BF102001089807002001 +:10348000C5320008014B33F8100070477E0700205A :1034900041717047426A806A131A58425841704716 -:1034A0007FB5044601A80D4616460AF0DCFB012351 +:1034A0007FB5044601A80D4616460AF0DEFE01234C :1034B000ADF808302046002301A9ADF80450ADF85E -:1034C0000660ADF80A30ADF80C300AF04DFC04B0DF +:1034C0000660ADF80A30ADF80C300AF04FFF04B0DA :1034D00070BD437913F0010307D00369C169026A23 :1034E000013B881A1840C0B27047184670474379AC :1034F00010B513F0010304460DD0FFF7EAFF58B1F1 @@ -864,14 +864,14 @@ :1035E0001023A261E162256201A9E561A56265621D :1035F000A4F84252A4F844528DF80630C4F808905A :103600000223A7718DF80730FFF70EFB206BFFF741 -:10361000A3FF41462046FFF78FFF322003F03DFB1A +:10361000A3FF41462046FFF78FFF322003F08BFBCC :103620001A4BD4F834811B681D46B5FBF9F1B1F58E :10363000803F03D3012DF8D96D08F6E7144A4046C0 :10364000B3FBF2F289B2D2B200F08CFC40463146B4 :10365000104A00F045FC256B012F14BF0222002206 :103660002868297BFFF71CFF284631460A4A00F0EC -:1036700037FC204603B0BDE8F08300BF541600209D -:103680004C1A01086C1A0108DC190108900100208D +:1036700037FC204603B0BDE8F08300BFE816002009 +:103680005020010870200108E01F01089801002067 :1036900040420F00B13800083D37000803460A4693 :1036A00090F84602D96A9B79FFF768BF10B590F889 :1036B0003C220446C2B9836A416A994228D0806993 @@ -884,7 +884,7 @@ :103720003922934209D201219940B0F84042013335 :103730002143A0F84012DBB2F3E710BD2B4B10B5CC :103740004FF4127404FB00346379DB074DD594F811 -:1037500038321BB3236B002118680AF0D3FA94F8AF +:1037500038321BB3236B002118680AF0D5FD94F8AA :103760003C3223B1B4F842320133A4F84232A27998 :10377000236B012A1868197B0CBF02220022FFF775 :103780008FFE012384F83B32002384F8393284F819 @@ -893,7 +893,7 @@ :1037B000B0FF94F83B12236BA27949B9012184F838 :1037C0003B128A421868197B0CBF0222002208E0D3 :1037D000002184F83B12012A1868197B14BF0222C9 -:1037E0000022BDE81040FFF75BBE10BD541600205C +:1037E0000022BDE81040FFF75BBE10BDE8160020C8 :1037F000012280F8382290F83B220023012A80F829 :1038000039320BD1827980F83B32036B012A186878 :10381000197B14BF02220022FFF742BE7047427993 @@ -907,14 +907,14 @@ :10389000B0F8403243F00103A0F840322046FFF771 :1038A000BEFF2046BDE81040FFF7A2BF10BD0000DC :1038B000064B10B54FF4127404FB00342046FFF79A -:1038C000F5FE2046BDE81040FFF7CCBF541600209F +:1038C000F5FE2046BDE81040FFF7CCBFE81600200B :1038D000436B13B190F844007047826A436AD31A6D :1038E0005842584170471FB5836800930023ADF8D4 :1038F0000430437903F0040101F0FF0231B14FF4C9 :103900000052ADF806204FF4806201E0ADF80620C9 :10391000ADF808200022ADF80C2013F0010218BF0A :1039200004229B07ADF80A2005D5BDF80A3043F004 -:103930000803ADF80A30006D69460AF0C9FA05B00F +:103930000803ADF80A30006D69460AF0CBFD05B00A :103940005DF804FB8160FFF7CEBF4171FFF7CBBF8D :10395000026B03691AB15168013B026C02E0C16954 :10396000026A013B881A1840C0B27047016B0346D7 @@ -925,124 +925,124 @@ :1039B00004D11046314600F0C9F807E0474B984261 :1039C00040F085801046314600F018F90025056268 :1039D000C56185624562C0F82C804671876085713B -:1039E0000446FFF780FF01A80AF084FDE36CF207AC +:1039E0000446FFF780FF01A80BF086F8E36CF207AE :1039F00001934FF480530A934FF080030B95059584 :103A000007950693089527D5206BD0B1E3680395F9 -:103A1000049320230993636902930AF0D5FC206B79 -:103A200001A90AF049FD206B01210AF070FD206D0B -:103A3000402101220AF0C4FA206B0AF07DFD2064C7 -:103A40000AE0206D40F225510AF0C3FA206D40F2E1 -:103A5000255101220AF09CFA01A80AF04BFDA36C43 +:103A1000049320230993636902930AF0D7FF206B74 +:103A200001A90BF04BF8206B01210BF072F8206D0F +:103A3000402101220AF0C6FD206B0BF07FF82064C4 +:103A40000AE0206D40F225510AF0C5FD206D40F2DC +:103A5000255101220AF09EFD01A80BF04DF8A36C40 :103A6000002501934FF480530A938027B3070B95E9 :103A7000059507950697089523D5606BD8B12369FE -:103A800009950493102303930AF09EFC606B01A92F -:103A90000AF012FD606B012202210AF043FD606B07 -:103AA00029460AF047FD636B206D5D6039460122AF -:103AB0000AF086FA05E0206D40F2277101220AF033 -:103AC00067FA206D01210AF057FA204600E0002035 +:103A800009950493102303930AF0A0FF606B01A92A +:103A90000BF014F8606B012202210BF045F8606B0B +:103AA00029460BF049F8636B206D5D6039460122B1 +:103AB0000AF088FD05E0206D40F2277101220AF02E +:103AC00069FD206D01210AF059FD204600E000202B :103AD0000CB0BDE8F08100BF003801400044004058 :103AE00003469A6A9969406B1144C160596A9142D0 :103AF00003D98A1A4260996204E019698A1A4260FD -:103B000000229A62002283F8442001210AF0FFBCBF +:103B000000229A62002283F8442001210BF001B8C0 :103B100010B5426A8469A154416A02690131B1FB5E :103B2000F2F402FB14124262426B32B11368DB07FB :103B30000BD4BDE81040FFF7D3BF006D40F22771F2 -:103B40000122BDE810400AF023BA10BD254B264AD9 +:103B40000122BDE810400AF025BD10BD254B264AD4 :103B500013B51A60254A98605A61254A0C469A6145 :103B60004FF48072DA601A61224A4FF480401A657D :103B700004329A64DA6402F5484254321A6301212D -:103B8000143A5A630AF00CFB02238DF803304FF409 +:103B8000143A5A630AF00EFE02238DF803304FF404 :103B90000073ADF80030A2074FF018038DF8023023 :103BA00003D515486946FFF73FF84FF48063ADF839 :103BB000003048238DF80230E30703D50E486946EC :103BC000FFF732F80E238DF8043001A801238DF899 -:103BD00005308DF806308DF8073009F045FE0148B4 -:103BE00002B010BDD80A0020F41901081608002000 -:103BF000D60900200038014000080140224B234A2A +:103BD00005308DF806308DF807300AF047F90148B6 +:103BE00002B010BDDC0A0020F81F01081A080020EE +:103BF000DA0900200038014000080140224B234A26 :103C000013B51A608022DA6040221A61204A986057 :103C10005A61204A0C469A611F4A4FF400301A65D7 -:103C2000012104329A64DA640AF0C6FA02238DF89C +:103C2000012104329A64DA640AF0C8FD02238DF897 :103C300003300423ADF80030A2074FF018038DF8CD :103C4000023003D515486946FEF7EEFF0823ADF8AC :103C5000003048238DF80230E30703D50F4869464A :103C6000FEF7E2FF26238DF804300222012301A88B -:103C70008DF805308DF806208DF8073009F0F4FD39 -:103C8000014802B010BD00BF2C0B0020F419010840 -:103C90001609002096090020004400400008014059 -:103CA00010B50B4C4FF400500AF04AFC606B002139 -:103CB0000AF02DFC626AA36A9A4204D02046BDE84D +:103C70008DF805308DF806208DF807300AF0F6F83B +:103C8000014802B010BD00BF300B0020F81F010832 +:103C90001A0900209A090020004400400008014051 +:103CA00010B50B4C4FF400500AF04CFF606B002134 +:103CB0000AF02FFF626AA36A9A4204D02046BDE848 :103CC0001040FFF70DBF012384F8443010BD00BF42 -:103CD000D80A00200D4B186D0288120614D59A6A76 +:103CD000DC0A00200D4B186D0288120614D59A6A72 :103CE000596A8A420BD09969895C0132C9B28180D4 :103CF0001969B2FBF1F001FB10229A62704740F2A1 -:103D0000277100220AF044B9704700BFD80A00208A +:103D0000277100220AF046BC704700BFDC0A002081 :103D100038B51B4C236D1D88ADB2AA0612D5E26AD8 :103D20001AB1988880B290470CE09B88E26961697B :103D3000DBB28B54E269E3680132B2FBF3F103FBBF :103D40001123E3612B0619D5A26A616A0C4B8A42E2 :103D50000CD09869196D805C0132C0B288801969F5 :103D6000B2FBF1F001FB10229A6238BD186D40F2EF -:103D700027710022BDE838400AF00AB938BD00BFFB -:103D80002C0B002010B50023094CDAB254F8224065 +:103D700027710022BDE838400AF00CBC38BD00BFF6 +:103D8000300B002010B50023094CDAB254F8224061 :103D900001338442F8D10023064CD8B234F81040E5 :103DA00001338C42F8D102EB8000C0B210BD00BFDD -:103DB000EC1A0108FC1A010870B504460026324BC3 -:103DC0009D5DA5B9204602210AF073F8012857D15C -:103DD000204602210AF078F829462046FFF7D2FF54 -:103DE0002A4D05EB001520460AF056F843E0042D55 -:103DF00014D1204629460AF05CF8012840D120461B -:103E000029460AF061F829462046FFF7BBFF1F4DFF -:103E100005EB001520460AF042F82CE0082D14D1DD -:103E2000204629460AF045F8012829D1204629468E -:103E30000AF04AF829462046FFF7A4FF134D05EB88 -:103E4000001520460AF02EF815E00C2D18D120465A -:103E500010210AF02EF8012812D1204610210AF074 -:103E600033F829462046FFF78DFF084D05EB001576 -:103E700020460AF01AF8AB6801460BB1287B984738 -:103E80000236082E9BD170BDFC1A0108800B002061 +:103DB000F02001080021010870B504460026324BAE +:103DC0009D5DA5B9204602210AF075FB012857D157 +:103DD000204602210AF07AFB29462046FFF7D2FF4F +:103DE0002A4D05EB001520460AF058FB43E0042D50 +:103DF00014D1204629460AF05EFB012840D1204616 +:103E000029460AF063FB29462046FFF7BBFF1F4DFA +:103E100005EB001520460AF044FB2CE0082D14D1D8 +:103E2000204629460AF047FB012829D12046294689 +:103E30000AF04CFB29462046FFF7A4FF134D05EB83 +:103E4000001520460AF030FB15E00C2D18D1204655 +:103E500010210AF030FB012812D1204610210AF06F +:103E600035FB29462046FFF78DFF084D05EB001571 +:103E700020460AF01CFBAB6801460BB1287B984733 +:103E80000236082E9BD170BD00210108840B002052 :103E900070B50C4615461E46FFF774FF0F2805D86F :103EA000034B03EB001086600471057370BD00BF07 -:103EB000800B00200C2912D8DFE801F00711111146 +:103EB000840B00200C2912D8DFE801F00711111142 :103EC000091111110B1111110D00022104E004213F -:103ED00002E0082100E01021012209F0E6BE70474F +:103ED00002E0082100E0102101220AF0E8B9704751 :103EE00038B504460D461346217B00682A46FFF785 :103EF000CFFF2068217BBDE83840FFF7DBBF07B567 :103F000000238DF804008DF8053001A801238DF8F9 -:103F100006308DF8073009F0A7FC03B05DF804FB0C -:103F20007FB5044601A816460D4609F089FE0B4BE5 +:103F100006308DF8073009F0A9FF03B05DF804FB07 +:103F20007FB5044601A816460D460AF08BF90B4BE7 :103F3000013D5E430A4B20461B6801A9B3FBF6F620 :103F4000013E0023ADF80850ADF80460ADF80A302A -:103F5000ADF8063009F02CFD04B070BD40420F00F2 -:103F60009001002010B504460068FFF7D9FF2068D3 -:103F7000012109F080FE607BBDE81040FFF7BFBF64 +:103F5000ADF806300AF02EF804B070BD40420F00F4 +:103F60009801002010B504460068FFF7D9FF2068CB +:103F700001210AF082F9607BBDE81040FFF7BFBF66 :103F80000148FFF719BF00BF002C01404FF08040EF :103F9000FFF712BF0148FFF70FBF00BF000400404A :103FA0000148FFF709BF00BF000800400248002198 -:103FB0004FF480720CF024BC800B002010B5FCF78D +:103FB0004FF480720CF026BF840B002010B5FCF784 :103FC0002DFE0A49FCF77EFE0949FCF72FFF094B3D :103FD00004461B681878FCF721FE01462046FCF7D2 :103FE00071FEFDF75BF880B210BD00BF3333534064 -:103FF00000F07F45800C002010B50D4B00201C7890 +:103FF00000F07F45840C002010B50D4B00201C788C :10400000621C1A70FDF728FD0A4A04F00704002319 :1040100022F814001846D15A02330844102B80B2FB :10402000F9D1C008FFF7CAFF034B187010BD00BFDD -:10403000840C0020860C0020E41A0020074B084A5C +:10403000880C00208A0C0020781B0020074B084ABF :104040001B7812889A4207D3064A126890789842E1 -:104050008CBF00200120704700207047E41A002028 -:10406000E61A0020800C0020114B70B51860202546 +:104050008CBF00200120704700207047781B002093 +:104060007A1B0020840C0020114B70B518602025AD :1040700000241E460020FDF7EFFC04440A2002F055 -:104080000CFE013DF6D1C4F34F10FFF797FF3168E6 +:104080005AFE013DF6D1C4F34F10FFF797FF316898 :1040900001234C782246904203D30133062B22445D :1040A000F9D1044A13708A785343034A138070BDD0 -:1040B000800C002010000020E61A00202DE9F04FAF +:1040B000840C0020100000207A1B00202DE9F04F16 :1040C0000446008885B048B9B4F9023043B9B4F960 :1040D0000430D3F1010338BF002302E0002300E0E5 :1040E000034613F0010377D13D4A00B2137000F08C -:1040F0000FFE0646B4F9020000F00AFE0546B4F9C8 -:10410000040000F005FE044630460AF023FA074694 -:1041100030460AF093FA804628460AF01BFA064613 -:1041200028460AF08BFA054620460AF013FA824622 -:1041300020460AF083FA394681465046FCF7C2FD14 +:1040F00017FE0646B4F9020000F012FE0546B4F9B8 +:10410000040000F00DFE044630460AF025FD074687 +:1041100030460AF095FD804628460AF01DFD064609 +:1041200028460AF08DFD054620460AF015FD824618 +:1041300020460AF085FD394681465046FCF7C2FD0F :10414000394683464846FCF7BDFD5146019040463E :10415000FCF7B8FD494602904046FCF7B3FD3146F6 :1041600003905046FCF7AEFD1E4C4946206006F118 @@ -1053,7 +1053,7 @@ :1041B00089FD01460398FCF77BFC2946A061019824 :1041C000FCF780FD01460298FCF774FC3946E0617B :1041D0003046FCF777FD206205B0BDE8F08F00BFE8 -:1041E00011000020980C00202DE9F8434D4B0C469F +:1041E000110000209C0C00202DE9F8434D4B0C469B :1041F0000168013A196081889980072A30D8DFE880 :1042000002F004080F14191E22261A8822805A88E8 :1042100003E05A8822801A88524262809B881EE0FE @@ -1066,4218 +1066,4317 @@ :10428000FCF7CCFC294D064629684046FCF71AFD90 :10429000E96881463846FCF715FD01464846FCF7BB :1042A00009FCA96981463046FCF70CFD01464846E9 -:1042B000FCF700FC0AF084F9696820804046FCF7AE +:1042B000FCF700FC0AF086FC696820804046FCF7A9 :1042C00001FD296981463846FCF7FCFC0146484659 :1042D000FCF7F0FBE96981463046FCF7F3FC014648 -:1042E0004846FCF7E7FB0AF06BF9A9686080404696 +:1042E0004846FCF7E7FB0AF06DFCA9686080404691 :1042F000FCF7E8FC696980463846FCF7E3FC0146B8 :104300004046FCF7D7FB296A07463046FCF7DAFC43 -:1043100001463846FCF7CEFB0AF052F9A080BDE812 -:10432000F88300BFBC0C002011000020980C002076 -:1043300070B5144D06462B78134CABB102F09CFCC3 -:104340002368334498421CD30020287002F052FCAA -:1043500002F092FC0D4B20601A780AB1013A1A70F3 -:104360000B4B01221A7070BD02F086FC23683233B9 -:10437000984206D30120287002F03CFC02F07CFC3D -:10438000206070BDC20C0020D00C0020C40C0020A6 -:10439000C30C002073B5234D8DF807302B788DF8B2 +:1043100001463846FCF7CEFB0AF054FCA080BDE80D +:10432000F88300BFC00C0020110000209C0C00206E +:1043300070B5144D06462B78134CABB102F0EAFC75 +:104340002368334498421CD30020287002F0A0FC5C +:1043500002F0E0FC0D4B20601A780AB1013A1A70A5 +:104360000B4B01221A7070BD02F0D4FC236832336B +:10437000984206D30120287002F08AFC02F0CAFCA1 +:10438000206070BDC70C0020D40C0020C90C002098 +:10439000C80C002073B5234D8DF807302B788DF8AD :1043A000062002AA8DF804008DF805101A4412F8B0 :1043B000042C443AD2B20A2A2CD81B49022B31F8D9 :1043C000124003D814B12046FFF7B2FF2B78022B1E -:1043D0000BD9164B1E6802F04FFC001B864204D21C +:1043D0000BD9164B1E6802F09DFC001B864204D2CE :1043E000104A00231370124A1370124B1A78012AD4 :1043F0001A4600D09CB92B78022B02D80949013308 :104400000B700D4B00201070187002B0BDE87040AA -:1044100002F0F0BB022B4FF03204D4D9D6E702B041 -:1044200070BD00BFC70C0020041B0108D00C002089 -:10443000C40C0020C30C0020C20C0020014B1860EB -:10444000704700BFC80C00202DE9F0473D4A0546E3 -:10445000537B91463C4E03B101234FF400703370FF -:1044600000F07EF9394C30B3394FDFF8EC803B680F +:1044100002F03EBC022B4FF03204D4D9D6E702B0F2 +:1044200070BD00BFCB0C002008210108D40C002077 +:10443000C90C0020C80C0020C70C0020014B1860DC +:10444000704700BFD00C00202DE9F047414A0546D7 +:10445000537B9146404E03B101234FF400703370FB +:1044600000F088F93D4C30B33D4FDFF8FC803B68ED :1044700098F802001B68003018BF01205B6898475D :1044800040B1012323703B681B68DB68984708B183 :10449000022323703B681B689B68984720B198F8FB :1044A00002300BB9022323703B681B689B69984755 -:1044B00008B100232370202005F0C2FC68B199F8F0 -:1044C0000A20244B12B91F4AD27A22B1224AD27A48 +:1044B00008B100232370202005F0BEFF68B199F8F1 +:1044C0000A20284B12B9234AD27A22B1264AD27A3C :1044D0000AB9012200E000221A702378022B02D1CF -:1044E0004C204E211CE0012B07D14D2153204C22A2 -:1044F0000B46BDE8F047FFF74DBF164B1B78012B6D +:1044E0004C204E211CE0012B07D153204D214C22A2 +:1044F0000B46BDE8F047FFF74DBF1A4B1B78012B69 :1045000003D1532001464E2205E03378012B04D11C :104510005320014602464D23EBE725B153204D21A0 -:104520000A464423E5E70D4B1B7823B13220BDE852 -:10453000F047FFF7FDBE0A4B28461D70BDE8F04767 -:1045400002F058BB80210020C50C0020C60C0020C2 -:10455000C80C0020CC0C00206F210020C40C0020CF -:10456000C20C0020014B1870704700BFC40C002023 -:104570000E4B1A78452A16D15A88B2F5886F12D197 -:104580001A79BE2A0FD193F83D240020EF2A0CD1CE -:1045900013F8012B5040064A9342F9D1D0F10100A3 -:1045A00038BF0020704700207047704700F80108AE -:1045B00040FC0108C8230380142383701E23C370AA -:1045C000012303716423C3804FF49673038128236E -:1045D0004381704710B50446272006F0E7FD2070A0 -:1045E000102006F0E3FD6070002006F0DFFDA070F3 -:1045F000002006F0DBFD4FF4E1336360A360E3606D -:1046000023615223E070237510BD000030B51F4CAC -:104610001F4D85B0204605F049FC2946204605F08F -:104620005FFC05F1240002F017F905F1680006F0BF -:10463000E7F814F8500C02F0E5FE04F1A40004F0D1 -:104640008DFAA4F14C0005F04FF904F1980000F048 -:10465000AFFE05F1280001F06BFF05F14B0300935D -:1046600005F13803019304F1A203029304F1580009 -:10467000A91D2A4604F1A00303F00CFD04F1140067 -:1046800005B0BDE8304001F059BF00BF781F0020E1 -:10469000B81B002008B5054B054903EB00204FF47B -:1046A000807200F59E70FCF719FD08BDE81A002025 -:1046B000281F0020F8B5274B45221A704FF4886256 -:1046C0005A80BE221A71EF2283F83D24002283F81B -:1046D0003E2411461F46BB5C0132B2F5886F81EA69 -:1046E0000301F8D11B4B042683F83E1409F078FC33 -:1046F0000025013E16F0FF061ED0342009F084FC90 -:10470000154CC4F3090363B13A1902F17842A2F5DA -:10471000FC322046116809F0C1FC0428054607D088 -:10472000E7E7204609F09CFC04280546ECD0E0E7CA -:104730000A4B04349C42E4D109F05EFC042D02D102 -:10474000FFF716FF20B90A20BDE8F84002F042BB8F -:10475000F8BD00BFE81A002000F8010840FC01087D -:10476000034B9B6818420CBF00200120704700BF1C -:10477000E81A0020024B9A6810439860704700BF07 -:10478000E81A00202DE9F04FB74AB84D85B01068FF -:104790005168B74C02AB03C34FF48862002128462E -:1047A0000CF02EF800214FF4807220460CF028F80F -:1047B00045232B70022003236B71FFF7DBFF4FF4BF -:1047C0001673A5F8F030FA23A5F8F2302A23A5F8DD -:1047D000EE304FF4FA73A5F8F630202385F8F43064 -:1047E0006E2385F804312B2385F80531212385F8C4 -:1047F000063140F24C43A5F8143140F26C730026A8 -:104800004FF0010840F2DC52A5F8163140F27E4329 -:10481000A5F8122185F83C64A5F8FA60A5F8F860BF -:10482000A5F8FC6085F8E26085F8E36085F8E4604F -:10483000A5F8E660A5F8E860A5F8EA6085F8ED60FF -:1048400085F8EC8085F8076185F8386185F83A616C -:1048500085F8396185F8106185F8186185F8196166 -:1048600085F81A6185F81B6185F81C81A5F8D030A0 -:1048700040F23A73A5F8D2304FF47A73A5F8D430E9 -:1048800040F27E53A5F8D63040F2EA53A5F8D8306E -:1048900040F2B4534FF03209A5F8DA3005F59070C4 -:1048A0004FF4C873A5F8DE300192A5F8DC90A5F8A6 -:1048B000E09085F81E61FFF78DFE40F6AC530820AE -:1048C0001E21AB81E07417230E20A1732376E173C0 -:1048D00063760B215523A0726420A37121722D23CE -:1048E0001421E0777820DFF8B0A123746172637738 -:1048F0002175607350215F48E3755F4B2827A177CE -:104900004FF00A0B5A21E1726062AE732670277174 -:104910006771A67684F807906674E676A6742677A3 -:1049200084F815B0277384F82180C4F830A0E363BD -:1049300023644FF08243E3624FF07C53A3634F4BF9 -:1049400084F8501063644E4B84F85460A3644D4B5C -:1049500084F85560E364412384F8513084F856604C -:10496000019AA062C4F834A004F15C00A4F85820B5 -:1049700084F8529084F8536002F028FD042384F8F0 -:104980006030152384F864303F4BC4F868A0E366B8 -:104990003E4B3F48236705F58471A4F85A6084F8BC -:1049A000617084F8627084F8748005F05BFC4FF4E9 -:1049B0004873A4F8A430C82384F8E9304FF4966310 -:1049C000A4F8EA3040F2D933A4F8EC3040F64303BF -:1049D000A4F8EE3084F8A06084F8A16084F8A27096 -:1049E00084F8A38084F8A66084F8E8B023464FF4E6 -:1049F0007F72A4F8A8204FF4FA62A4F8AA2002A9B2 -:104A000040F2DC52A4F8AC208A5D013684F8AE2076 -:104A1000082E4FF0FF0284F8AF2004F10804E6D11D -:104A200001221C4883F8F02083F8F12083F8F2205B -:104A3000FFF7C0FD0023EA1810330021C02B1161DD -:104A4000F9D10024281900F59E7009494FF48072AD -:104A500004F58074FCF742FBB4F5407FF2D105B059 -:104A6000BDE8F04FFFF726BE3C190108E81A002008 -:104A7000281F0020000020408FC2753DCDCC4C3D4A -:104A80000000A04000004040F6287C3F3D0A773FF0 -:104A90001A1B01081C2000209A99193F08B5FFF73E -:104AA00067FD18B9BDE80840FFF76CBE08BD0000FF -:104AB000024B9A6822EA000098607047E81A0020CA -:104AC00010B5354C48F20103A268134033B9334B9B -:104AD00013401BB94FF40040FFF74CFEA36803F4EA -:104AE0002033B3F5203F03D14FF40030FFF7E0FF50 -:104AF000A368DA0311D51B0702D50820FFF7D8FFFA -:104B0000A368180403D54FF40040FFF7D1FFA36852 -:104B1000D90702D50120FFF7CBFFA3681A070BD5F1 -:104B2000180403D54FF40040FFF7C2FFA368D9076C -:104B300002D50120FFF7BCFFA26848F20103134031 -:104B400048F20102934203D14FF40040FFF7B0FF57 -:104B5000A3685A0505D51B0403D44FF48060FFF702 -:104B6000A7FFA26848F24003134048F24002934274 -:104B700002D14020FFF79CFF094805F0F5F90948EC -:104B800006F092FC074806F00DFC20B90548BDE888 -:104B90001040FFF71FBD10BDE81A002008000100FB -:104BA000F01B0020081C002007B5FFF7E1FC10B93E -:104BB0000A2002F00FF9104B104918464FF4886292 -:104BC000FCF78CFA90F83C24022A84BF002280F87B -:104BD0003C2490F83C2400EB022101F59E714FF437 -:104BE00080720748FCF77AFAFFF76AFF03B05DF8B6 -:104BF00004EBFFF70BBD00BFE81A002000F8010826 -:104C0000281F002008B5FFF7CFFFBDE808400F20A0 -:104C10001421012208F096BB08B5054B93F83C041B -:104C2000FFF738FDFFF746FDBDE80840FFF7EABF94 -:104C3000E81A0020014B9868704700BFE81A00206E -:104C4000884203DB9042A8BF104670470846704771 -:104C500070B504460E461546FCF7D2F930B9204629 -:104C60002946FCF7EBF918B1284670BD304670BDF7 -:104C7000204670BD0023036170472DE9F0410669AD -:104C800004460136012E0D46066105D10023616000 -:104C900021608360BDE8F081D0F80080084641467D -:104CA000FBF706FF07463046FBF7B8FF01463846DC -:104CB000FCF7BCF801464046FBF7FCFE0646606088 -:104CC00031462846FBF7F4FE01463846FBF7FAFF6B -:104CD000A168FBF7EFFE2660E060A060BDE8F08110 -:104CE00010B504460069012807DD0138FBF796FF7F -:104CF0000146E068FCF79AF810BD002010BD08B529 -:104D0000FFF7EEFFBDE8084009F0B0BE000000006C -:104D100008B5FBF779FB04A3D3E90023FBF7DAFB23 -:104D2000FBF772FE08BD00BF399D52A246DF913FDE -:104D30002DE9F041069C002B06460F460CBF4FF0B4 -:104D400020084FF03008234613F8011B09B9154617 -:104D500003E0002AFBDD013AF6E7002D04DD3046D2 -:104D60004146B847013DF8E714F8011B11B1304640 -:104D7000B847F9E7BDE8F081014B186801F0FCBEC7 -:104D8000DC0C00202DE9F04788B006460F46039260 -:104D90001C46039A531C03931178002900F08D8060 -:104DA000252901D0304686E00023911C049303910D -:104DB0005578302D05D1D31C039395784FF0010819 -:104DC00000E09846A5F13003DBB2092B06D828464F -:104DD00003A90A2204AB00F034F905466C2D05D175 -:104DE000039B5A1C03921D78012200E00022632DD0 -:104DF0004FD006D8252D5CD0582D2AD0002D5CD060 -:104E0000C7E7732D4AD002D8642D14D0C1E7752DA1 -:104E100002D0782D1DD0BCE704F1040905AD20684F -:104E20000A2122B100222B4600F090F80EE02B461A -:104E300000F0BFF80AE005AD04F104092068294636 -:104E400012B100F0ABF801E000F0DBF84C46009541 -:104E500018E004F1040A0DF11409206810213AB198 -:104E6000B5F15804624262414B4600F06FF806E02B -:104E7000B5F158035A425A414B4600F09AF854464D -:104E8000CDF8009030463946049A4346FFF750FF6C -:104E90007FE730462178251DB84708E02368304673 -:104EA00000933946049A0023251DFFF741FF2C4645 -:104EB0006FE730462946B8476BE708B0BDE8F08792 -:104EC0000FB407B50A4904AB08680A4953F8042B24 -:104ED00009680193FFF756FF074B186801F06BFE56 -:104EE0000028F9D003B05DF804EB04B0704700BFB0 -:104EF000D80C0020D40C0020DC0C0020034A044B0A -:104F00001A60044B00221A60704700BF794D0008F8 -:104F1000D40C0020D80C0020014B1860704700BF53 -:104F2000DC0C002070B50646B6FBF2F408461546C8 -:104F300014B12046FFF7F6FF05FB1464024B1B5D1E -:104F400000F8013B70BD00BF231B0108F0B5012430 -:104F5000B0FBF4F58D4201D34C43F9E70026DCB1F8 -:104F6000B0FBF4F504FB1500B4FBF1F41EB9002D01 -:104F700001DC002CF3D1092D03F101075FFA85FC58 -:104F800004DD002A0CBF5725372500E03025654495 -:104F90001D7001363B46E2E71C70F0BD00280B4651 -:104FA00003DA2D2240420A704B1C0A210022FFF72F -:104FB000CDBFF0B50124B0FBF4F58D4201D34C43D5 -:104FC000F9E70026DCB1B0FBF4F504FB1500B4FBF7 -:104FD000F1F41EB9002D01DC002CF3D1092D03F1F1 -:104FE00001075FFA85FC04DD002A0CBF5725372531 -:104FF00000E0302565441D7001363B46E2E71C7039 -:10500000F0BD00280B4603DA2D2240420A704B1CEB -:105010000A210022FFF7CDBFA0F13003DAB2092A3E -:1050200001D818467047A0F16103052B01D8573805 -:105030007047A0F14103052B94BF37384FF0FF3084 -:1050400070472DE9F8430D6804460F46904699468F -:1050500000262046FFF7E0FF002806DB404504DC81 -:1050600008FB060615F8014BF3E73D602046C9F83A -:105070000060BDE8F883931E232B28BF0A22031E7D -:1050800010B50C4603DA2D2001F8010B5842FFF74A -:1050900049FF00230370204610BD000030B587B0E3 -:1050A00005460C4603A800210C220BF0A9FB28465C -:1050B0000021FBF7C3FF20B128462949FBF7FAFC82 -:1050C00003E028462649FBF7F3FC2649FBF7FAFDE7 -:1050D000FBF7BEFF054685EAE570A0EBE570694683 -:1050E0000A22FFF7C8FF002DACBF20232D236846FE -:1050F0008DF80C300BF07AFF012807D130238DF8A2 -:105100000D308DF80E308DF80F300CE0022805D1EF -:1051100030238DF80D308DF80E3004E0032804BFE5 -:1051200030238DF80D30694603A80BF061FE03A80B -:105130000BF05CFF0338C5B22A4603A920460BF0EA -:10514000ADFF00236355204607490BF051FE03A92C -:10515000204629440BF04CFE204607B030BD00BF6E -:105160006F12033A00007A44A02501082DE9F041AE -:1051700002780346202A00F10100F9D0092AF7D06D -:105180002D2A02D10346414D04E02B2A08BF0346D5 -:105190004FF07E551E460024334616F8012BA2F12F -:1051A0003007F9B209290DD839492046FBF78AFDA5 -:1051B00004463846FBF732FD01462046FBF77AFCF1 -:1051C0000446E9E72E2A17D1314F334616F8010B72 -:1051D0003038C2B2092A0FD8FBF720FD3946FBF759 -:1051E00025FE01462046FBF765FC29490446384662 -:1051F000FBF768FD0746E8E71A7802F0DF02452A68 -:1052000038D15A782D2A02D10233012604E02B2A04 -:1052100014BF013302330026013B002713F8012F8E -:10522000303AD1B2092903D80A2101FB0727F5E753 -:10523000B7F59A7F28BF4FF49A77B8464FF07E5162 -:10524000B8F1070F07D908461249FBF73BFDA8F153 -:1052500008080146F4E707F0070737B108460C498C -:10526000FBF730FD013F0146F7E72EB12046FBF783 -:10527000DDFD04E04FF07E512046FBF723FD0146A3 -:105280002846FBF71FFDBDE8F08100BF000080BF8E -:105290000000204120BCBE4C014B00229A80704788 -:1052A000E40C0020034BB3F90400D0F1010038BF37 -:1052B00000207047E40C0020014B187A704700BFB3 -:1052C000E40C0020014B01221A727047E40C00200C -:1052D000064BB3F90400064B1B681B7803EB8303F2 -:1052E0009842D4BF00200120704700BFE40C00208A -:1052F000F00C002010B50446FFF7EAFF002814BFA9 -:105300002046002000F0010010BD0000074B1A6885 -:10531000074B1178B3F9040053780B4403EB830374 -:105320009842D4BF00200120704700BFF00C00203D -:10533000E40C0020024B9A8801329A80704700BF2B -:10534000E40C002070B5FFF7C3FF30B3134C237A91 -:105350000BB9A38070BD124EB578281C18BF012070 -:10536000FFF7C8FF88B1012373700E4B1A680E4B0C -:10537000518919805189598052899A800B4A126843 -:105380005288DA80E3880133E380FFF7BFFF00B97A -:105390001DB9BDE8704000F08BBB70BDE40C00206F -:1053A0006F210020F40C0020C8210020F00C002008 -:1053B000024B00221860024B9A807047F00C0020CC -:1053C000E40C0020044B18600448054B03600023E4 -:1053D000C3800372704700BFF40C0020E40C00206F -:1053E000481B0108044B9A8811B21429CCBF143A07 -:1053F00000229A80704700BFE40C0020032810B5FB -:105400000D4B0DD80D4A126894888C4208D2D28870 -:105410008A4205D9012202FA00F01A781043187066 -:105420001B780F2B06D1044B00221A70BDE81040E8 -:10543000FFF7D8BF10BD00BFE00C0020F00C00202B -:10544000F0B5854C87B0FFF759FDFFF727FBFFF755 -:10545000ABFBA07B003018BF012001F029FC94F8C1 -:10546000073133B103F0F702012A02D18DF8003081 -:1054700004E000238DF8003084F807316846FCF71B -:10548000F9FA0220FFF76CF910B17448FEF7ECFD51 -:105490007348744DFEF712FE0E2004F0DBFC7248D8 -:1054A000B4F8EE1094F8ED20B5F95A3001F0A4FAF2 -:1054B0002F4610B9032001F08DFC6C4B10225A616D -:1054C00008221A610A26694D1920EB68013E83F013 -:1054D0001003EB60EB6883F00803EB6001F0DDFB89 -:1054E000012001F087FB192001F0D7FB002001F01B -:1054F00081FB16F0FF06E6D108232B6110232B61F8 -:1055000002F012F860795A4902F028FEFEF74EFDCB -:10551000584806F05BF863790E2B01D0082B03D1B5 -:1055200001238DF80B3001E08DF80B60012151480B -:1055300005F07EFF8DF807004020FFF711F98DF888 -:1055400008004FF40040FFF70BF98DF804004FF40A -:105550000030FFF705F98DF806000120FFF700F98C -:105560008DF8050003F02AFA97F8F2308DF809005B -:10557000C3F380038DF80A30B4F8DE304FF4804076 -:10558000ADF80E30B4F8E030ADF810304FF47A7367 -:10559000ADF81230FFF7E4F820B12F4BB3F8DA3052 -:1055A000ADF81230BDF80E30B3F5FA7F84BF00239A -:1055B000ADF81230B4F81231ADF8143094F8073168 -:1055C000012B04D0092B01D1072300E0002301A8FF -:1055D0008DF80C30FDF780FC2748FFF7F3FE274DD0 -:1055E0002860FEF72BFF2448296804F0F7FC4FF4ED -:1055F0008070FFF7B5F838B1214A1E4894F81E11A3 -:10560000A2F1F00304F0C0F94FF48060FFF7A8F8AE -:1056100008B101F09DFA4FF40060FFF7A1F808B15E -:1056200005F076F901F00EFB164B18606379052B37 -:1056300003D14FF4C87000F063FE4FF47A7001F0AC -:1056400011F9C82000F08AFF0F4B01225A73002283 -:105650005A7007B0F0BD00BFE81A0020EC1B002014 -:10566000CE1B0020281F0020CA1B0020000C014078 -:10567000F81A0020081C0020F01B00202820002021 -:105680001C200020240D00206F21002008B5FFF70A -:10569000D7FE00F033FAFCE708B5034BB3F9D400AA -:1056A00002F078FEFEE700BFE81A002008B50220ED -:1056B00004F0C6FB18B900F029FE28B90AE000F092 -:1056C00043FF0028F7D108BD01F0D2F880F00100B7 -:1056D000C0B205E0022004F0B3FB0028F4D00120A2 -:1056E00000F0010008BD0000054B1A683AB900F54A -:1056F000F42000F590701860024B08225A61704740 -:10570000180D0020000C0140034B00221A60034BCF -:1057100008221A61704700BF180D0020000C0140DC -:10572000084A136863B1C01A002809DB064903F56B -:10573000F423C86803F5907380F00800C860136014 -:10574000704700BF180D0020000C0140A84B2DE948 -:10575000F04FB3F90600A74B85B0B3F8582090423C -:105760000FDBB0F5FA6F93F8564007DA811A4C4315 -:10577000A2F5FA6294FBF2F4643403E0C4F1640429 -:1057800000E064249C4A93F85410B2F812C192F9D4 -:10579000EC2093F8A05093F8A160524293F8553052 -:1057A00092B201910021029203930A46904B40F27B -:1057B000E637CB5E0093CCEB030303F2F31EBE454A -:1057C00003D8002BB8BF5B4201E04FF4FA73022A02 -:1057D000DFF830822CD025B1AB42CCBFC5EB030340 -:1057E00000236427DFF840A293FBF7FE6FF0630B02 -:1057F0003AF81E900BFB0E3B0EF1010E3AF91EA07B -:105800000FFA89FECEEB0A0E0EFB0BFE9EFBF7FE97 -:10581000CE4428F801E0DDF8048003FB08FE774B56 -:105820009EFBF3F33B449BB2634393FBF7F714E017 -:1058300026B1B342CCBFC6EB03030023DDF808E07A -:1058400003FB0EF7A8F80470039F002BB8BF5B4260 -:105850007B436A4F93FBF7F76437664BDFF8CC81E5 -:1058600002EB030E9EF80490642307FB09F999FBF1 -:10587000F3F902F808909EF80E909EF818E007FBE6 -:1058800009F907FB0EF7DFF8A88199FBF3F902F895 -:105890000890DDF8008097FBF3F3594FE045D355AE -:1058A000584F02DA7B5A5B427B520132032A01F1E4 -:1058B00002017FF47BAF504C4FF4FA62B4F814113C -:1058C000FFF7BEF9B4F814314FF47A74C01A4443A8 -:1058D000C3F5FA63B4FBF3F464214B4894FBF1F392 -:1058E0006FF0630630F8132006FB0344013330F9F0 -:1058F000130013B2C31A5C4394FBF1F1434C0A4406 -:10590000637A404DFA80002B38D0414B1888414BC8 -:105910001B88C01A00B2FFF7FBF9064608F01AFE12 -:105920000746304608F08AFE0646B5F90200FBF746 -:1059300075F98046B5F90000FBF770F939468146E4 -:10594000FBF7C0F9314682464046FBF7BBF90146FA -:105950005046FBF7ADF8FBF77BFB39462880404605 -:10596000FBF7B0F9314607464846FBF7ABF901466D -:105970003846FBF79FF8FBF76BFB68800220FEF7C9 -:10598000EFFE254D88B1254A13780133DBB2137041 -:105990000622B3FBF2F102FB113313F0FF0F04D127 -:1059A000FEF72AFBFEF74AFB28702878003018BF64 -:1059B0000120FEF749FDA3781BB1194B08225A615B -:1059C0003EE0FFF773FE20B1154BDA6882F0080263 -:1059D000DA6001222270A2780C4B12B95A7B02B90C -:1059E0001A7023780F4D2BB3FFF78EFE25E000BF12 -:1059F000C8210020281F0020E81A00200CFEFFFF0D -:105A000087200020962100209E2100206F21002069 -:105A10008E200020362000201D0D0020060D0020C5 -:105A2000000C0140FC0C0020B62100208A20002040 -:105A3000842000202868FFF757FE2868FFF770FED3 -:105A400004F046FF8020FEF78BFEA8B1134B144AEA -:105A50001B681168591A00290EDB03F543435033C4 -:105A6000A07813600F4B003018BF0120B3F902106B -:105A7000B3F90020FDF726F905F0B8FD202004F069 -:105A8000DFF918B1054B186804F066F9064B9B68FE -:105A90000BB10648984705B0BDE8F08FFC0C00201C -:105AA000000D0020A00F0020682000202C200020E6 -:105AB000024B9A780AB100229A7070476F21002039 -:105AC0000B4B19781A4651B1997879B9597831B98F -:105AD00001229A70074B1A88074B1A8070479378F7 -:105AE00023B90220FF21012207F02CBC704700BF20 -:105AF0006F2100208E200020362000202DE9F84F55 -:105B00008F4F04F0B5FA386804F0DAFA8D4C0028AB -:105B100000F03D82386804F083FB4FF48040FEF7CC -:105B20001FFE20B1884B1B780BB9FFF7C1FF04F0B3 -:105B3000ADFB4FF40070FEF713FE88B13B68834A5B -:105B4000834D934208D92B681B681B6A984718B984 -:105B50002B681B685B6A98472B681B685B699847D2 -:105B60000022B4F81451B4F81661134679489B0822 -:105B7000115E0232A942C4BF63F07F03DBB2B142BF -:105B8000B8BF43F04003082A8146EFD1724EDFF8D8 -:105B9000E48132789A4205D198F80020F92A04D895 -:105BA000013200E0002288F800204FF4804033707A -:105BB000FEF7D6FD58B1B4F81211B4F8DC20B9F9EB -:105BC0000630881A834202DD0A4493420ADB4FF40E -:105BD0008040FEF7C5FDC8B9B9F90620B4F8143104 -:105BE0009A4213DA01F0F6FB01F0FCFB5B4BB3F8D1 -:105BF00076305BB1544B1A78594B002A00F0398348 -:105C00001A78002A00F03583FFF75AFF98F8003021 -:105C1000142B40F0C380524B504D93F802B09A467B -:105C2000BBF1000F18D0B5F8763023B933785F2B6D -:105C300001D1FFF73DFF94F81A31002B00F0AE8040 -:105C4000B5F87630002B40F0A98033787D2B40F0FA -:105C5000A580FFF72DFFA1E03378572B18D14FF423 -:105C60007A7000F0FFFD4FF48070FEF779FD08B107 -:105C700002F0DCFF042004F0E3F810B10A2000F089 -:105C80006DFC082004F0DCF8F0B9364B18801BE0FE -:105C90000420FEF765FDB8B12F4B1B785A2B13D1AA -:105CA000314B1A782AB183F800B0304B01221A70B8 -:105CB0000AE02F4A137883F0010313700BB102201E -:105CC00000E00320FEF74EFC33785D2B00F0D88215 -:105CD0005B2B00F0D7825E2B00F0FE82B5F87630A9 -:105CE0002BB932786F2A02D1FFF7EAFE13E094F85D -:105CF0001A211AB113B933787E2BF5D03378972B4C -:105D000004D14FF4C87000F0FBFA04E0A72B04BFE5 -:105D100001238AF80E303378BB2B03D1B5F85E30FF -:105D2000023304E0B72B05D1B5F85E30023BA5F88D -:105D30005E3028E0BE2B1FD1B5F85C30023320E086 -:105D4000FC0C0020E81A002080210020404B4C0071 -:105D500028200020C8210020F80C0020281F002047 -:105D60006F2100208E2000201C0D0020140D00202B -:105D70000B0D0020160D0020BD2B0FD1B5F85C30A7 -:105D8000023BA5F85C3094F83C04FEF783FCFEF778 -:105D900091FCFEF737FF002388F800300420FEF75F -:105DA000DFFC48B37E4A7F4B117871B17E49897818 -:105DB00059B1B9F90600B4F81411884205DD197813 -:105DC00019B97A483225058011705B7C53B1784B44 -:105DD0001A782AB9774A127812B9744A3221118096 -:105DE000012208E0734B1A7832B16F4A92781AB9DF -:105DF0001A70714B01221A7070480123002230F88A -:105E0000021F5E1EA1F21555B5F5C77F8CBF002598 -:105E100001259D4009B22A4340F21355A942CCBF47 -:105E200000250125B5402A4340F2A465A942D4BF0C -:105E3000002101215D1CA94003330A430D2B92B2BE -:105E4000DDD100235E49574E01EB4301B1F87610D6 -:105E50000A420CBF0021012199550133152BF1D1C4 -:105E60007378514D23B1022003F0EAFF68B914E0C2 -:105E70004FF40070FEF774FC78B1524B1B681B683E -:105E80009B6898470028EED107E0EB783BB901F01A -:105E9000A1FA454B0122DA7001E00023EB70B378E0 -:105EA0004BB10023EB702B7933B901F093FA3E4BE1 -:105EB00001221A7100E02B71EA78434B12B93A4A79 -:105EC000127912B110225A6101E010221A610420E5 -:105ED00003F0B6FF10B3F3788BB1AB7983B9324AD4 -:105EE00001219171394A1168394A1160394AD188C2 -:105EF000394A1180394A1360394A136000E0AB71A6 -:105F00004FF40050FEF72CFC40B133792BB1EB7B02 -:105F100023B9254B0122DA7300E0EB73022003F072 -:105F20008FFF10B1737933B90FE0082003F088FFB9 -:105F30000028F7D119E06B7943B91B4B01225A7144 -:105F4000284B1A88284B1A8000E06B71B3792BB16B -:105F50006B7A23B9144B01225A7200E06B72F37909 -:105F60001BB1204B1A88214B1A80202003F068FFB8 -:105F700008B103F095FE337B03B10123AB72637963 -:105F8000082B01D00E2B6BD100236B7268E0184DEB -:105F90002B68042B64D8DFE803F02D37424C570000 -:105FA0000B0D0020802100206F210020200D0020FB -:105FB0000A0D00201C0D0020140D0020CE21002011 -:105FC000281F002028200020000C0140B0200020C5 -:105FD000B420002096210020040D0020840F002012 -:105FE000900F00208E2000207C20002036200020F2 -:105FF000100D0020012308202B6003F021FF18B1B1 -:10600000A14800F0A3FB58BB2B68042001332B6090 -:1060100003F016FF18B1386800F0A6FA00BB2B6831 -:10602000042001332B6003F00BFF10B101F02EFFB1 -:10603000B0B92B684FF4807001332B60FEF790FBF2 -:1060400010B102F019FE0BE0002310202B6003F0CA -:10605000F7FE08B100F08AFD4FF40050FEF780FB18 -:1060600000F0F0FDA2893860884B22B11968411A0E -:106070000029C0F2F0801044186001F07DFCFFF7A9 -:1060800065FB00F0DFFD824B82491A683860821A96 -:10609000186008200A8003F0D3FE7F4E002830D01D -:1060A0007E4A9188154601F145039BB28A2B7C4AB2 -:1060B0007C4B24D87C4847790FB31F881388407BDA -:1060C000FA1A92B293B21FB2B337BCBF02F5B473DF -:1060D0009BB21AB2B32AC4BFA3F5B4739BB294F8AF -:1060E000EC2070B152B252425343327B1BB2534345 -:1060F0006FF01D0293FBF2F31944A98001E01B88A5 -:106100001380042003F09CFE002879D0664B9A7916 -:10611000002A75D01F7C614D002F69D196F8A3101D -:10612000624896F8A220624BB5F806E029B3B0F9B0 -:1061300000000FFA8EF1C0EB010CBCF1000FB8BFEC -:10614000CCF1000C94450FDD8142C8BF5242DFF80C -:1061500084C11FFA8EFEC8BF92B2CCF800707244A0 -:1061600001271F70EA804BE01A78002A34D0514A88 -:106170001F701168504A11602EE007880FFA8EFCDC -:1061800038B2C0EB0C0CBCF1000FB8BFCCF1000C66 -:10619000944518DD494ADFF82081B2F800C0F44484 -:1061A000C7EB0C0C0FFA8CFC4FF4FA6ED8F80070A9 -:1061B0009CFBFEF10F440EFB11C111800122C8F8B7 -:1061C00000701A7008E01A7832B13A4A19701768EC -:1061D000394A1760394A1180394BB4F8D0101B681E -:1061E00064311844B4F8D220FEF72AFDE88007E0B5 -:1061F000334B6A8894F91C111B6801FB03236B80E5 -:1062000096F8A63053B1284BDA780AB91B792BB12E -:10621000224B2C4A1188DA880A44DA80202003F0C5 -:106220000FFE40B1204BDA790AB91A7A1AB11B7BFA -:106230000BB103F093FC2448244B00F14C01B4F85B -:10624000F6201D6800F15803A84702F0B5F802F0E7 -:1062500031F802F08BF81E4B1B78002B4DD14FF418 -:106260000060FEF77DFA002847D0BDE8F84F04F043 -:1062700079BB9B78002B3FF4C9ACFFF719FCC5E450 -:1062800001222AE0022228E0E61B00200C0D00205B -:10629000240D00201E0D0020281F00209621002024 -:1062A0007C2000208E2000206F210020040D002083 -:1062B000150D0020B0200020B4200020080D002083 -:1062C000900F0020940F00202C1F002014000020AD -:1062D000A4150020840F002003225FFA82FB0BF13B -:1062E000FF3384F83C34FEF7E5F9FEF75DFC02204D -:1062F00028215A4607F026F8F0E4BDE8F88F00BFE1 -:10630000014B1880704700BF340D0020034B1888E4 -:10631000D0F1010038BF0020704700BF340D0020CD -:10632000204B00222DE9F0411968804613461E4C8F -:106330001E4E25881E4FB5F5C87F04BF0025F550B9 -:10634000F05832F907C0194D844446F803C00433AD -:1063500000260C2BD6538E5202F10202E7D123887D -:10636000012B19D12B68404603F1C8024FF4C873C2 -:1063700092FBF3F20A806A68C83292FBF3F24A8019 -:10638000AA68C83292FBF3F30A4A12889B1A8B80E0 -:1063900001F01CF8FEF740FC2388013B2380BDE898 -:1063A000F08100BF380D0020340D0020480D002082 -:1063B000A8200020120000202DE9F041354D0446B0 -:1063C0002B88322B0ED1344B1A68344B118819802C -:1063D0005188928859809A80314B02881A8042886D -:1063E0005A8001E0002B34D02B490022D1F800C0A4 -:1063F00013460F46298832292A4904BF0020C85075 -:106400002948CE5832F900804644CE50043300214A -:106410000C2B11522CF8021002F10202EAD12B8847 -:10642000012B13D1214A02201170214A1370FEF76B -:1064300099F81A4A3B6811881980518892885980C6 -:106440009A80174B1A885B88228063802B88013BD7 -:106450002B80184B1A78DAB1124900221A700E4BB1 -:1064600008681B68322290FBF2F01880486890FBA5 -:10647000F2F058808968204691FBF2F20E490988B3 -:10648000521A9A8000F0A2FFBDE8F041FEF7C4BBAB -:10649000BDE8F081200D0020380D00202A0D0020DD -:1064A000300D00203C0D0020A82000200A0D002007 -:1064B0001C0D0020140D002012000020064B028845 -:1064C00019888A1A1A80598842888A1A5A809988A3 -:1064D00082888A1A9A807047A82000200F4B10B536 -:1064E0005B6804460E4898470E4B0D481A780146E3 -:1064F000FDF77AFE0C4B1B8813B12046FFF710FF07 -:106500000420FEF72DF910B12046FFF755FFBDE836 -:106510001040064B1868FFF7D1BF00BF382000209D -:10652000A8200020280D0020340D0020380D002068 -:10653000014B1860704700BF380D0020014B1860F8 -:10654000704700BF5C200020034B1888D0F1010089 -:1065500038BF0020704700BF640D0020014B188039 -:10656000704700BF640D00202DE9F041224D2B68DB -:10657000C31A002B3CDB214E28603378204C012BC2 -:1065800010D123699847636898472B6822881D4873 -:1065900013442B601C496369984700233370022021 -:1065A000BDE8F081A3689847E36898471748184901 -:1065B0000068D1F80080134B0078D3F800C008F1D0 -:1065C0000103834208BF0023124A1348176840F8AA -:1065D00028C050F82300BC44C0EB0C070B601760C8 -:1065E0002B6862880120134430702B60BDE8F08175 -:1065F0000020BDE8F08100BF5C0D0020700D002080 -:1066000044200020600D0020680D00205C20002048 -:10661000580D0020780D0020800D0020F8B51E4C8C -:106620001E4A236810681B781D4D013BB0FBF3F038 -:10663000FAF7F0FA1B49FAF7F9FB1B4908F08EF854 -:1066400001464FF07E50FAF733FA1849FAF73AFB51 -:1066500007F0B6FF236807465C682868FAF7DEFA99 -:106660002146FAF72FFB124B06461868381AFAF73C -:10667000D5FA214607464FF07E50FAF719FA01463F -:106680003846FAF71FFB01463046FAF713FA07F0CF -:1066900097FF2860F8BD00BF5C200020780D002027 -:1066A000740D002080E6C547B1DC423ED048874AE1 -:1066B0006C0D002010B5154B154A1B681168187831 -:1066C000144B01381B68B3FBF0F0082391FBF3F483 -:1066D000091B0844106090FBF3F0FAF79FFA0E498B -:1066E000FAF7A4FB0D4908F039F801464FF07E5047 -:1066F000FAF7DEF90A49FAF7E5FAFAF7A9FC094BC5 -:106700001860094B1A88013A1A8010BD5C200020DD -:106710007C0D0020780D002080E6C547B1DC423EAC -:10672000D048874A6C0D0020640D002038B5054C18 -:1067300010256561FCF79EF9034B012225611A7053 -:1067400038BD00BF000C0140510E0020F8B5374B9A -:10675000374D1B682A6804469A1A002A63DB03F542 -:10676000C333A03333482B60FCF74AF93148324B2E -:1067700001461A78FDF738FD304B314A997B1846AF -:1067800079B12968002311600021E1520E462949A0 -:106790002C4F595AD9532C4FD9530233062BF3D1CE -:1067A00086732A4B1B7863B1224B21881888411AC3 -:1067B000198058886188411A59809888A188411A9F -:1067C00099801368002B2CD02A681E48D31A204ABF -:1067D0001D49934216D81F4BDA6882F00802DA602E -:1067E0000023144AC55E9A5A14B2A542C4BF154D7F -:1067F0005A53CD5EA542BCBF134C1A530233062B2D -:10680000EFD10EE00E4A00231360C55ECA5E2A4433 -:10681000022592FBF5F2E2522B44062BF5D1FEF74E -:10682000FBF90120F8BD0020F8BD00BFFC0C0020E2 -:10683000400E002060200020500E00206F2100201C -:106840004C0E0020520E0020440E0020510E00205D -:106850007FC3C901000C0140014B1860704700BFA5 -:10686000580E0020014B1880704700BF680E0020B2 -:10687000034B1888D0F1010038BF0020704700BFDB -:10688000680E00203C4B2DE9F74F5B683B4898476A -:106890003B4B3A481A780146FDF7A6FC394B374F77 -:1068A0001A889846DFF8E8A0002A3CD0364B00252D -:1068B0001B68364E93F800B02C46B8F80030DFF86D -:1068C000D490B3F57A7F05D10023304649F80430DF -:1068D000FEF7D0F9785F59F80430034449F80430E2 -:1068E000FAF79CF901463046FEF7C7F900237B53BF -:1068F0002AF80530B8F80030012B25D13046FEF7D4 -:10690000FEF90346BBF1000F0FD058460193FAF78A -:1069100085F9019B01461846FAF790FB28B1194BFF -:106920004FF47A721A8000231BE059F804304FF4B8 -:106930007A7203F5FA7393FBF2F30A200F21012216 -:106940002AF8053006F0FEFC04340C2C05F1020593 -:1069500006F11406B1D1B8F80030013BA8F80030B8 -:10696000E1E7F95A3AF803208A1AFA520233062B61 -:10697000F7D103B0BDE8F08F682000209020002000 -:10698000A80E0020680E0020580E00206C0E00207B -:10699000640F00205C0E002038B505460A4C002329 -:1069A0000A4829462370FBF723F848B907482946C7 -:1069B000FAF7AEFD20B905482946FAF7D7FE08B127 -:1069C0000123237038BD00BFA80E002068200020DE -:1069D00003780BB1054A137043780BB1044A137066 -:1069E00083780BB1034A1370704700BFA80E0020D4 -:1069F000280D0020500E00202DE9F743814608465F -:106A000014469846FFF7C8FF0746002800F08A8022 -:106A1000464E00233370464D072C38D8DFE804F08B -:106A2000080819242F373704022003F01BFA2EE040 -:106A30008DF8043001A84FF448733E49ADF8063094 -:106A4000FAF7AAFC18B101232B7004233370012C30 -:106A50001DD03848FAF77CFF30B102232B70022C8E -:106A60004FF00103337012D03248FAF7F1FD30B124 -:106A700003232B70032C4FF00203337007D02D48F3 -:106A8000FAF7ECFC18B104232B70012333702B7838 -:106A90002BB90CB11C46BBE7022003F0E3F92648F2 -:106AA000FBF72AFB30B92448FBF75EF910B9042044 -:106AB00003F0D8F94846FFF78BFF022003F0C0F936 -:106AC00010B11C4B1B6898471C4B1B689847FBF781 -:106AD00083FF18B11A4B03221A7002E0082003F05A -:106AE000C1F9082003F0ACF9164C0546C0B1642783 -:106AF00098FBF7F63046FAF791F8814607FB1680C7 -:106B000000B2FAF78BF81049FAF7DCF8014648466C -:106B1000F9F7D0FF0D49FAF7D5F82F46206001E0CC -:106B200000232360384603B0BDE8F083280D002021 -:106B3000540D002038200020442000206820002030 -:106B4000500E00209C0F00208988883C00002041C6 -:106B500008B50120FCF738F9102003F07BF9024B4F -:106B600000221A6008BD00BF782000200148FCF711 -:106B700095B900BF7820002008B503681B689847C6 -:106B800008BD38B505460C4614F8011B19B1284656 -:106B9000FFF7F2FFF8E738BD08B503685B68984770 -:106BA00008BD08B503689B68984708BD08B5036829 -:106BB000DB68984708BD08B503681B69984708BD9E -:106BC00008B503685B69984708BD0000034B4FF4A4 -:106BD000805208B15A6170471A617047000801403D -:106BE000034B4FF4805208B11A6170475A617047E5 -:106BF0000008014008B5024B1B68984708BD00BF5C -:106C0000AC0E0020064B00201A68064B9A4208BFC3 -:106C1000054A064B18BF064A1A60FFF7EBBF00BFD4 -:106C20008C010020001BB700E16B0008AC0E0020B7 -:106C3000CD6B0008024B1A6801321A60704700BF22 -:106C4000B00E002010B5094A094913688C68126813 -:106C50009342F8D1074A106811684FF47A72504392 -:106C6000001BB0FBF1F002FB030010BDB00E0020D2 -:106C700010E000E0B40E0020014B1868704700BF20 -:106C8000B00E002038B50446FFF7DCFF0546FFF7DD -:106C9000D9FF401BA042FAD338BD10B504462CB131 -:106CA0004FF47A70FFF7EEFF013CF8E710BD0000EB -:106CB00070B53A4D8CB006AC06460FCD0FC495E8C2 -:106CC000030084E80300304606F0BEFB344801218F -:106CD00007F072FA44F61D20012107F061FA012045 -:106CE000014607F051FA2F4D07F08AFA00238DF87C -:106CF00002300CAC4FF6FF732B48694624F8303D48 -:106D0000FBF792FF28466946FBF78EFF2748694646 -:106D1000FBF78AFF264B07AC5A6842F000725A60B4 -:106D2000FFF770FF08232B6110232B610DAD214B62 -:106D30001A68214B9A4204D1A378142B04BF102364 -:106D4000A37054F8040C21460834FBF76DFFAC42E5 -:106D5000EDD101A807F0CCF9019B184AF021B3FB53 -:106D6000F2F3174A17481360174B1A684FF47A73F7 -:106D7000B2FBF3F2154B013A5A60154A82F8231020 -:106D800000229A6007221A60FBF778FCFBF77AFA78 -:106D90006420FFF782FF0CB070BD00BF44190108EA -:106DA00007004000000C01400008014000100140B5 -:106DB000000001408C010020001BB70040420F0082 -:106DC000B40E0020005800409001002010E000E0C8 -:106DD00000ED00E040F2DB14604308B50D4B1022DB -:106DE0005A6108221A61841E0A4B2046DA6882F032 -:106DF0001002DA60DA6882F00802DA60FFF74DFF0D -:106E00000120FFF7F7FE1920FFF747FF0020FFF7EB -:106E1000F1FEE9E7000C014010B1034A034B1A6090 -:106E2000034A044BDA607047EFBEADDEF04F00203E -:106E30000400FA0500ED00E02DE9F04F87B005935E -:106E40007A4B0492B3F90220B3F90030002AB8BF9C -:106E50005242002BB8BF5B4200249A42B8BF1A4688 -:106E6000074603922546A146A04602940194264671 -:106E70006F4BDA7812B91B79002B38D0022E36D03E -:106E80006A4BDDF810C0E85E6A4BCCF10001EB5EA6 -:106E9000624603EB4000FDF7D3FE674BDDF814C0FC -:106EA00035F903B03CF90530CBEB000000EB030BE8 -:106EB000F879FA7E00FB0BF064236FF0040190FB7D -:106EC000F3F0514302EB8202FDF7BAFEDFF888A12E -:106ED000019054F80A005949584442F21072FDF7E3 -:106EE000AFFE7B7C44F80A00584300130290504BDD -:106EF000DA781AB11B790BB9022E33D14B4B5020E3 -:106F000035F90380DFF83CA100FB08F0BB5D35F9E3 -:106F10000A20DFF8489190FBF3F0042392FBF3F38F -:106F2000C01A54F809304FF47A5218444449FDF716 -:106F300087FE35F90A3049F80400002BB8BF5B42E0 -:106F4000B3F5206FC4BF002349F8043059F804207A -:106F50007D2392FBF3F9BB199B7A03FB09F94023CC -:106F600099FBF3F9324B1A79D2B1022E18D0DDF821 -:106F70000CC04FF4FA710CFB08F2CCF5FA73DDF893 -:106F800004C003FB0C22DDF80CC092FBF1F20CFBF9 -:106F900009F0DDF808C003FB0C0393FBF1F308E0F4 -:106FA000DB780BB1022E02D14B46424601E0029B38 -:106FB000019A2449DFF8A8B0695A04200FFA81FC2D -:106FC00016F80BB09CFBF0FA0BFB0AFB6FF04F0AB4 -:106FD0009BFBFAFA02EB0A0B1B4A35F902A0A952F5 -:106FE000CAEB0C0C9CFBF0F0184ADFF878C054F8A0 -:106FF00002A054F80C10A050154A5144B25C014450 -:107000005143202291FBF2F15B1A124801369B4456 -:10701000032E44F80CA025F800B004F1040405F197 -:1070200002057FF425AF07B0BDE8F08F9621002060 -:107030006F2100204E120020A00F0020F0D8FFFF8B -:1070400080C1FFFF960F0020DC0E0020FC0E002008 -:10705000872000207E200020140F0020F00E00204A -:107060008A200020E40E00202DE9F04F002485B096 -:1070700006468A469346039307462546022DDFF8C7 -:107080003C814FEA450908D19AF80530B8F90480E7 -:107090001B3308FB03F35B1128E03F4B38F9150065 -:1070A00033F915305A4603EB4000CBF10001FDF7F0 -:1070B000C7FD3A4B33F91530C01A039B33F915203D -:1070C0001044374AD37873B99AF8043038F90980F4 -:1070D0001B3308FB03F312791B113AB1727C504346 -:1070E00003EB202302E0F37943431B112D4A705D2B -:1070F00032F90980042298FBF2F8C8EB030800FB80 -:1071000008F0DFF8BCC0C0110290BCF80000264BAC -:1071100000FB08F0E258B97AC01201FB00202349B5 -:10712000E0504FF400120193CDF800C0FDF788FD48 -:10713000019BDDF800C0E0501D4B4FF6FF72E15897 -:1071400044F80380BCF80030C1EB08011B09B2FB16 -:10715000F3F35943DFF86CC0164B891154F80380E0 -:1071600054F80C20E150029B424403EB60303B7D1D -:107170000A445A430135104B00EB2222032D44F8F8 -:107180000C8023F8092007F1010704F104047FF4BF -:1071900075AF05B0BDE8F08F4E120020A00F0020A3 -:1071A0006F210020960F0020F00E00200000E0FF6D -:1071B000D00E0020280F00207E20002096210020E5 -:1071C0001E0D0020080F00202DE9F04F89B0069316 -:1071D000684B804618880591F9F71CFD6649F9F758 -:1071E00071FD00240490464625462746022FDFF80D -:1071F000CC910BD1059AB9F9040053790A3358435D -:10720000F9F70CFD5D49F9F711FE37E05C4B39F9F0 -:107210000500EB5E5B4918444FF4FA72FDF710FD70 -:10722000594BDFF89CB1EB5EC01A069B5A5F1044C5 -:10723000F9F7F4FC5549F9F7F9FD9BF8032082466C -:10724000C2B9059B39F905001A7914325043F9F790 -:10725000E5FC4A49F9F7EAFD9BF80420814672B142 -:10726000D8F848105046F9F72DFD01464846F9F781 -:1072700021FC03E0D8F84410F9F724FD8146444B83 -:107280000137585FF9F7CAFC424B0436D968F9F761 -:1072900019FD824651464846F9F70AFCF1698346D2 -:1072A000F9F710FDDFF81C91049907905846F9F79B -:1072B00009FDB16AF9F706FD54F80910F9F7FAFB70 -:1072C000354A3649FDF7C4FC44F80900DFF8F89068 -:1072D000834654F809105046F9F7EAFB44F809A030 -:1072E000024604994FF07E500192F9F79FFD019AF2 -:1072F00001461046F9F7E6FC294B2A4A54F803C028 -:10730000A1588146604601920293CDF80CC0F9F76E -:10731000D1FB4946F9F7CEFBDDF80CC0029B019A80 -:10732000214944F8039044F802C0F9F77FFD716BDE -:10733000F9F7C8FC1D4A1E49FDF78AFC59468146EB -:107340000798F9F7B7FB4946F9F7B2FB07F038F9A8 -:1073500018494FF47A72FDF773FC174B032F5853FB -:1073600004F1040405F102057FF440AF09B0BDE863 -:10737000F08F00BF1E0D0020BD378635000048424B -:107380004E1200200CFEFFFFA00F00200000204145 -:10739000960F00206820002000007A4300007AC386 -:1073A000340F00201C0F00200000404000009643D6 -:1073B000000096C318FCFFFF7E20002096210020CD -:1073C0006F210020B80E0020C40E0020002303808F -:1073D00043807047024B00221A605A60704700BF1A -:1073E000140F0020054B00221A605A609A60044B6B -:1073F00000221A605A609A60704700BFF00E0020A9 -:10740000B80E00200128054B03D0022803D0044AFF -:1074100002E0044A00E0044A1A60704714000020A9 -:10742000396E000869700008C9710008000000008A -:107430002DE9F84F384E04463768384607F08AF889 -:107440000546384607F0FAF876688046304607F079 -:1074500081F88346304607F0F1F8D4F804900646E8 -:1074600029464846F9F72EFCA76882464146384629 -:10747000F9F728FC01465046F9F71AFB21688246C5 -:107480005846F9F71FFC414604464846F9F71AFCEE -:107490003146F9F717FC01462046F9F70BFB314658 -:1074A00004463846F9F70EFC2946F9F70BFC01466D -:1074B0002046F9F7FFFA0146504607F04DF9174903 -:1074C000F9F700FCF8F7B2FF11A3D3E90023F9F7AD -:1074D0002BF9134B044618680D46F8F7A7FF024630 -:1074E0000B4620462946F8F743FE00220D4BF9F7DC -:1074F0001BF9F9F789FA07F063F883B21A0444BF5D -:1075000000F5B4739BB218B2BDE8F88FAFF30080FA -:10751000182D4454FB210940500F00200000E14485 -:107520009C0F00200000244010B5294C2088F9F75A -:1075300075FB2849F9F7C6FB07F042F8264B18807F -:107540002088F9F76BFB01462448F9F76FFC2449C2 -:10755000F9F76CFC234B1860234BB3F8A400F9F740 -:107560005DFB01462148F9F761FCF8F75FFF12A3C4 -:10757000D3E90023F8F7AEFFF9F746FA1C4B186081 -:107580001C4BD868F8F752FF0DA3D3E90023F8F796 -:10759000A1FF0DA3D3E90023F8F79CFFF9F734FA14 -:1075A000154B1860082002F04BFC18B1BDE81040E4 -:1075B000FFF7BCB810BD00BF3B597E90A9E78140E2 -:1075C000399D52A246DF913F000000A0F7C6B03EB1 -:1075D00012000020C903683F480F00200AE81C4140 -:1075E00000401C46A4200020281F00200000614409 -:1075F000C020002068200020C4200020AFF30080BD -:107600002DE9F041044600680D460146F9F75AFBA2 -:10761000D4F80480064641464046F9F753FB01463C -:107620003046F9F747FAA768064639463846F9F76B -:1076300049FB01463046F9F73DFA07F017FA0021F9 -:107640000646F9F7D3FC70B920683146F9F7EEFB2E -:10765000314628606068F9F7E9FB31466860A06848 -:10766000F9F7E4FBA860BDE8F0812DE9F04F0C6864 -:10767000836889B0D0F800A0D0F804800646204680 -:1076800003938B4606F066FF0746204606F0D6FFBA -:10769000DBF804408146204606F05CFF05462046A4 -:1076A00006F0CCFFDBF8082004461046019206F0F5 -:1076B00051FF019A8346104606F0C0FF39460290FA -:1076C0005846F9F7FFFA394604900298F9F7FAFAA2 -:1076D000594605904846F9F7F5FA0299069048464A -:1076E000F9F7F0FA294607905846F9F7EBFA014600 -:1076F0005046F9F7E7FA214683460698F9F7E2FA89 -:1077000001460598F9F7D6F901464046F9F7DAFA45 -:1077100001465846F9F7CEF9214683460498F9F711 -:10772000D1FA01460798F9F7C3F901460398F9F72A -:10773000C9FA01465846F9F7BDF93060029905F1DA -:107740000040F9F7BFFA01465046F9F7BBFA214667 -:1077500083460798F9F7B6FA01460498F9F7A8F9AD -:1077600001464046F9F7AEFA01465846F9F7A2F944 -:10777000214683460598F9F7A5FA01460698F9F7D8 -:1077800099F901460398F9F79DFA01465846F9F729 -:1077900091F9214670605046F9F794FA294604465B -:1077A00009F10040F9F78EFA01464046F9F78AFAE6 -:1077B00001462046F9F77EF9394604462846F9F78E -:1077C00081FA01460398F9F77DFA01462046F9F758 -:1077D00071F9B06009B0BDE8F08F80EAE073A3EB07 -:1077E000E0738B4206DB002801DD401A704702D0AF -:1077F00008447047002070472DE9F041524B86B095 -:107800001A685B6802F1004203F1004301934F4B99 -:107810000646B3F900000092F9F700FA00F10040C3 -:10782000F8F704FE46A3D3E90023F8F753FEF9F76F -:10783000EBF8474C0290B4F90000F9F7EFF9039028 -:10784000B4F90200F9F7EAF90490B4F90400F9F781 -:10785000E5F9404D0590694603A8FFF706FF95F846 -:107860007430012B15D13C4B3C4C9B7863B9236899 -:10787000402093FBF0F0181AF9F7D0F90599F9F7C1 -:1078800019F9F9F7E5FB20602068402390FBF3F03D -:1078900001E0334B1888F9F7C1F901460598F9F76B -:1078A00007F905903046F9F7B5F92E490746F9F77B -:1078B00001F901463846F9F7B9FADFF8B88007460A -:1078C000D8F8004005982146F9F7F2F80146384605 -:1078D000F9F7F8F901462046F9F7ECF8224C07468B -:1078E000C8F800000398D4F8008006F069FE95F807 -:1078F0006210FFF772FF404420600498D4F80480BF -:1079000006F05EFE95F86210FFF767FF4044606086 -:107910003846D4F8088006F053FE95F86110FFF75A -:107920005CFF124B40441A68A06016441E60104B66 -:107930001A6801321A6006B0BDE8F081AFF300802A -:10794000399D52A246DF913F500F00208E2000202B -:10795000B8200020281F00206F210020780F002071 -:10796000120000203661823C98200020740F002015 -:10797000880F00207C0F00202DE9F04F89B0FEF722 -:1079800081FF022002F05CFA9B4D9C4F002800F022 -:10799000B2819B48FEF7A2FDFFF754F9994C0646C9 -:1079A0002368C3EB00094846F9F734F9964B196888 -:1079B000F9F788F9954A266092F86030002603901E -:1079C00002933446B246285FF9F728F90399F9F78C -:1079D00079F9029A0DF1140848F806005AB31046D6 -:1079E000F9F71CF901464FF07E50F9F71FFADFF85E -:1079F00050B2024611464FF07E500092F9F758F807 -:107A000056F80B10F9F75EF98446385FCDF804C0DC -:107A1000F9F704F9009A1146F9F754F9DDF804C0B2 -:107A200001466046F9F746F84BF80600F9F710FBF7 -:107A3000774A105302E0395B754AA152744A043602 -:107A4000A15E0234062C01FB01AA9346BBD1714A08 -:107A50006424128804FB0AF352436F48414693FBA7 -:107A6000F2F4FFF702FE082002F0EAF920B16B48B9 -:107A70004146FFF7FAFD07E069484146FFF7F5FD8B -:107A800067480146FFF7BCFD493C664EA4B23B2C5B -:107A9000B6F8F00006D90820B6F8F24002F0D0F9A6 -:107AA00048BB53E0F9F7B6F84FF07E518046F9F73E -:107AB00001F801464FF07E50F9F7B8F90024074667 -:107AC000DFF854A140465AF81410F9F7FBF80346C2 -:107AD0003BF904000193F9F7A1F8019B0146184610 -:107AE000F8F7E8FF3946F9F7EDF84AF814000234E0 -:107AF000062CE5D1CFE74B4BB3F8F200F9F78AF843 -:107B000080462046F9F786F84FF07E51F8F7D2FF0D -:107B100001464FF07E50F9F789F9002407463F4EA1 -:107B2000404656F81410F9F7CDF83F4B8246185FDF -:107B3000F9F774F801465046F8F7BCFF3946F9F7F3 -:107B4000C1F846F814000234062CE8D1374B324C09 -:107B5000B3F90000F9F762F8A668014630464FF025 -:107B60000107F9F76BFA00B90746314B31466068F7 -:107B70005F7306F0F1FD2F4ED4F808A03060206846 -:107B800000F1004760680146F9F79CF851468046CD -:107B90005046F9F797F801464046F8F78BFF06F094 -:107BA00065FF0146384606F0D7FD70603068F8F78B -:107BB0003DFC0FA3D3E90023F8F78CFCF8F724FF72 -:107BC00006F0FEFC1C4F38807068F8F72FFC08A305 -:107BD000D3E90023F8F77EFCF8F716FF06F0F0FC77 -:107BE0007880082002F02CF9144E58B30B482AE094 -:107BF0003B597E90A9E7814090200020A8200020DA -:107C0000841F00204C0F0020C4200020281F0020CB -:107C1000B820002012000020C8200020580F0020AB -:107C200018000020E81A002060200020480F0020E3 -:107C30006F210020500F0020A00F00208E20002078 -:107C4000A80F00204048FFF7F3FB30804846FFF7BD -:107C5000D3FD3E4A92F8A630002B4FD020686768CB -:107C60000146F9F72FF8394606463846F9F72AF85B -:107C700001463046F8F71EFFA46806462146204616 -:107C8000F9F720F801463046F8F714FF06F0EEFE4B -:107C900001462046F9F7CAF82D490646F9F7BAF920 -:107CA0002C4C10B10023238028E0304606F004FD60 -:107CB000294B1968F9F706F806F082FCB0F5617FE8 -:107CC000A8BF4FF46170F8F79FFB1DA3D3E9002311 -:107CD000F8F72AFDF8F798FE06F0B0FC1B4B0646B5 -:107CE00093F8A600F8F79AFF3146F8F7EBFF06F095 -:107CF00067FC208002E038807880B880174B5B7981 -:107D0000012B174B06D02A881A806A885A80AA88C5 -:107D10009A8010E0134AB5F90410B2F9000001EBA3 -:107D20004001032091FBF0F189B211802A889980EB -:107D30001A806A885A8009B0BDE8F08FAFF30080DE -:107D4000A2EB0FE5DD16964018000020281F00204A -:107D50008FC2753C940F0020C0200020E81A00203C -:107D6000960F00208C0F0020044A002313605360FC -:107D70009360034A1360034A136070479820002001 -:107D8000880F0020740F0020028840F23E6302F248 -:107D90001F3292B29A4208D8408800F21F3080B257 -:107DA00098428CBF002001207047002070470000DF -:107DB0002DE9F04707462D4889469046FFF7E4FF36 -:107DC000002851D02A4B4FF4FA721868294B2A49DF -:107DD0001B682A4CC01AFCF733FF0A21FFF7FDFC91 -:107DE000E37980225843264990FBF2F04FF49672D3 -:107DF000FCF726FFC71B607B20237843204990FBBC -:107E0000F3F04FF49672FCF71BFFE37D1D4D5F43CB -:107E1000082397FBF3F72B684FF448321A49824640 -:107E2000F8182860FCF70CFF0646286094F821003B -:107E3000F8F7F4FE414604464846F8F73BFE014693 -:107E40002046F8F73FFF4FF07251F8F73BFFF9F784 -:107E5000FFF86FF095019622FCF7F2FE4FF4806375 -:107E600096FBF3F6301A5044BDE8F087A00F0020CF -:107E7000B4200020B02000200CFEFFFF281F0020AF -:107E8000D4FEFFFF840F002000E0FCFF2DE9F04F3F -:107E900085B0FEF7D7FE674B46F2A7121E68861B19 -:107EA000964240F2C2801860FEF74EFB624C28B941 -:107EB000FEF700FC614A002323601360FEF7AEFB6F -:107EC0005F4B604918600246086800930192F8F71A -:107ED000A1FE5D490746F8F7F5FE5C4982468868D1 -:107EE000F8F79CFE5A4905460868F8F797FE0146E0 -:107EF0002846F8F79BFF574905460968F8F7E2FE60 -:107F00003946F8F7DFFE4FF07C510390F8F7DAFEC0 -:107F10005146F8F7D7FE2768844651463846CDF8D3 -:107F200008C0F8F7CFFEDFF84CB1DDF808C0DFF885 -:107F30000C81DBF8709001466046F8F7BBFDD8F87D -:107F40000010F8F7B7FD4946F8F7BCFE019A8246E3 -:107F50001046F8F763FE494602464FF07E50019204 -:107F6000F8F7A6FD019A01461046F8F7ABFE014668 -:107F70005046F8F79FFDC8F80000F9F769F8364A4F -:107F8000039910603846F8F795FD344F2060FFF7ED -:107F9000EBFE009B3868D3F80080C0EB0800F8F7D0 -:107FA0003DFE2F49F8F78EFE81463046F8F732FE47 -:107FB00001464846F8F73AFFF9F74AF84FF4967247 -:107FC0002849C7F80080FCF73BFE0A21FFF705FCB3 -:107FD000DBF86C60216880463046F8F773FE074690 -:107FE0004046F8F71BFE314680464FF07E50F8F7CA -:107FF0005FFD01464046F8F765FE01463846F8F752 -:1080000059FD206006F0DCFA05210646FFF7E5FB86 -:10801000154C164B2946186022683046FFF7C8FEFB -:10802000134B25601860012000E0002005B0BDE87A -:10803000F08F00BFA40F0020400F0020440F00204D -:10804000740D0020740F0020BD3786359820002065 -:10805000880F0020A4200020B02000206C0F0020FA -:1080600000247449D4FEFFFF800F0020700F002011 -:10807000900F0020281F002010B5054C00202188FB -:10808000FBF76CF861880120BDE81040FBF766B88B -:108090002400002010B5094C2060094801600949FE -:1080A0000A60094A1360094A029B1360084A039B4D -:1080B0001360084A049B136010BD00BFB40F00207A -:1080C0009010002094100020C00F0020BC0F002052 -:1080D000C80F00208C1000200A4B1A6802EBC00267 -:1080E000D379FF2B07D008490978994203D9074A69 -:1080F00032F8130004E00728D4BF908840F2DC5027 -:1081000000B27047B40F0020C4210020C821002015 -:10811000054B1B6803EBC00090F9063019420CBFF9 -:1081200001204FF0FF307047B40F002010B500243D -:108130004FF48040FCF714FB08B1054B00E0054B01 -:108140001B68054A9B88A3520234182CF0D110BD3D -:108150009010002094100020EC2000202DE9F04128 -:108160003B4BDFF80481C400187008EB04035B7814 -:10817000384E054620200F463360FCF7F1FA4246A0 -:1081800008B101233360162D1AD10024385900217B -:10819000F8F72CFF28B14FF48040FCF7E1FA48BB18 -:1081A00024E02D4E3B1926440FCB86E80F002B4BC5 -:1081B00010341A78C02C02F101021A70E6D1EAE7F5 -:1081C000144412F83570254BD4F804E01F70BEF14A -:1081D000000FE0D00024BC42DDDA1F4E23011E4414 -:1081E00073440FCB013486E80F00F4E7082D1C4BD5 -:1081F00024D125E0194B1F78012FF7D9194C0026FF -:10820000BE4204F11004F1DA54F8100C4FF07C5126 -:10821000F8F758FD4FF07C5144F8100C54F8140C4A -:10822000F8F750FD4FF07C5144F8140C54F80C0C46 -:10823000F8F748FD013644F80C0CE1E70E2D01D1AA -:10824000012200E000221A74BDE8F041FFF76EBF82 -:10825000B80F002098100020CC0F0020C60F00207F -:108260006F210020D40F0020501D01082DE9F0419E -:108270008C46461C002300224CF803201033C02BF0 -:10828000F9D10B4B03EBC602576898466FB1002437 -:1082900018F836309C4208DA23010CEB03053B4406 -:1082A0000FCB013485E80F00F2E7BDE8F08100BF95 -:1082B000501D0108284B10B51B68002B4AD0274BD6 -:1082C0001B78013B142B3DD8DFE803F00B3C3C242A -:1082D000403C3C1C3C3C3C3C3C2C3C3C3C3C3C2422 -:1082E0002C001F4B1B685B7833B11E4B0020598953 -:1082F000BDE81040FAF732BF1B4B98780028F4D144 -:108300000146F5E7174C0020E188FAF727FF012026 -:108310002189EDE7134C00202189FAF71FFF012086 -:108320006189E5E70F4C0020E188FAF717FF01208B -:108330002189FAF713FF02206189FAF70FFF032062 -:10834000A189D5E72020FCF70BFA18B1BDE8104051 -:10835000FFF792BE10BD00BF98100020B80F00209C -:10836000C00F0020240000206F21002010B5002342 -:10837000D8B25C1C054B1B78834206D9044B33F8FA -:108380001010FAF7DFFE2346F2E710BDC60F0020FB -:10839000D4200020064B1A780023D9B2914204D28F -:1083A000044921F813000133F7E7FFF7DFBF00BFEF -:1083B000C60F0020D42000202DE9F74FA94E3378B6 -:1083C000032B0FD9A84BA94CB3F904206FF063011C -:1083D000002AB8BF5242891AB4F904006432FCF78B -:1083E0002FFCA0803778012F1ED8A14AA14C13780A -:1083F0009046013B142B00F2D281DFE813F091008C -:10840000D001D00168009F00D001D0012901D00126 -:10841000D001D001D001D001BD00D001D001D001E8 -:10842000D001D0019201A9018F4B9349B3F806A066 -:108430008E4B0968B3F80280B3F80090B3F904B02A -:108440008E4C01910025BD4204F11004CDD20FFAEB -:108450008AF0F8F7E3FB54F8101CF8F733FC0346F6 -:108460000FFA88F00093F8F7D9FB54F8081CF8F7D6 -:1084700029FC009B01461846F8F71CFB03460FFA3F -:1084800089F00093F8F7CAFB54F80C1CF8F71AFCB3 -:10849000009B01461846F8F70DFB019A034692F936 -:1084A0000000009340420BFB00F0F8F7B7FB54F8D4 -:1084B000041CF8F707FC009B01461846F8F7FAFA87 -:1084C000F8F7C6FD6E4B23F815000135BBE7022116 -:1084D0000420FFF71DFE654D0121AF8878431FFA88 -:1084E00080F90420FFF714FE6D8800FB05901FFA49 -:1084F00080F90420FFF7F0FD484420810221052087 -:10850000FFF706FE7843012187B20520FFF700FE42 -:1085100000FB057087B20520FFF7DEFD38440BE055 -:1085200005200121FFF7F4FD504B9D88684385B27B -:108530000520FFF7D1FD2844608130E1514B002038 -:108540001D68FFF7C9FDDFF8549195F90630B9F9B8 -:1085500002203227534393FBF7F318442080012075 -:10856000FFF7BAFD95F90E30B9F90020534393FB9C -:10857000F7F73844608012E1434B9A789946434BB1 -:108580001B6812B99B88E38107E0374A1988B2F962 -:1085900006005A88FCF754FBE081394BE2893C4FD6 -:1085A0001A803B68374D1B7843B30220FFF794FDD8 -:1085B0002B68B3F91010B3F91220FCF741FB354BCF -:1085C0001B685989344B081A1A8800B20FFA82FEC8 -:1085D000864503DA38680078024403E003DD386832 -:1085E0000078121A1A802A68B3F9003092F916201E -:1085F0005343642293FBF2F31944A18099F80A30A3 -:1086000063B1194B1A88D5F800A0E28022819A88BC -:10861000184F62815B880325A38101E0134BF1E7CA -:108620000AEBC50393F90630B7F90690284609FB13 -:1086300003F9642399FBF3F9A7F80690FFF74CFDC3 -:1086400001354844072DF88007F10207E8D1A6E07C -:108650000D4B9A781F460D4B1B680ABB9B88E38124 -:1086600026E000BFC60F0020962100207E200020BB -:10867000B80F002024000020C00F0020CC0F0020E5 -:10868000D4200020B40F00206F210020941000207F -:10869000BC0F0020C80F0020C40F0020A00F002036 -:1086A000B54A1988B2F906005A88FCF7C9FAE08180 -:1086B000B24BE289B24D1A80BB7A032001211BB173 -:1086C000FFF726FDAC4F02E0FFF722FDAD4FB7F8F4 -:1086D0000290022100FB09F01FFA80FA0320FFF745 -:1086E00017FD3F88012100FB07A0E8800420FFF769 -:1086F0000FFD00FB09F002211FFA80F90420FFF7AB -:1087000007FD00FB079028810320FFF7E5FCE388C5 -:108710001844E0800420FFF7DFFC238918442081FF -:108720003DE001210420FFF7F3FC964D6F8878436C -:1087300087B204202781FFF7CFFC38442081012134 -:108740000520FFF7E5FC2D88684385B26581EFE6DB -:108750008C4B0325B3F804A0994628460221FFF765 -:10876000D7FC00FB0AF0012187B22846FFF7D0FCB6 -:10877000C5F106035B0839F8133000FB037087B2BC -:1087800024F815702846FFF7A7FC384424F8150094 -:108790000135072DE1D1784BDA88784B1A802020FB -:1087A000FBF7DEFF784F002849D00020FFF794FC4C -:1087B000208081460120FFF78FFC744B704D1B7A9F -:1087C0006080002B3BD0724B1B681B7813F0020FAC -:1087D000704B1ED0D7F800E0B3F900109EF90E20C0 -:1087E0009EF906E0B3F902304A43CEF1000E03FBD6 -:1087F0000EF3322192FBF1F26FF0310E92B293FB45 -:10880000FEFE9644F14493FBF1F1A5F800900A4472 -:1088100013E03968B3F902E091F90620B3F90030AA -:108820000EFB02FE32229EFBF2FEF144A5F8009000 -:1088300091F90E104B4393FBF2F21044688000252F -:108840003B68605F03EB850233F92510B2F9022023 -:10885000FCF7F6F960530235102DF1D14C4B1B6833 -:108860001B785B0704D4454D32782F8801231CE028 -:1088700098F800300E2B0AD0082B08D0464A02EB9D -:10888000C3035B78002B14BF0225002500E00425FC -:108890000024424B601903EB4403C0B21989013430 -:1088A000FAF75CFC042CF4D1DDE7934208D235F9E9 -:1088B00013103FB2B942A8BF0F46BFB20133F4E76D -:1088C0000024A1463378994574D2DFF8E0803AB2AB -:1088D000D8F800305B889A4203DD2A5BDB1B134427 -:1088E0002B534FF48040FBF73BFFDFF8C4B02B4B1A -:1088F000C0B1B3F90620DBF800305B899A42284BFF -:1089000006DD1A68D8F800305188285F5A8805E0DB -:10891000D8F800201B689188285F1A88FCF790F926 -:1089200028531FE0D8F80020285F11885288009350 -:10893000FCF786F9009B2853B3F90620DBF80030DA -:10894000DFF868A09B8905EB04089A420ADA102038 -:10895000FBF706FFDAF8003008B91B8800E09B88B7 -:10896000A8F800300F4B9B7813B90F4BE35A2B53E9 -:1089700009F101090234A5E796210020D420002046 -:10898000240000207E200020B40F00208021002041 -:108990008C100020A00F0020501D0108C8210020CD -:1089A000901000206F210020EC2000209410002067 -:1089B000C80F002003B0BDE8F08F00BF024B18685D -:1089C000003018BF012070479810002044F2506317 -:1089D000984203DDA0F50C40A0387047034B984245 -:1089E000BCBF00F50C40A030704700BFB0B9FFFF1E -:1089F00010B5044C002320702361FEF73DF960613F -:108A000010BD00BFD012002010B5F8F707F9002103 -:108A10000446F8F713FB08B1204601E004F10040DA -:108A20000549F8F703FA0549F8F74CF905F092FD06 -:108A3000034B186010BD00BF8096184B35FA8E3C72 -:108A400034000020F8B5101A0C461F46F8F7E6F877 -:108A50000546381BF8F7E2F8174B079E1968F8F738 -:108A600031F9294604462846F8F72CF921460746ED -:108A70002046F8F727F901463846F8F71BF805F0C5 -:108A8000F5FF0E49F8F71EF9F8F708FB069B21469B -:108A9000186005F1004005F05FFE0949F8F712F98A -:108AA0000849F8F707F8F8F7D3FA0028BCBF00F533 -:108AB0000C40A0303060F8BD340000202C7D8E3F8B -:108AC000A00CB34500A00C46F8B51D4614460E4652 -:108AD000F8F7A4F86968F8F7F5F83146F8F7F2F80E -:108AE0002168F7F7E7FF2060F8F7B2FAED6807466C -:108AF00005F10040F8F7ACFA06462846F8F7A8FA60 -:108B0000314602463846FCF79BF8F8F787F82060B4 -:108B1000F8F79EFAF8BD000030B5002213460E4962 -:108B2000CC5C0D469CB12E2C04D1013378B11D4490 -:108B300000242C540A246243C95CA1F13004092C9E -:108B40009CBF303A52180E2B03D80133E7E710468A -:108B500030BD002030BD00BF18120020014B18604E -:108B6000704700BFF4120020F8B52B4B2B4C1B783C -:108B700013B1012B0AD04CE06278294B03EB0213AE -:108B8000284A59681068FEF711F83FE0254D28681B -:108B9000FEF711F82E4600283BD02378012B1ED17A -:108BA000FEF76AF863690646C31A632B33D9236953 -:108BB000042B12D81A4F286807EB03135968FDF7E6 -:108BC000F5FF6378286807EB0317B968FDF7D9FF4D -:108BD00023696661013323611BE0022017E02369EA -:108BE0003BB962780E4B286803EB02135968FDF716 -:108BF000DDFF2369094D8B2B08D80B4A3068D15C07 -:108C0000FDF7BAFF2B6901332B6102E00320FFF768 -:108C1000EFFE00236360F8BD4C120020D01200204C -:108C200000220108281200207221010810B50B4C07 -:108C3000E37A8BB10A4B1B78042B0DD9094A0A4BF6 -:108C40001068526818605A60FFF7DEFE074B1A88FA -:108C5000074B1A800123237310BD00BF6F21002032 -:108C60005C21002044210020282100208E200020AB -:108C70003E120020000000002DE9F04F994B8BB010 -:108C80001B68BBB9984C2378013B032B00F2CB85C2 -:108C9000DFE813F08F058F05A90592052068FDF721 -:108CA00080FF924B04461B78012B00F0DD8008D337 -:108CB000022B06D08B4C2068FDF76EFF0028EDD10B -:108CC000E0E7242C07D18A4A00231370894A1370E5 -:108CD000894A1370C4E02C2C02D02A2C40F08380E7 -:108CE000844E864B3278824D002098542A788449ED -:108CF000B2B90A701A78472A68D15A78502A65D1D1 -:108D00009A78472A40F07E85DA78472A40F07A85BB -:108D10001A79412A40F0768501220A7000F072BD6E -:108D2000097801293AD1022A05D1184601F02EF816 -:108D3000744B18604AE0032A07D11B78532B45D1A6 -:108D4000704B1A6852421A6040E0042A05D1184656 -:108D500001F01CF86B4B586038E0052A07D11B78EE -:108D6000572B33D1674B5A6852425A602EE0062A7D -:108D700007D11A78644B302A94BF00220122DA729C -:108D800024E0072A04D1FFF7C7FE604B18701DE0EE -:108D9000092A1BD1FFF7C0FE5D4B16E0022915D151 -:108DA000072A0CD10120FFF7B7FE41F218435843C0 -:108DB0004FF47A72B0FBF2F3564A138006E0082AA9 -:108DC00004D10120FFF7A8FE534B18802B782A2CE2 -:108DD00003F101032B704FF00003337037D14F4B79 -:108DE00001221A703CE00D2C4C4B01D00A2C24D1EE -:108DF0001A78F2B1414908784978A0F13002D2B22C -:108E0000092A84BFA0F13702D2B202F00F0210018A -:108E1000A1F13002D2B2092A84BFA1F13702D2B245 -:108E2000354902F00F0202440978D2B28C1A62422C -:108E30006241002119707AB912E02E490A780E2A8F -:108E400003D8501C08702D498C541B7843B92A4B09 -:108E50001A7854401C7003E0294B1B78012B00D07A -:108E6000002303F0010358E12D4B00221978082953 -:108E700000F25281DFE801F00A05111927607D96A2 -:108E8000A100622801D1022205E01A70B52C40F041 -:108E900043811A7801321A703EE103221A70214B85 -:108EA0001870214B1870214B0BE01F4904221A70D7 -:108EB0001E4B0A7818782244D2B20A7002441A7003 -:108EC0001B4B1C7028E1184905221A70174B0A78B1 -:108ED00018782244D2B20A7002441A70154B1C80D2 -:108EE0001AE100BF28120020D01200204C120020EE -:108EF000C01200205C12002027120020181200204F -:108F000040120020442100206F2100205C2100201D -:108F1000162100201A21002004120020CD1000206C -:108F2000CC100020C8120020391200203C12002072 -:108F3000C51000203A120020624906221A70624BC6 -:108F40000A7818782244D2B20A7002441A705F4B31 -:108F50001A8802EB0424A4B2B4F5007F01D81C8067 -:108F600003E000221A805A4B1A705A4A00231380D9 -:108F7000D3E05448544A017815782144C9B20170AD -:108F80002944117053490A88C72A9CBF5248845407 -:108F9000013292B20A804D490988914240F0BC806A -:108FA000072278E708221A70464B1B78834200F0AC -:108FB000B380474A00231370AFE01A70424B1B780E -:108FC000834240F0A980454B1B78062B39D004D84A -:108FD000022B12D0032B24D09EE0122B44D0302B36 -:108FE00040F09A803C4B1A793D4B102A88BF1022E2 -:108FF0001A701978384A002344E0374B394A5968C7 -:109000005160996811601A694FF47A7392FBF3F218 -:10901000354B1A80354B1A78354BDA720122354BB5 -:1090200020E02D4A537913F0010303D01379D81EA1 -:10903000434243412D4A1370002B38D12C4AD3723E -:1090400035E0254BDA7A12F0010203D09A7AD11E6C -:109050004A424A4125490A700AB92549CA7293F819 -:109060002F20254B1A7022E01B4B24495A690A8095 -:109070009A6942F2107392FBF3F2214B1A8001229B -:10908000204BEFE78B4202F10C0210DA12F8044C8D -:109090001D481C5412F8034C1C481C5412F8014C77 -:1090A0001B481C5414781B481C540133EAE711492F -:1090B0000B788BB3134B1A7872B300221A700A70B4 -:1090C00001232AE0391200203C1200203A1200202D -:1090D000CC100020C21200203C110020C51000203E -:1090E0005D2100204421002016210020F0120020E4 -:1090F0006F210020381200205C2100201A2100205E -:1091000004120020C9120020042100203221002076 -:109110004C2100205E2100200023002B3FF4CAAD2B -:109120008B4CA368E360FDF7A7FDA060202000F052 -:1091300091FE884B884C1A78012A0CBF002201222C -:109140001A70E37A002B3FF4B5AD844B1B78042BE7 -:109150007FF6B0ADA37803B92373227B12B90BB1AC -:10916000FFF764FD7E4B4FF0050E1A787D4D0132FE -:1091700092FBFEFE0EEB8E0ECEEB020E83F800E0AD -:10918000794B1B780593794B03EB8E0E0023784ABD -:1091900078499858DFF81C82774E585090FBF8F1C8 -:1091A0009951764EDFF8109206FB010003EB830A1B -:1091B0005EF80A6053F8097042F2107CBF1B90FB06 -:1091C000FCFC05264EF80A00384443F8090090FBE1 -:1091D000F6F008FB01016A481FFA8CFC195005984B -:1091E00003EB020B012825F802CF164606D1ACF19D -:1091F000020CBCF5797F98BFCBF800100433082B24 -:10920000C5D1FDF739FD5F4F5F4D3B68C01AF7F7D9 -:1092100001FD5E49F7F70AFE2860FDF72DFD386075 -:109220002F684FF07E513846F7F7EAFE08B94FF045 -:109230007E5706AA2F60564B009207AA019296E825 -:1092400003000CCBFFF7FEFB069A64235149B2FBE7 -:10925000F3F207980A80504A90FBF3F31380237BC4 -:109260000BB90B801380DFF854A14C4F9AF80030F3 -:10927000002B36D029684FF07E50F7F7D7FD3B68BA -:1092800080463068C01AF7F7C9FC4146F7F71AFD67 -:10929000F7F7DEFE7B681FFA80FB70680FFA8BFB26 -:1092A000C01AF7F7BBFC3E4B1968F7F70BFD4146B8 -:1092B000F7F708FDF7F7CCFE3A4B00B2B3F90220FE -:1092C0004FF0020E8118B3F9002037485A4491FB41 -:1092D000FEF192FBFEF289B292B241800280598087 -:1092E0001A8001238AF8003071683068237A796027 -:1092F000386023B9184BDB79002B3FF4DBACDFF887 -:10930000C0B0DFF8C080294CCDF800B0CDF80480A3 -:1093100094E80C00FFF796FB73686068244FC01A4E -:10932000F7F77CFC1E4BBA461968F7F7CBFCF7F74A -:109330008FFE226833687860D31A3B600A4B93F93A -:109340000030012B40D0022B00F0D980B2E400BFE6 -:10935000D0120020FE1200206F2100205C2100208E -:109360000C13002066120020C41000209C10002066 -:1093700044210020E812002054120020806967FF79 -:10938000D0100020CC120020F812002000007A44F7 -:109390002821002024210020302100202C12002030 -:1093A0003400002080120020AC1200204412002063 -:1093B0000413002080969800B81200200D1300209E -:1093C000601200207C1200207D4D00245AF81460A9 -:1093D000DFF830923046F7F721FC7A4B7A4F196864 -:1093E000F7F770FCF7F734FE34F809B0774BCBEBA6 -:1093F00000001FFA80FB24F803B00FFA8BFB5846DD -:10940000F7F70CFC3968F7F75DFCF7F721FE704AB7 -:109410001FFA80F811680BEB06002A463B46FFF75F -:1094200053FB6C4EBF686A4B40445AF814B0A053CB -:10943000686804971F68C0EB0B00F7F7EFFB39462D -:10944000F7F7F4FC644B28611B6884469878D5F8DC -:109450000880CDF80CC0F7F7DDFBF6F7E7FF56A361 -:10946000D3E90023F7F736F80B4602465B490020A4 -:10947000F7F75AF9F7F7C8FA3946F7F71BFB014631 -:109480003846F7F7D3FCDDF80CC007464146604686 -:10949000F7F70EFB01463846F7F714FC0146404645 -:1094A000F7F708FBC5F804B001462861A8600498E6 -:1094B000F7F708FCF7F7CCFD49494FF4FA62FBF7E0 -:1094C000BFFB34F80930474931339BB2622B335B21 -:1094D00098BF0020184480B2305340F6B83200B232 -:1094E000FBF7AEFB0A226243305355F8141B3E4B88 -:1094F0000234042CD1507FF469AFFFF7DBBB364B4D -:10950000DBF800701B68394CB3F908607B089E4299 -:1095100028BF1E46B4F80090B6B232B20FFA89F3F3 -:109520009A4208DD32492868F7F7CCFBF7F790FD3F -:10953000484486B226802F4BD8F800401B682E4D39 -:10954000C3EB04084046FFF741FA0028D8BF404269 -:1095500041F293139842CCBF00200120002853D041 -:109560004046F7F75BFB2549F7F7ACFB05F066F8DB -:1095700080463846F7F74EFB01464046F7F7A2FB18 -:10958000F7F766FD1E4B80B21880164900B240F610 -:10959000B832FBF755FB48F6A0432044984203DD60 -:1095A000A0F50C40A03804E00028BCBF00F50C403A -:1095B000A030286029E000BF182D4454FB21194039 -:1095C00084120020081200206C120020B01200202B -:1095D000F812002064120020F41200200000F03F76 -:1095E00030F8FFFF48F4FFFFEC100020FC120020D1 -:1095F0000000C842C4120020C8100020D30237392E -:10960000D8100020AC1200202C6028688A4DC0F5CC -:109610000C502830F7F702FB8849F7F753FB044654 -:1096200004F098FF0990204605F008F800240890FF -:1096300030B2F7F7F3FA08AB53F81410F7F742FB20 -:109640007F4B0746185FF7F7E9FA01463846F7F708 -:109650002FFAF7F7FDFCDFF82C9280B24FF47A7204 -:1096600024F80900774900B2FBF7EAFA80B20FFA52 -:1096700080FA754F24F809005046F7F7CFFA396899 -:10968000F7F720FBF7F7E4FCDFF8FC8180B22A460D -:109690003B46D8F8001004905046FFF715FABF6813 -:1096A000844634F909A068680597D8F80070C0EBC3 -:1096B0000A00CDF80CC0F7F7B1FA3946F7F7B6FB58 -:1096C000DFF8C8912861D9F8003083469878F7F719 -:1096D000A1FAF6F7ABFE56A3D3E90023F6F7FAFE9C -:1096E0000B46024659490020F7F71EF8F7F78CF9A8 -:1096F0003946F7F7DFF901463846F7F797FBD5F813 -:109700000880074641465846F7F7D2F901463846E1 -:10971000F7F7D8FA01464046F7F7CCF9DDF80CC068 -:10972000049F01462861A860C5F804A00598674415 -:10973000F7F7C8FAF7F78CFC3844454F80B2E0538E -:10974000444940F6B83200B2FBF77AFA0A22624383 -:10975000385355F8141B404B0234042CD1507FF47D -:1097600067AFD9F800301A7932B13C4A11686422E7 -:1097700091FBF2F13A4A11803A4A1B8812689A42E8 -:109780000ED9394B1868394B1B68C01AFFF71EF900 -:1097900042F210730028B8BF404298427FF78AAA6D -:1097A000334B01221A70334B1A882D4B1A80FFF766 -:1097B00081BAFFF7D9F936E06368052201336360A7 -:1097C00063780133DBB2B3FBF2F202EB82029B1A45 -:1097D0006370FDF751FA284A00231370274AA060EE -:1097E000D37201200BE0FDF747FAA36840F6C412DC -:1097F000C01A904217D9202000F034FB0420FFF754 -:10980000F7F810E09B781E4A522B7FF4DFAAD3783A -:109810004D2B7FF4DBAA1379432B7FF4D7AA0223C5 -:109820000B70FFF7D3BA0BB0BDE8F08FAFF3008039 -:10983000182D4454FB211940EC100020D302373975 -:10984000AC12002018FCFFFFDC1000200000F03FED -:109850006412002048F4FFFF84120020C81000208A -:109860007C200020601200207C120020C412002006 -:10987000C41000203E1200205C2100206F21002037 -:1098800018120020B0120020F8120020F41200205C -:1098900010B500231A460E49002050520D490E4CB7 -:1098A00050520E495052002119511C446060A16071 -:1098B0000B4C023219511C446060A160094C042A0F -:1098C00019511C446060A16003F11403E3D110BD81 -:1098D0004E120020341200201411002064120020C7 -:1098E00084120020EC10002070B504460079F7F7D0 -:1098F00091F91E49F7F79AFA1D4D1E4E2860A07B7C -:10990000F7F788F91949F7F791FAEE60686060791E -:10991000F7F780F91849F7F789FA184D2860E07BC6 -:10992000F7F778F91149F7F781FA6860607EF7F781 -:1099300071F91349F7F77AFAEE60A860A079F7F7A2 -:1099400069F90D49F7F772FA0E4D2860207CF7F798 -:1099500061F90649F7F76AFA6860A07EF7F75AF9E5 -:109960000749F7F763FAEE60A86070BD0000C842CF -:10997000081200200000FA44000020416C12002070 -:1099800000007A44DC1000202DE9F7439946214B72 -:10999000214C18600025C3686570204E06EB051049 -:1099A0004068B046984206D00135EDB2042DF4D996 -:1099B0000023637000E06570194B1A4E002031706F -:1099C0001A60FFF715F8FDF757F933780025AB4219 -:1099D000A06048460CBF012703276560FFF784FF9E -:1099E00066783B4608EB06160095102029467268FB -:1099F00001F084FD0C4B186030B94FF4807003B057 -:109A0000BDE8F043FBF754B8012003B0BDE8F043D4 -:109A1000FEF7EEBF00130020D01200200022010844 -:109A2000F41200204C12002028120020F7B5244B1D -:109A30001D78032D3ED1202001F034FC214E044638 -:109A400038B101F0DDFD336820461969FDF7AEF845 -:109A500009E03368009021461A6920202B4601F066 -:109A60004DFD044640B3184B08221A6110221A61BA -:109A7000164D2868FDF790F850B1134E082777610E -:109A80002868FDF78EF801462046FDF775F8376126 -:109A90002046FDF781F80028EAD00B4E10277761A9 -:109AA00020462D68FDF77DF801462846FDF764F84D -:109AB0003761DDE7022000E0284603B0F0BD00BFBB -:109AC000D012002000130020000C014028120020BA -:109AD000F7B50368174C184D23600B68174E636089 -:109AE0000068FEF791FF95E80300154B019600937F -:109AF00094E80C00FEF7A6FF3668124B60681E6003 -:109B00006B68114FC01AF7F789F8104B1968F7F70F -:109B1000D9F8F7F79DFA22682B687860D31A3B6072 -:109B20000B4B1E600B4B1B68DA880B4B1A8003B083 -:109B3000F0BD00BF44120020442100207C12002010 -:109B400060120020C8100020041300203400002000 -:109B5000C4120020F4120020FC1200202DE9F84F5E -:109B6000484BDFF834A1B3F90000F7F757F846493E -:109B7000F7F7A8F8044604F061FD0746204604F014 -:109B8000E9FCDAF80030064693F80390DFF80C8120 -:109B90003E4DB9F1000F43D03D4CB8F90200B4F886 -:109BA00002B00FFA8BF3C01AFEF710FFC9F10001E3 -:109BB0004A46FBF745F8B4F8009058446080B8F97D -:109BC00000000FFA89F3C01AFEF700FFDAF8003040 -:109BD000DA785142FBF734F848441FFA80F9A4F8C8 -:109BE0000090B4F90200F7F719F880460FFA89F0EF -:109BF000F7F714F8314604464046F7F763F839465C -:109C000081462046F7F75EF801464846F6F750FFD2 -:109C10002049F7F70BF9F7F71BFA288040461DE0BB -:109C2000B8F90200F6F7FAFF8146B8F90000F6F736 -:109C3000F5FF314604464846F7F744F83946804672 -:109C40002046F7F73FF801464046F6F731FF114945 -:109C5000F7F7ECF8F7F7FCF9288048463946F7F7AC -:109C600031F8314607462046F7F72CF801463846CA -:109C7000F6F720FF0749F7F7D9F8F7F7E9F9688011 -:109C8000BDE8F88F8E20002035FA8E3C4E12002061 -:109C90003412002000002041F41200206412002041 -:109CA00038B5244CE37A2546002B3CD0224B1B7858 -:109CB000042B38D9214B9A7A7AB1E379002B37D12A -:109CC00001221F48E2711F4A011D13702372FFF722 -:109CD000FFFE1D4B02221A7038BDDB7AE271BBB168 -:109CE0001A4B1B68588900F0CBF888B1237AFBB96E -:109CF000144A17481370174B01251A685B68011D39 -:109D0000436025720260FFF7E3FE0F4B1D7038BD04 -:109D100000232B720B4B1A7852B901221A70BDE83E -:109D20003840FFF7B5BD084A0023EB712B72137062 -:109D300038BD00BF6F2100205C2100208021002061 -:109D40002821002038000020C4100020F412002038 -:109D50001C21002044210020094B1A68821A002A85 -:109D60000DDB084A1278042A09D900F5123000F5F3 -:109D7000F8701860044BDA6882F01002DA607047FD -:109D8000B41200205C210020000C0140294BF0B5EA -:109D90001D68024600F1100716781446AB19597871 -:109DA000013201F0040101F0FF0369B1BA42F3D1BD -:109DB0000020F0BD1BB103EB83035B00DBB210F8A6 -:109DC000012B303A1344DBB2221A022AF2DC0021C2 -:109DD00084420AD919B101EB81014900C9B210F8D6 -:109DE000012B303A1144C9B2F2E72E2E14D10134BE -:109DF00004200022267802EB8202AF197F785200FD -:109E00007F0792B203D5303A3244013492B201381E -:109E100010F0FF00EED100E0002207480624414385 -:109E2000642000FB02120548B2FBF4F200FB0320A1 -:109E3000F0BD00BFAC01002040420F0080969800AA -:109E4000034B1B6818420CBF00200120704700BF65 -:109E500010130020024B1A6810431860704700BFAF -:109E600010130020024B1A6822EA000018607047A5 -:109E700010130020014B1868704700BF101300201A -:109E8000094BB3F90020002AB8BF5242824209DAD6 -:109E9000B3F90230002BB8BF5B428342ACBF002055 -:109EA00001207047002070479621002010B54478AB -:109EB0000078002303FB03F11939614301F6C41153 -:109EC0005943414340F6C41291FBF2F1034A22F890 -:109ED00013100133072BEDD110BD00BFB6210020B8 -:109EE0002DE9F0478278C6781E4BC2F1640802EB78 -:109EF000820C54425FFA88F84FEA4C0CC6F16409B0 -:109F0000A4B203F11807A5B228B2002804DC002D82 -:109F100014BF1546012500E0454600FB00FA6D43DD -:109F20000AFB06FA9AFBF5F54D4468434FF00A0A1E -:109F300090FBFAF0604480B258800D88B1F802A01E -:109F400000B2C5EB0A0A00FB0AF04FF47A7A90FBE4 -:109F5000FAF0054423F8025F0A34BB42A4B2D2D11E -:109F6000BDE8F0879C210020014B1860704700BFBE -:109F70009C130020074B1B681B7A032B09D8DFE8D2 -:109F800003F00202040600F0F3BB00F037BA00F061 -:109F90001BBB70479C13002008B5037A032B12D813 -:109FA000DFE803F00202070C0A490B4A00F0E8FB65 -:109FB00008E00849084A00F029FA03E00549064A82 -:109FC00000F00AFB28B90820FAF772FD024B0022C4 -:109FD0001A6008BDC421002094130020174B10B54F -:109FE0001860044600236089154A98520233242BD6 -:109FF000F9D1144B08201960FAF7B2FB10B12046D2 -:10A00000FFF7CAFF4FF48030FAF7AAFB20B12046D1 -:10A010000D490E4A00F09AF90120FAF7A1FB28B188 -:10A0200009480A49BDE8104000F09EB94FF40040CD -:10A03000FAF796FB0028F3D110BD00BF9C13002057 -:10A04000C821002090130020C42100209413002078 -:10A05000037A032B09D8DFE803F00202040600F0BC -:10A06000C9BB00F001BA00F0D7BA00207047000069 -:10A0700010B5104C002308202370FAF771FB20B1B3 -:10A080000D4B1868FFF7E4FF20704FF48030FAF7AB -:10A0900067FB10B100F050F9207023784BB14FF4FA -:10A0A0000070FAF75DFB20B1044B1B681B681B684E -:10A0B000984710BD981300209C1300209013002097 -:10A0C000054B1B782BB9054B1B68C01AC043C00F4A -:10A0D00070470120704700BF98130020A013002094 -:10A0E0000E4A0F4B127802F0030202EB800223F8B3 -:10A0F000121003EBC00233F8301053880B449188E0 -:10A10000D2880B441344074A9BB222F810301BB28A -:10A11000042293FBF2F080B2704700BF14130020BA -:10A120002E130020161300202DE9F04740F20120E5 -:10A13000FAF716FB28B1F9F7EDF88246F9F7F6F8C9 -:10A1400001E04FF0010A0026234BF4B21B78A34232 -:10A1500040D9224B224F1B68DFF88C802BB9D8F8EE -:10A1600000305B8927F8143032E0D8F80020072C43 -:10A1700094BF12F80490A1461748494698470546EF -:10A180004FF40070FAF7ECFA48B1BAF1000F06D0BC -:10A19000144B48461B6829461B68DB699847A5F2A3 -:10A1A000EE2240F2DC5392B29A4288BFD8F80030D7 -:10A1B00048F2010088BF5D89FAF7D2FA10B927F892 -:10A1C000145005E020462946FFF78AFF27F81400BF -:10A1D0000136B9E7BDE8F087C421002094130020C0 -:10A1E000C8210020901300209C13002010B5064CBD -:10A1F000237843B1054B1B681B681B689847FFF722 -:10A2000093FF0023237010BD9813002090130020AB -:10A21000024B1A7801321A70FFF786BF1413002020 -:10A2200008B500F59C400D4B203018604FF40070CD -:10A23000FAF796FA20B10A4B1B681B681B6998470E -:10A2400048F20100FAF78CFA18B9BDE80840FFF7A8 -:10A25000CDBFBDE80840FFF7DBBF00BFA013002063 -:10A2600090130020F8B505460F46441E14F8011F50 -:10A2700049B1054E304606F0E1FD0028F6D0861BB8 -:10A28000631BBB55F2E7F8BD5022010810B51F4B08 -:10A290001A681C46127C3AB123681B7C5BB11C4ACD -:10A2A000013B32F813001BE04FF40030FAF758FA84 -:10A2B0000028F1D110BD4FF40030FAF751FA78B10F -:10A2C000F8F7FAFF114B80B21B685B7C012B07D1BA -:10A2D00003B2B3F57A7FC8BF002000F57A7080B270 -:10A2E00000B24FF47A720021A0F57A70FAF7A8FC58 -:10A2F000F6F794FC0749F6F799FD0749F6F7E2FCF3 -:10A30000F6F7CCFE054B188010BD00BF9C13002053 -:10A31000C821002000007A4400C07F44C6210020EC -:10A32000014B33F811007047C8210020014B012276 -:10A330001A707047A4130020034B187810B1002244 -:10A340001A700120704700BFA413002008230B706F -:10A350000AB1024B13600120704700BF21A300081F -:10A360000846F9F78FB80000084B10B50B6004469B -:10A370004FF40040FAF7F4F908B1082323700120E4 -:10A38000FAF7EEF908B10C23237010BD61A30008A1 -:10A39000034B53F82100400800F5777080B27047F6 -:10A3A000B013002038B50446FCF74CFC0F4B40F6C8 -:10A3B000C4111A681860821A8A420D4A84BF0021AB -:10A3C000117013780BB90F2C0FD10A4800210170BE -:10A3D0004BB1094D182B1D4405F8014C03D1012345 -:10A3E0001170037038BD0133137038BDA8130020FD -:10A3F000AC130020AD130020E0130020024B43609B -:10A400008360032343737047A0860100F7B50025DE -:10A41000074605230E4614460E49009508200E4AAD -:10A4200001F06CF879890D4BA1F57771186049003E -:10A430002B460B4A99500433302BFAD10CB1094BFF -:10A44000236000304FF00C0318BF0120337003B0BD -:10A45000F0BD00BFA5A30008A0860100FC130020EA -:10A46000B013002091A30008344B10B51A780AB934 -:10A47000002010BD00221A70314B9A7D1207F7D4CC -:10A48000587819782F4A00F0070441EA0421116036 -:10A49000997801F03F04640144EAD0005060D87814 -:10A4A000800040EA9110197901F0010440EA84200B -:10A4B0009060587900F00F04E40144EA5101D16042 -:10A4C000997901F07F04240144EA10101061D879D1 -:10A4D000400040EAD111187A00F0030441EA442117 -:10A4E0005161597A01F01F04A40144EA900090617F -:10A4F000987AC00040EA5111187BD161D97A00F0F6 -:10A50000070441EA04211162597B01F03F04640110 -:10A5100044EAD0005062987B800040EA9110D97BD9 -:10A520001B7C01F0010403F00F03DB0140EA8420EF -:10A5300043EA51019062D162012010BDAD130020A9 -:10A54000E0130020B0130020024B53F82100C0F3A9 -:10A55000CF0070473014002010B50446FCF772FBA2 -:10A56000144B1A681860821AB2F57A6F124A84BFC7 -:10A5700000211170137823B9A82C1AD10F490B7040 -:10A5800006E0022B02D10E490C7001E0242B01D809 -:10A590000C49CC540133DBB21370094A12785200D3 -:10A5A0000532934205D1044B00221A70034B01225D -:10A5B0001A7010BD00140020701400202A1400200E -:10A5C00004140020051400204FF4E133436083603D -:10A5D000012343737047000037B5002300930D46F5 -:10A5E00001231446082009494FF4E13200F086FFA8 -:10A5F000074B18600CB1074B236000304FF010037D -:10A6000018BF01202B7003B030BD00BF59A5000852 -:10A610002C14002049A50008134B10B51A780AB96C -:10A62000002010BD00221A70104B5B78012BF7D16F -:10A630000F4B1A78102A84BF10221A700D4A19780D -:10A640000023D8B2884202F102020AD212F8010CA9 -:10A6500012F8024C40EA0424074840F82340013332 -:10A66000EFE7012010BD00BF2A14002005140020D0 -:10A67000041400200814002030140020114B10B5E1 -:10A6800001221A700446FCF7DDFA0F4A01461368EE -:10A690001160C31A0D4841F28832934203600C4B9B -:10A6A00084BF00221A701B780A4AE4B20F2BD454DC -:10A6B00003D1094B01221A7010BD054A01331370F2 -:10A6C00010BD00BFAC140020C4140020741400207E -:10A6D00078140020AF140020721400202DE9F041FE -:10A6E0001C4B04781A781D46FAB11B4B1E781B4B85 -:10A6F0001F7802231A4803F10108C25C324102F0BC -:10A700000F02A2420CD20B2A0AD810F803C010F88C -:10A7100008000CEA070C00EB0C2C124840F822C091 -:10A720000233102BE6D100232B708C420ED90E4B36 -:10A73000187860B10D4B1A780A4B53F8210002B11A -:10A74000400800F5777080B2BDE8F0810020BDE8D8 -:10A75000F08100BF7214002071140020AE1400209C -:10A76000AF1400207C140020AC140020AD14002095 -:10A770004FF4E1334360836001234373704700006B -:10A7800013B5037A14465BB1012B13D1134A03208E -:10A790001070134A07201070124A13700C2308E03F -:10A7A0000E4A022010700E4A032010700D4A1370DA -:10A7B00007230B7000230093082001230A494FF45C -:10A7C000E13200F09BFE094B18600CB1084B23608E -:10A7D000003018BF012002B010BD00BF711400206E -:10A7E000AE140020AD1400207DA60008C014002087 -:10A7F000DDA60008014B1878704700BF72140020D6 -:10A80000014B1860704700BFCC140020034B1B683D -:10A810001878D0F1010038BF00207047CC14002018 -:10A82000034B1B681878431E58425841704700BFBD -:10A83000CC140020034B1B681878831E58425841E3 -:10A84000704700BFCC14002008B54FF40060F9F742 -:10A8500087FF20B10420BDE8084000F007BE08BD16 -:10A86000084B1B7863B1084B1B685B7813B1074B2F -:10A87000187D01E0064B9878003018BF0120704722 -:10A8800001207047C8140020CC1400208021002033 -:10A890006F21002008B5FFF7B9FF18B1BDE80840E7 -:10A8A00000F082BAFFF7BCFF18B1BDE8084000F025 -:10A8B0004DBC08BD08B5FFF7A9FF08B100F0B0F81E -:10A8C000FFF7AEFF18B1BDE8084000F015BB08BDAA -:10A8D00038B50D4B1B78B3B1FFF7C2FF0B4B0446E5 -:10A8E0001A781D4682420ED050B1FFF78FFF08B193 -:10A8F00000F0AEF8FFF794FF20B100F03DFB01E05F -:10A90000FFF7D8FF2C7038BDD0140020C9140020E8 -:10A9100008B50121042000F0B5FD0F4B1870FFF7BA -:10A9200093FF0E4B1870FFF771FF18B10C4B1868AE -:10A9300000F070F8FFF774FF18B1094B186800F0C9 -:10A94000F3FAFFF777FF18B1054B186800F001FC28 -:10A95000BDE80840FFF7BCBFC8140020D014002099 -:10A96000CC14002008B50C4B1B789BB1FFF778FF87 -:10A9700080B1FFF74BFF08B100F0ACF8FFF750FFD4 -:10A9800008B100F02BFBFFF755FF18B1BDE80840F8 -:10A9900000F0E0BB08BD00BFD014002038B5064C65 -:10A9A00005465E212068FCF7E7F820682946BDE8E7 -:10A9B0003840FCF7E1B800BFE8140020024B5E21EC -:10A9C0001868FCF7D9B800BFE814002010B50A4C8D -:10A9D0005E280146206805D15D21FCF7CDF820688E -:10A9E0003E2105E05D2903D1FCF7C6F820683D2132 -:10A9F000BDE81040FCF7C0B8E814002010B50446CC -:10AA0000C0B2FFF7E3FFC4F30720BDE81040FFF733 -:10AA1000DDBF0000014B1860704700BFDC14002050 -:10AA200010B5084B084C19782068FCF7C9F8074B9B -:10AA300020681968FCF7BAF820680421BDE81040C6 -:10AA400000F05CBCD9140020E8140020D4140020CD -:10AA500073B5042000F026FC144C01462060144E0F -:10AA6000144D90B143794FF41651337083682B60C5 -:10AA7000FCF79CF820680221FCF7A2F8206804216A -:10AA800002B0BDE8704000F029BC0B4B4FF41652E9 -:10AA90001B6804209B780093022300F02FFD43796C -:10AAA0002060337083682B6002B070BDE814002012 -:10AAB000D9140020D4140020DC14002008B5044B65 -:10AAC0001868FCF769F8D0F1010038BF002008BD14 -:10AAD000E81400202DE9F843FFF7F0FF002800F00C -:10AAE0004481FCF7C9F8A24B1A68821A7C2A40F20A -:10AAF0003C81A04E1860337800240133337004F198 -:10AB00002400C0B2FFF74AFF9B4B33F91400F6F75D -:10AB100085F89A4B05461888F6F780F801462846CE -:10AB2000F6F784F99649F6F7CDF8F6F791FA01347D -:10AB300000B2FFF763FF032CE1D13020FFF72EFFB7 -:10AB4000904BB3F90000FFF759FFFFF737FF30785C -:10AB500010F0030729D18C4D1020FFF71FFF2B6841 -:10AB6000642493FBF4F000B2FFF748FF2120FFF7C5 -:10AB700015FF2B6893FBF4F004FB103484EAE470B7 -:10AB8000A0EBE47000B2FFF739FF1420FFF706FFD7 -:10AB90007E4BB3F90000FFF731FF1C20FFF7FEFEEC -:10ABA0003846FFF72BFFFFF709FF33785B0740F0CC -:10ABB000B6800220FFF7F2FE754B0A25B3F90000BC -:10ABC00090FBF5F0FFF71AFF0220F9F7C9FD002806 -:10ABD0004CD0DFF8CC816F4F98F800303A7840F6CF -:10ABE0003401B2FBF3F24A436B4C2A21B2FBF1F27F -:10ABF0002188062091FBF3F903FB19194FEA091983 -:10AC00001FFA89F949EA02291FFA89F9C2F30322D6 -:10AC100049EA0209FFF7C2FE0FFA89F0FFF7EEFEDC -:10AC2000228898F80030013292B292FBF3F103FBD4 -:10AC3000112323803B786E245C43152394FBF3F4AB -:10AC40003A204FF06408FFF7A9FEB4FBF8F708FBC1 -:10AC500017443846A4B2FFF7D1FE05343B20FFF776 -:10AC60009DFE94FBF5F000B2FFF7C8FE2020FFF731 -:10AC7000E7F8002851D0494C1320FFF78FFE2368D6 -:10AC8000DFF82081002BB8BF5B4293FBF8F000B2E5 -:10AC9000FFF7B4FE1B20FFF781FE23680A27002B75 -:10ACA000B8BF5B4293FBF7F342F2107593FBF5F2EA -:10ACB00005FB123000B2FFF7A1FE2320FFF76EFE66 -:10ACC0002368002BACBF4E205320FFF797FE1220C5 -:10ACD000FFF764FE6368002BB8BF5B4293FBF8F09C -:10ACE00000B2FFF78BFE1A20FFF758FE6368002BB7 -:10ACF000B8BF5B4293FBF7F797FBF5F305FB1370C7 -:10AD000000B2FFF77BFE2220FFF748FE6368002BAE -:10AD1000ACBF45205720FFF771FEFFF74FFE337899 -:10AD2000282B22D1134B00221A70FBF7A5FF4FF4FA -:10AD30007A763C24B0FBF6F61720FFF72FFEB6FB21 -:10AD4000F4F5B5FBF4F004FB1050000200B2FFF77D -:10AD500055FE1820FFF722FE04FB156000B2FFF736 -:10AD60004DFEBDE8F843FFF729BEBDE8F88300BFFC -:10AD7000E0140020D8140020B82000201200002089 -:10AD800000007A44700F0020740D00208E200020F7 -:10AD90002C200020E41A0020E4140020442100208C -:10ADA00010000020A08601004FF4165070470000EC -:10ADB00010B5054C2068FBF7EFFE18B12068FBF7D3 -:10ADC000F0FEF6E710BD00BF2C150020DFF890C0A4 -:10ADD0002DE9F043204E91FBFCF406FB04180627F6 -:10ADE000C90F07FB08F8417292FBFCF106FB012634 -:10ADF0001A4B04EB840498FBF3F903FB19887E4398 -:10AE00004FFA89F904EB840409EB8404A4B2847238 -:10AE1000240AC47296FBF3F403FB146301EB810173 -:10AE200064B201EB8101642504EB810198FBF5F824 -:10AE300093FBF5F389B280F80C80D20F4FEA2828F3 -:10AE4000C1734374090A1B1280F80D808273017468 -:10AE50008374BDE8F08300BF806967FF40420F0044 -:10AE60008096980010B5174B174A1B78D27A044683 -:10AE7000837612B92D23C37610BD042B8CBF3323E8 -:10AE80003223C376114B93E80600FFF79FFF104B68 -:10AE90001A886423B2FBF3F303EBC3039B009BB25A -:10AEA000E3711B0A23720B4B1B88E3741B0A237587 -:10AEB000094B1B8863751B0AA375084B1B882377F6 -:10AEC00010BD00BF5C2100206F2100204421002024 -:10AED0001A210020242100201621002030210020EA -:10AEE000044A00231278837003718277C377027556 -:10AEF00043757047E41A002010B5084B084C1978C8 -:10AF00002068FBF75DFE074B20681968FBF74EFED3 -:10AF100020680421BDE8104000F0F0B9321500208F -:10AF20002C1500201C150020F8B5104C104B2C27B8 -:10AF30001860002120463A4605F062FC8E236370BB -:10AF40007C26E0237D25E370267084F82B50094C85 -:10AF5000002120463A4605F053FC8A236370A02363 -:10AF60002670E37084F82B50F8BD00BFED1400206C -:10AF7000381500204015002073B5042000F092F928 -:10AF8000134C01462060134E134D90B143794FF49A -:10AF90009641337083682B60FBF708FE206801211F -:10AFA000FBF70EFE2068042102B0BDE8704000F0FF -:10AFB00095B900904FF496420123042000F09EFAC8 -:10AFC00043792060337083682B6002B070BD00BF8E -:10AFD0002C150020321500201C1500202DE9F84307 -:10AFE000FBF730FE4C4D4D4A2B680446C31A934282 -:10AFF00006D94B48FFF774FF4A48FFF733FF2C6030 -:10B00000494E4A4F96F80090B9F1000F0ED1DFF883 -:10B010002881D8F80000FBF7BFFD012806D90228D7 -:10B02000434D46D0FFF7C4FE01232B703D68DFF887 -:10B03000FCC0002D6ED037783B4A3E4E3FB133689E -:10B0400040F6B731E31A8B420BD8BDE8F8830123F1 -:10B050001370394B02211868FBF7B2FD374B1F7094 -:10B0600024E0374F34483B784BB900680121CCF8D5 -:10B0700000301370FBF7A4FDFFF79AFE16E0013BCA -:10B08000D9B239702D4A2F4B19B911784D1C157052 -:10B0900006E015F8011B1778CCF800500F44177024 -:10B0A0001A78006801321A70FBF766FD3460BDE85B -:10B0B000F8832A78244B1AB11C6085F80090B5E714 -:10B0C0001B68E31AB3F57A6FB0D30123D8F80000F8 -:10B0D0002B70FBF766FD0546D8F80000FBF761FD15 -:10B0E000802DA3D18A2802D08E280AD09EE7202066 -:10B0F000FEF7A6FE002899D03378002B96D1094B95 -:10B1000003E03378002B91D1054B3B600C4B2D2293 -:10B110001A708BE7BDE8F883241500203F0D03006B -:10B12000ED14002040150020281500203C150020BB -:10B1300039000020201500202C150020EC140020E0 -:10B140003115002030150020341500204FF49640B2 -:10B150007047704702F0E0B810B500230C245C4340 -:10B160000549DAB2615C814203D00133042BF5D189 -:10B170001A46104610BD00BF3C000020037A002292 -:10B18000D0B2013213B1581E0340F9E70A7AD9B29E -:10B19000013312B1511E0A40F9E7884294BF0020E2 -:10B1A00001207047004870476C00002000230549CB -:10B1B000DAB2595C814203D00133092BF7D11A4628 -:10B1C00010467047592201082DE9F74F137C81463C -:10B1D0000E461446032B40D80C225A43214903F152 -:10B1E000010A01EB020898F8080019EA000F31D0B3 -:10B1F0008B5C43B1012B06D0022B04D0032B14BF70 -:10B200000425032500E01D46174B4FEA051B40208F -:10B2100003EB0B070193F9F7A3FA019B20B913F88D -:10B220000B30023B012B15D9737B13B13A7B1342D0 -:10B2300010D071687A6891420CD3B168BA689142B3 -:10B2400008D82570A760C4F80480E66084F810A0D0 -:10B25000204603E05FFA8AF3BCE7002003B0BDE8B4 -:10B26000F08F00BF3C0000206422010870B50A4C3A -:10B2700006460D4620460021142205F0C1FA074873 -:10B2800004210C22064B05F005FB304629462246D8 -:10B29000BDE87040FFF798BF6C1500203C0000200F -:10B2A0007DB100080B4AA2F13003197A81420BD01C -:10B2B0000C339342F9D1084B197A014004D10C3375 -:10B2C0009342F9D1084670470BB158687047184649 -:10B2D000704700BF6C0000203C00002010B5002328 -:10B2E000054A1A445468844203D00C33302BF7D1FA -:10B2F0000022517210BD00BF3C0000200023064A0E -:10B300001A445168814203D00C33302BF7D100220C -:10B3100000235372704700BF3C00002038B5002264 -:10B3200005461D491301585CA84204D00132062A83 -:10B33000F7D1002038BD194C0B44042D0FCB84E805 -:10B340000F001BD007D8012D0FD0022D21D1144B97 -:10B350001B689B6810E0102D15D0202D09D0082DFA -:10B3600017D12046FEF706FE11E00D4B1B685B6807 -:10B370000CE00B4B1B681B69636007E0FFF78AFA60 -:10B380006060A06003E0064B1B68DB68A36020469A -:10B3900038BD024838BD00BFA42201089415002022 -:10B3A00090150020214B10B518600120FFF7B6FF63 -:10B3B00001460120FFF75AFF08B9002010BD022006 -:10B3C000FFF7ACFF01460220FFF750FF0028F4D042 -:10B3D0001020FFF7A3FF01461020FFF747FF0446A8 -:10B3E0004FF48070F9F7BCF908B1002CE5D00820C3 -:10B3F000FFF794FF01460820FFF738FF04460820B6 -:10B40000F9F7AEF908B1002CD7D00420FFF786FF7A -:10B4100001460420FFF72AFF04464FF40060F9F7C5 -:10B420009FF908B10CB9C8E7012010BD90150020A4 -:10B4300070B50E4600240C4D0023605DE95CEA18EF -:10B44000814203D01033602BF8D100221146FFF760 -:10B450000DFF83681B78B34204D01034602CEAD10E -:10B46000002070BD012070BDA422010810B5044663 -:10B47000FFF754FF01462046FFF7F8FE003018BFE3 -:10B48000012010BD38B505460C46FFF747FF0146C1 -:10B490002846FFF7EBFE28B143681B7A1C420CBF1D -:10B4A0000020012038BD0000F8B505460020FFF758 -:10B4B00053FE104E0C272B780F4C07FB0060E35C0B -:10B4C00003720120FFF748FE6B7807FB0060E35C26 -:10B4D00003720220FFF740FEAB7807FB0060E35CDD -:10B4E00003720320FFF738FEEB7807FB0060E35C94 -:10B4F0000372F8BD3C000020592201082DE9F04FED -:10B5000087B0984682460F4616469DF84040FFF7A2 -:10B5100005FF0DF1080E0546034600F1100C1868F2 -:10B520005968724603C2083363459646F7D12B7BB0 -:10B530000BB903960496504602A9FFF797FE0546FD -:10B5400040B14368586830B1504602A92A46FFF717 -:10B550003BFEF4E730E0AB6895F800B093F800905C -:10B56000B9F1030F28D8DFE809F002050E100094A6 -:10B57000134801E013480094394632464346F8F731 -:10B580000FFA04460BE0002000E001203946234674 -:10B590003246F7F7F3FF41460446FBF711FB54B17F -:10B5A000094B84F8049043F82B406B6820465C609C -:10B5B0005146FFF793FE204607B0BDE8F08F00BF6D -:10B5C00000380140004400408015002038B5064C8A -:10B5D00005462060FFF768FF284601F093FD2068CC -:10B5E000BDE8384000F0E6BE90150020034B1B7804 -:10B5F0000BB100F0E7BD01F01BBE00BFA415002099 -:10B6000010B504462046FBF7D6FA18B90A20FBF716 -:10B6100044FBF7E710BD0000232801D100F0D2BDA4 -:10B62000044B1B681B7D834202D10120FBF7F4BB56 -:10B63000704700BF9015002010B5441E14F8011F7C -:10B6400021B1034B1868FBF797FAF7E710BD00BF6D -:10B65000DC1500200148FFF7EFBF00BF9024010870 -:10B6600010B50748FFF7E8FF0024064B06481A19F3 -:10B67000E15852680C34F9F723FCC02CF5D110BD09 -:10B68000CE240108AC230108E424010870B5FBF7BF -:10B69000F3FA244B4FF47A711A78234BB0FBF1F193 -:10B6A0001B782248F9F70CFCFEF7E4FB204B05461B -:10B6B0001968204B2048B1FBF3F1F9F701FC002495 -:10B6C0001E4AE3B252F8231049B1012202FA03F3F1 -:10B6D0002B4202D01A48F9F7F3FB0134F0E70220BD -:10B6E000FEF7AEFB68B1174B17481A78174B53F8A3 -:10B6F0002210F9F7E5FB164B197A11B11548F9F745 -:10B70000DFFB1548FFF798FF144B1C88F7F75EF92D -:10B71000214602464FF488631148BDE87040F9F7AE -:10B72000CFBB00BFE41A002010000020EC24010869 -:10B730009001002040420F002A250108983301089B -:10B7400048250108540D00204C2501086C240108EF -:10B750003820002056250108BC2701081E0D0020B6 -:10B760005A25010838B50C680546204605F03EFC10 -:10B77000214602462868BDE8384005F067BC000055 -:10B7800037B5037904460D46052B34D8DFE803F0BE -:10B7900003060A0D1114836819782DE0836893F964 -:10B7A000001029E08368198826E08368B3F9001047 -:10B7B00022E0836819681FE0836869461868F9F712 -:10B7C0006DFC01461248F9F77BFBF5B1E068F5F72F -:10B7D00025FA6946F9F762FC01460E48F9F770FB55 -:10B7E0002069F5F71BFA6946F9F758FC0146094844 -:10B7F000F9F766FB09E000210748F9F761FB25B17D -:10B800000648E1682269F9F75BFB03B030BD00BF71 -:10B810005325010852250108902501088C250108AF -:10B8200008B50648FFF708FF054B1868FFF7E8FE64 -:10B83000BDE808400020FBF7EFBA00BF93250108E0 -:10B84000DC15002008B50748FFF7F6FE064B93F815 -:10B850003C04F8F71FFFF8F72DFFBDE80840FFF79D -:10B86000DFBF00BFA2250108E81A00207FB504460B -:10B8700005F0BCFB082825D100231F49E25C0968BC -:10B880001144497801F00301022908BF203AE2542B -:10B890000133082BF1D10025665D1848314605F0CB -:10B8A000CDFA28B101356019314605F0C7FA18B153 -:10B8B0001348FFF7C1FE1DE0082DEDD120461149C8 -:10B8C000FEF7D0FC1048FFF7B7FE00230F4A04A98B -:10B8D0001A4492F808210A440849595C0133082B9C -:10B8E00002F80C1CF2D10023094801A98DF80C3094 -:10B8F000F9F7E6FA04B070BDAC010020502201084F -:10B90000AC250108F01B0020CC250108E81A002016 -:10B91000E724010808B5FEF789F8022802D00328B9 -:10B9200000D008BD0248BDE80840FFF785BE00BF53 -:10B93000E12501082DE9F041054605F057FB0446D5 -:10B94000F9F778F906468CB92948FFF775FE294BB7 -:10B9500053F8241041B10123A340334202D02648BA -:10B96000F9F7AEFA0134F2E7244821E028462449E9 -:10B97000224605F06BFB58B92248FFF75DFE224CCA -:10B9800054F8041F0029EFD01B48F9F799FAF7E79C -:10B990002B7800262D2B03BF013504F1FF344FF027 -:10B9A00001084FF00008134B53F8267027B91748C9 -:10B9B000BDE8F041FFF740BE28463946224605F073 -:10B9C00045FB98B90120B040B8F1000F03D0F9F75A -:10B9D0006FF80F4802E0F8F7CDFE0E48FFF72CFE97 -:10B9E00039460D48BDE8F041F9F76ABA0136DAE7A1 -:10B9F000072601080423010848250108BC2701087F -:10BA0000763101081A260108002301082F260108B3 -:10BA10004926010853260108E724010810B5044609 -:10BA20000848FFF709FE084A00231370074A13600D -:10BA3000074A1370FCF77AFB2046BDE81040FFF779 -:10BA400001BF00BF5C260108A5150020D815002005 -:10BA5000A415002008B50448FFF7EEFDF8F792FEA4 -:10BA6000BDE80840FFF7DCBE742601082DE9F0436D -:10BA700089B0044605F0BAFAC6B2002E6CD17B48F4 -:10BA8000FFF7DAFD7A4C20690021F5F7AFFA40BBE9 -:10BA9000013678483146F9F713FA206904A9F9F715 -:10BAA000FDFA01467448F9F70BFA606904A9F9F741 -:10BAB000F5FA01467048F9F703FAA06904A9F9F705 -:10BAC000EDFA01466C48F9F7FBF9E06904A9F9F7CA -:10BAD000E5FA01466948F9F7F3F90C2E04F1100470 -:10BAE000D1D10025664C2F462B464FF00008B045BB -:10BAF00004F1100415DA184654F8101CF4F7DAFFB4 -:10BB000054F80C1C81462846F4F7D4FF54F8081C5E -:10BB100005463846F4F7CEFF08F101084B460746C4 -:10BB2000E5E75848019302950397FFF785FD002448 -:10BB300001ABE058544920F00040F5F77FFA534B31 -:10BB4000534A0434002814BF10461846FFF774FD0A -:10BB50000C2CEDD14F4871E020464F49052205F0ED -:10BB600075FA38B9424B002203441030C0281A61DC -:10BB7000F8D177E020464949042205F067FA0546E6 -:10BB800020460DBB202105F059F900286AD0461C3B -:10BB9000304605F02BFA2C460746414B53F824500B -:10BBA0000DB940484AE030462946FAB205F04EFA4F -:10BBB00040B920463C49FCF759FB3C482946F9F777 -:10BBC0007FF947E00134E8E704F0C6FD461E0B2E7E -:10BBD000074643DC2046202105F030F9054640B1F8 -:10BBE000451C2846F9F7C2FA214B3F01D8510124E0 -:10BBF00000E004462846202105F020F9054640B122 -:10BC0000451C2846F9F7B2FA194B013403EB061329 -:10BC100058612846202105F011F9054640B1451C20 -:10BC20002846F9F7A3FA124B013403EB0613986187 -:10BC30002846202105F002F918B91D48FFF7FCFC41 -:10BC400010E00130F9F792FA094B032C03EB0616CA -:10BC5000F061F2D11748FFF709FF03E016480C2105 -:10BC6000F9F72EF909B0BDE8F08300BF9526010869 -:10BC7000E81A0020C0260108C6260108E7240108AA -:10BC8000FC1A0020CA2601080AD7233C9126010885 -:10BC90008D260108BC270108D9260108DF260108E6 -:10BCA00050230108E4260108F81A0020FC260108A8 -:10BCB0000F270108FB29010849270108F8B50746A5 -:10BCC00005F094F9044638B91A4B1B485A791B4BB6 -:10BCD000013A53F8221028E038461949224605F067 -:10BCE000B5F960B91748FFF7A7FC174C54F8041FC3 -:10BCF00019B11648F9F7E4F8F8E7154805E000250A -:10BD00000E4B53F8256026B91248BDE8F840FFF7FE -:10BD100093BC38463146224605F098F90135002893 -:10BD2000EED1044B0C485D713146BDE8F840F9F79F -:10BD3000C7B800BFE81A0020712701085023010886 -:10BD400076310108852701084C23010848250108A0 -:10BD5000BC270108E4260108982701082DE9F047CF -:10BD6000074605F043F94D4D064620B1012818D18C -:10BD70003B782A2B15D14A48FFF75EFC002429594D -:10BD80004848F9F79DF828193146FFF7F9FC46486D -:10BD9000FFF752FC143440F6EC139C42EFD1BDE89F -:10BDA000F08738463D2105F049F800285BD0441C57 -:10BDB000204604F0D1FC82462046F9F7D7F900244A -:10BDC00006464FF0140909FB04F955F8098040466E -:10BDD00005F00CF941460246384605F037F90028CF -:10BDE00039D12E4F4F44F868F4F718FF014630461A -:10BDF000F5F71AF900282CD03869F4F70FFF01463F -:10BE00003046F5F707F920B33B79052B4FF01403C3 -:10BE100003FB0454227918BF5646052A0FD8DFE8E1 -:10BE200002F003030606090CA268167007E0A26878 -:10BE3000168004E0A268166001E0A3681E60414617 -:10BE40001A48F9F73DF820460021BDE8F047FFF712 -:10BE500097BC174803E001347F2CB2D11548BDE8E8 -:10BE6000F047FFF7E9BB04462E593946304605F046 -:10BE70009BFA58B10B483146F9F722F807480021E0 -:10BE80002044FFF77DFC0848F9F71AF8143440F60F -:10BE9000EC139C42E8D1BDE8F08700BFB83301083D -:10BEA000AA27010884290108BC270108BF27010827 -:10BEB000CA270108EF27010810B50446204605F0FF -:10BEC00095F810F0FF0F07D10B4B0C4893F83C147A -:10BED000BDE81040F8F7F4BF204604F03DFC02280E -:10BEE00008D8054B064C83F83C04F8F7E3FBF8F759 -:10BEF0005BFEE3E710BD00BFE81A00200C28010834 -:10BF0000FB29010870B5044605F070F808B920480F -:10BF100030E020461F4905F047FB00242646254611 -:10BF200078B12CB1012C06D104F016FC064602E0D3 -:10BF300004F012FC054617490020013405F034FBDB -:10BF4000EEE70B2D05D9BDE8704013480C21F8F73A -:10BF5000B7BF012C08DC114B294633F915201048D6 -:10BF6000BDE87040F8F7ACBFA6F57A73B3F57A7FF9 -:10BF700004D90C48BDE87040F8F7A2BF0A4829462A -:10BF80003246F8F79DFF054B23F8156070BD00BFE2 -:10BF900022280108C52901085C280108EC2000209E -:10BFA000822801089A280108BC28010838B50546EE -:10BFB00005F01CF8C0B268B90446124B214603EBE9 -:10BFC00044031148B3F876200134F8F779FF152CB3 -:10BFD000F3D138BD284604F0BFFB142804460BDC1F -:10BFE0002021284604F02AFF04F0B6FB054B03EBA2 -:10BFF0004404A4F8760038BD04481521BDE8384053 -:10C00000F8F75EBF281F0020D5280108E1280108A5 -:10C010002DE9FF47584C5948F8F752FF5848FFF7A9 -:10C02000C5FF6279574B013A53F822105648F8F78A -:10C0300047FF20690021F4F7D9FF274600285AD18D -:10C040000546266900213046F4F7D0FF00284ED17E -:10C0500001354E482946D4F814A0D4F81890D4F8E5 -:10C060001C80F8F72DFF30460021F4F7C9FF10B10E -:10C070004748F8F725FF69463046F9F70FF80146BB -:10C080004448F8F71DFF50460021F4F7B9FF10B1FE -:10C090003F48F8F715FF69465046F8F7FFFF01469D -:10C0A0003C48F8F70DFF48460021F4F7A9FF10B10E -:10C0B0003748F8F705FF69464846F8F7EFFF0146AD -:10C0C0003448F8F7FDFE40460021F4F799FF10B11F -:10C0D0002F48F8F7F5FE69464046F8F7DFFF0146BE -:10C0E0002D48F8F7EDFE0C2D04F11004A9D12B48D2 -:10C0F000691CF8F7E5FEF8F79DFD294C054654F854 -:10C10000041F19B12748F8F7DBFEF8E70C46264B69 -:10C1100053F8241041B10123A3402B4202D02348FD -:10C12000F8F7CEFE0134F2E7CB1993F8083104AAF0 -:10C1300013441F4A8A5C0131082903F8102CF3D1FB -:10C1400000241C4869468DF80840F8F7B9FE1A4DDE -:10C150001A486159F8F7B4FE28190021FFF710FBBF -:10C160001748FFF769FA143440F6EC139C42EED1FD -:10C1700004B0BDE8F08700BFE81A002007290108D5 -:10C18000FB29010850230108372901084229010829 -:10C19000C529010853250108E72401084A29010897 -:10C1A000002301085C290108042301086A29010809 -:10C1B0005022010877290108B833010880290108B5 -:10C1C000BC2701082DE9F0476C4B86B01A789946D8 -:10C1D0006B4F7AB901233868022189F80030FFF7E4 -:10C1E0007DF83868F8F798FE6648FFF725FA664844 -:10C1F000FFF722FA3868FAF7CFFC002800F0BB807E -:10C200005F4B624C1868FAF7CCFC0928014601D054 -:10C210003F2852D14FF00008D4F800A05C4E4546AC -:10C22000BAF1000F05D05B483168524604F00EFFAA -:10C2300010B9B04605B93546574B0C369E42EFD380 -:10C24000CDB1D5F800E0D8F800C053461EF8036021 -:10C250001CF80300B04201D023600CE05A1C4D4989 -:10C2600030B92D2B04D82026CE542260885402E009 -:10C27000CE541346EAE723681BB1454501D1554624 -:10C2800011E04648FFF7D8F9454508D855F80C0B9A -:10C29000FFF7D2F938680921FAF76EFCF4E73A485B -:10C2A000FFF7CAF9002523689D42A3D2394B3868AD -:10C2B000595DFAF761FC0135F5E723682BB90428CD -:10C2C00036D13448FFF7AAFB55E00C2801D1344899 -:10C2D0008BE70A2901D00D2944D13248FFF7ACF988 -:10C2E0002C4D22680023AB5404932F4B03A80093DA -:10C2F000274910220C23039504F032FA064638B180 -:10C30000006804F073FE0130B3682844984702E0E7 -:10C310002648FFF791F91F480021302204F070FAF7 -:10C320000023236099F80030002B7FF460AF22E0F7 -:10C330000C28CCD07F2903D15CE72F2B3FF65AAFD6 -:10C34000A1F12002D2B25E2A3FF654AF13B92029E0 -:10C350003FF450AF5A1C22600E4A3868D154FAF7A5 -:10C360000BFC47E77F29E8D10A4A013B0021236003 -:10C37000D1540F483CE706B0BDE8F087A415002073 -:10C38000DC1500208A290108C2290108D8150020DF -:10C39000AC230108A51500206C240108C729010859 -:10C3A000CC290108BC27010865B70008D729010876 -:10C3B000F829010837B505460220FEF773FF064C41 -:10C3C0000146206030B90090AA6802200323FFF7DD -:10C3D00095F8206003B030BDDC150020F8B5154E8F -:10C3E000154C164D0746C1B230682170FAF7C4FBF0 -:10C3F00022782B78C7F30721534030682B702170C7 -:10C40000FAF7BAFB22782B78C7F30741534030681C -:10C410002B702170FAF7B0FB22782B78390E53403D -:10C4200030682B702170FAF7A7FB2B7822785340E5 -:10C430002B70F8BDE8150020E11500204216002001 -:10C44000F8B50C4E0C4D0D4CC1B207463068297042 -:10C45000FAF792FB2A782378C7F307215340306814 -:10C4600023702970FAF788FB23782A7853402370C9 -:10C47000F8BD00BFE8150020E0150020421600209E -:10C48000054B10B5044621461868FAF775FB034BB7 -:10C490001A7854401C7010BDE81500204216002088 -:10C4A000034A1378591C1170024AD05C704700BFD0 -:10C4B000E21500200216002010B5FFF7F1FF044638 -:10C4C000FFF7EEFF04EB002080B210BD10B5FFF7C0 -:10C4D000F3FF0446FFF7F0FF04EB004010BD00003F -:10C4E00038B5044624200D46FFF7CAFF4D20FFF75C -:10C4F000C7FF002C0CBF3E202120FFF7C1FF064BD9 -:10C50000284600221A70FFF7BBFF044B1878BDE8DD -:10C510003840FFF7B5BF00BF42160020EC150020E1 -:10C5200001460020FFF7DCBF01460120FFF7D8BF1E -:10C53000014B1878FFF7A4BF4216002070B50646DD -:10C5400008460D46FFF7ECFF0024E3B29D4204D0FD -:10C55000305DFFF795FF0134F7E770BD10B5441E5D -:10C5600014F8010F10B1FFF78BFFF9E710BD0000C1 -:10C570002DE9F047002701240025154B1B789D422B -:10C580001DDA144B144E15F803800C2303FB0863CB -:10C59000586804F02BFDB24681460CB9264601E0EE -:10C5A00007440AE04E4508DA0C2303FB08A35B6846 -:10C5B000985DFFF765FF0136F4E70135DDE724B14B -:10C5C000F8B2FFF7ADFF0024D6E7BDE8F08700BF63 -:10C5D000E3150020ED15002074000020F8B5D94BBC -:10C5E0001B787B2B00F0468300F2C6806E2B00F098 -:10C5F000BA8360D8682B00F0598325D8652B00F0EA -:10C600004E8219D8642B40F064850720CE4CFFF78A -:10C6100087FFE620FFF734FF6079FFF731FF002046 -:10C62000FFF72EFF94F81B01C84BC94A00280CBF26 -:10C630001046184600F02ABD662B00F0B082672B2A -:10C6400040F04785C34832E36B2B00F06A8323D860 -:10C65000692B00F053836A2B40F03B851020FFF7D5 -:10C660005FFFBD4BBD4CD87AFFF70AFFBC4B187873 -:10C67000FFF706FF2068FFF7B1FE6068FFF7AEFE28 -:10C68000B84BB3F90000FFF7DBFEB74BB3F900007E -:10C69000FFF7D6FEB54B63E36C2B00F054836D2B94 -:10C6A00040F017850620FFF73BFFB14B1868FFF7F6 -:10C6B00095FEB04B54E3732B00F021843DD8702BD2 -:10C6C00000F08183C0F06083712B00F0EF83722B48 -:10C6D00040F0FF849C4C1620FFF722FF0020FFF75C -:10C6E000AFFEB4F9D000FFF7ABFEA34DB4F9D20012 -:10C6F000FFF7A6FEB4F9D400FFF7A2FEB5F9EA00F1 -:10C70000FFF79EFE0020FFF79BFE0020FFF766FE6E -:10C71000B5F95A000A2390FBF3F0FFF791FE94F865 -:10C720000401FFF7ADFE94F80601FFF7A9FE94F8A7 -:10C730000501FFF7A5FE00F011BC762B00F0EA839F -:10C740000DD8742B00F0C983752B40F0C2842F20C4 -:10C75000FFF7E6FE8948FFF701FF00F0BDBC772B2D -:10C7600000F0BE83782B40F0B484834C3820FFF770 -:10C77000D7FE04F140054BE2D02B00F0228400F2FA -:10C780009B80CA2B00F0068139D8A42B00F081844D -:10C7900011D8A02B40F09D840C20FFF7C1FE784BF0 -:10C7A0001868FFF71BFE774B1868FFF717FE764BEC -:10C7B000186800F06BBCC82B00F0B580C92B40F0A6 -:10C7C0008884FFF76DFE644B644CD872FFF768FEF7 -:10C7D000634B1870FFF77AFE2060FFF777FE60600A -:10C7E000FFF76AFE5F4B1880FFF766FE5E4B18800E -:10C7F000664B1A7842F002021A7000F02EBCCD2B64 -:10C8000000F0E68324D8CB2B00F08B80CC2B40F0BB -:10C810006084FFF745FE584C84F85000FFF740FE57 -:10C8200084F85100FFF73CFE84F85400FFF738FE0F -:10C8300084F85500FFF734FE84F85600FFF730FE09 -:10C8400084F85200FFF72CFE84F8530000F005BC7A -:10C85000CE2B00F0C683CF2B40F03B84FFF72CFE9D -:10C86000FFF72AFE384C444DA4F8D000FFF724FE11 -:10C87000A4F8D200FFF720FEA4F8D400FFF71CFEB6 -:10C88000A5F8EA00FFF718FEFFF720FEFFF714FEF9 -:10C8900000EB80004000A5F85A00FFF701FE84F885 -:10C8A0000401FFF7FDFD84F80601FFF7F9FD84F8A8 -:10C8B0000501FFF7F5FDD0E3D52B00F0E98111D894 -:10C8C000D22B00F0D880C0F04D83D32B00F0E28053 -:10C8D000D42B40F0FE83284C0020FFF721FE04F10A -:10C8E0004005A9E1F02B00F0C4830FD8D62B00F04F -:10C8F000B980EF2B40F0ED83FFF7DEFD1E4CA4F86E -:10C900005E00FFF7D9FDA4F85C00A6E3FA2B00F067 -:10C910009783FE2B40F0DD830820FFF701FE002403 -:10C920009FE300248EE00024FFF7C6FD184B185348 -:10C930000234102CF8D10020FFF7F2FDFDF7F6FCD1 -:10C94000CAE300BFEC150020E81A00201C0000809C -:10C9500014000080240000206F21002044210020CA -:10C960005C210020162100201A2100200412002042 -:10C97000B0200020700F0020281F0020A43D0108D7 -:10C98000E8F7FF1FECF7FF1FF0F7FF1FFE12002074 -:10C99000C8210020C84B1A781C46022A42D103F154 -:10C9A000200503F12C06FFF77BFDF4F733F9C349AB -:10C9B000F4F73CFA45F8040FFFF772FDF4F72AF993 -:10C9C000BF49F4F733FAE860FFF76AFDF4F722F99C -:10C9D000BC49F4F72BFAB542A861E4D10325072D31 -:10C9E00012D1FFF75DFDF4F715F9B449F4F71EFA1B -:10C9F000A064FFF755FDF4F70DF9B049F4F716FA06 -:10CA0000E064FFF74DFD09E0FFF74AFD661930715C -:10CA1000FFF746FDB073FFF743FD307601350A2D71 -:10CA2000DDD11AE35C1E03F10905FFF739FD01347E -:10CA30002071FFF735FDA073FFF732FDAC42207681 -:10CA4000F3D10AE3A04B1B789C4280F006839F4BF6 -:10CA5000E55CFFF731FD984B013403EB4505A5F884 -:10CA60007600EFE70024FFF727FD994B18530234B7 -:10CA7000102CF8D1F1E2974B9C78002C40F0ED821D -:10CA8000FFF70EFD944B022894BF83F83C0483F813 -:10CA90003C44DEE2FFF710FD904B1880DDE20B20F6 -:10CAA000FFF73EFD8E4BB3F90000FFF7C9FCF5F729 -:10CAB0008DFF00B2FFF7C4FC0220FDF7C1F9054667 -:10CAC0000420FDF7BDF904460820FDF7B9F9800000 -:10CAD00040EA44042020FDF7B3F92C43A4B244EA11 -:10CAE000C00084B21020FDF7ABF944EA001000B298 -:10CAF000FFF7A6FC774A00201479D378A40044EA13 -:10CB0000430493781C43937944EAC304537944EA79 -:10CB10004314537A44EA8314724BD97944EAC1141A -:10CB2000197A44EA0124597A44EA4124D17944EA41 -:10CB30008124117A927A44EAC12444EA02345A7B6D -:10CB400044EA42349A7B44EA82341A7C44EA02443E -:10CB50001A7944EA02145A7C44EA42449A7C44EA30 -:10CB60008244DA7C1B7D44EAC24444EA0354564BB7 -:10CB7000197803468B420CD2544A9D5C012202FA7A -:10CB800005F5254218BF9A4003F1010318BF104371 -:10CB9000F0E7FFF723FC504B93F83C04DFE1122051 -:10CBA000FFF7BEFC504B514C1B88B3F5806F22D968 -:10CBB0000025605F082390FBF3F00235FFF740FC8F -:10CBC000062DF6D14A4CB4F90000FFF739FCB4F950 -:10CBD0000200FFF735FCB4F90400464CFFF730FCC7 -:10CBE000B4F90000FFF72CFCB4F90200FFF728FCB1 -:10CBF000B4F9040047E2B4F90000FFF721FCB4F9EE -:10CC00000200FFF71DFCB4F90400FFF719FCD9E797 -:10CC1000B4F9A800FFF714FCB4F9AA00FFF710FC60 -:10CC2000B4F9AC00FFF70CFC083494F8A600FFF749 -:10CC300027FCAC42ECD14FE2FFF73EFCA4F8A80081 -:10CC4000FFF73AFCA4F8AA00FFF736FCA0F57A73C8 -:10CC500007289BB298BF84F8AF00B3F57A7F98BFDE -:10CC6000A4F8AC00FFF71CFC083484F8A600AC4222 -:10CC7000E2D131E20820FFF753FC00240E4B23449D -:10CC800093F8AF000834FFF7FBFB402CF6D123E20A -:10CC90000020FFF745FC0024FFF702FC064B23446D -:10CCA0000834402C83F8AF00F6D115E21248102169 -:10CCB000FFF744FC10E200BF281F002000002041C5 -:10CCC0000000C84200007A44E3150020ED15002062 -:10CCD000EC2000206F210020E81A00207C2000209A -:10CCE0001E0D00208021002012000020B82000200E -:10CCF000960F002060200020D4200020BC4D00248E -:10CD00002878400000F0FE00FFF70AFC2B789C42D8 -:10CD100080F0E281B74B33F91400FFF791FB013447 -:10CD2000F4E70520FFF7FCFBB34BB3F90000FFF776 -:10CD300087FBB24BB3F90000FFF782FBB04B1878CA -:10CD400000F001000BE1AF4C0620FFF7E9FBB4F95E -:10CD50000000FFF775FBB4F90200FFF771FBAA4B67 -:10CD6000B3F900008FE10720FFF7DAFBA74B187833 -:10CD7000FFF786FB0020FFF763FBA54BB3F900002C -:10CD8000FFF75EFB00207EE1A24C0720FFF7C8FB07 -:10CD900094F85000FFF774FB94F85100FFF770FB14 -:10CDA00094F85400FFF76CFB94F85500FFF768FB0C -:10CDB00094F85600FFF764FB94F85200FFF760FB0D -:10CDC00094F85300CBE01E20FFF7AAFB914B1A7892 -:10CDD0001C46022A5AD103F1200503F12C0655F80E -:10CDE000040F8D49F3F76EFF01F0EAFBFA220021F0 -:10CDF000F7F726FFC0B2FFF743FB8849E868F3F76F -:10CE000061FF01F0DDFBFA220021F7F719FFC0B244 -:10CE1000FFF736FB8249A869F3F754FF01F0D0FB16 -:10CE200000216422F7F70CFFC0B2FFF729FBB542DF -:10CE3000D5D10325072D1BD17749A06CF3F742FF0D -:10CE400001F0BEFBFA220021F7F7FAFEC0B2FFF7AD -:10CE500017FB7149E06CF3F735FF01F0B1FB0021DE -:10CE6000FA22F7F7EDFEC0B2FFF70AFB002007E059 -:10CE700066193079FFF704FBB07BFFF701FB307ECA -:10CE80000135FFF7FDFA0A2DD4D125E15C1E03F12F -:10CE9000090501342079FFF7F3FAA07BFFF7F0FAD8 -:10CEA000207EFFF7EDFAAC42F3D115E15D4D002491 -:10CEB0002878400000F0FE00FFF732FB2B789C4200 -:10CEC00080F00A81584BE25C524B013403EB420381 -:10CED000B3F97600FFF7B4FAF0E7FFF749FBFBE0A0 -:10CEE000504D00242878FFF71BFB2B789C4280F0E4 -:10CEF000F3804D4B185DFFF7C3FA0134F5E70820C6 -:10CF0000FFF70EFB0124E0B20134FFF7B9FA092C58 -:10CF1000F9D1E1E0FFF7C4FA06461220FFF700FB63 -:10CF20000EB9424B02E0102E03D1414B1D685C68E4 -:10CF300001E0002425463046FFF7A2FA2846FFF715 -:10CF40004DFA2046FFF74AFA3A4B1868FFF746FABF -:10CF50000020FFF775FA0020FFF772FA0020FFF7B4 -:10CF60008FFAB9E0FFF79CFA0546FFF7AFFA0746DC -:10CF7000FFF7ACFA0646FFF7A9FA0446FFF79CFA5A -:10CF8000FFF79AFAFFF78CFA5DB9284B01225E6031 -:10CF90001F60294BDD711A73002C5ED0254B1C607D -:10CFA0005BE0102D59D1224B1F605E600CB1214B0C -:10CFB0001C601F48214B0222011D1A70FCF788FDDE -:10CFC0004BE01D4B9B78002B47D1F7F7DBFB42E092 -:10CFD000194B9B78002B40D14FF4C870F9F790F9AA -:10CFE0003BE0154B9A78002A37D101229A7334E03E -:10CFF000C4210020C821002024210020302100204D -:10D00000FE120020A00F00208E200020E41A002035 -:10D01000C6210020281F0020000020410000C84237 -:10D0200000007A44E3150020ED150020282100209F -:10D030001C210020B42000206F210020C4100020FB -:10D04000274B9B78002B44D1264B93F83C04F7F7F1 -:10D0500021FBF7F72FFBF7F7A7FD0020FFF760FA9A -:10D060003AE0214B185F0234FFF7EAF9082CF8D1B7 -:10D0700032E01E4C0420FFF753FAB4F95E00FFF7CC -:10D08000DFF9B4F95C00FFF7DBF925E0FFF7A6F95B -:10D0900022E0174D0024287880000130C0B2FFF74D -:10D0A0003FFA2878FFF7ECF92B789C4214D2114B09 -:10D0B000185DFFF7E5F9104B185DFFF7E1F90F4B2D -:10D0C000185DFFF7DDF90E4B185DFFF7D9F9013454 -:10D0D000EAE70020FFF728FABDE8F840FFF728BA92 -:10D0E0006F210020E81A00202E200020281F002099 -:10D0F0005D21002004210020322100204C2100204D -:10D100005E2100202DE9F341454DFF211522074600 -:10D11000284603F075FB002302202B70FCF790FEDD -:10D12000012418B102236C70AB7003240420FCF7B7 -:10D1300087FE68B103234FF40050661C2B55F7F7A8 -:10D140000FFB20B1364B042202349A5500E03446DE -:10D150000220FCF775FE48B12A19052306212B553C -:10D16000A31C51700722EA54033404E00820FCF7A2 -:10D1700067FE0028F0D12020F7F7F2FA10B108235B -:10D180002B5501344FF48070F7F7EAFA28B10A22E0 -:10D190002A55631C0B22EA540234224A53799046E2 -:10D1A000082B01D00E2B02D10C232B5501340D235B -:10D1B0000420661C2B55F7F7D3FA18B1184B11222F -:10D1C0009A55A61C98F839011323003018BF012086 -:10D1D000741CAB55F7F7C4FA18B1114B14221A5549 -:10D1E000B41C114B00221C70104B1A601D467A684B -:10D1F00000240021009101200323FEF77FF920B9CC -:10D200004CB94FF496420124F3E72A68002AEED184 -:10D21000064B1860EBE702B0BDE8F041FDF7C2BF76 -:10D22000ED150020E81A0020E3150020E815002085 -:10D2300010B5304C2068F9F7AFFC002858D02068B2 -:10D24000F9F7AFFC2C4C034622786AB9B0F12402FE -:10D25000534253412370002BEBD1284B9B78002B7A -:10D26000E7D1FEF7D9F9E4E7012A04D14D2814BF2C -:10D27000002302233AE0022A04D13C2814BF0023F1 -:10D28000032333E0032A0FD140284FF0000201D9D5 -:10D290002270CEE71A49042308701A490A701A4905 -:10D2A0000A701A4A107021E0042A08D1184A107036 -:10D2B000164A117880EA01031370052316E0052A47 -:10D2C000B7D110480E4A017812788A420F4A07D91E -:10D2D00014785C4014704A1C02700E4A5354A8E73C -:10D2E00012789A4201D1FFF779F900232370A0E761 -:10D2F00010BD00BFE8150020E41500206F210020BC -:10D30000E5150020E6150020E21500204216002059 -:10D31000EC1500200216002010B5074C074A2368C0 -:10D32000D25C074B1A70FFF759F923680133092BB8 -:10D3300088BF0023236010BD44160020833E0108EF -:10D34000EC1500202DE9F04106460F4690460025D9 -:10D35000EBB2434518D20024E3B2B3420FD20B4BD9 -:10D360000120DA68013482F00802DA60F9F742FC41 -:10D370003846F9F792FC0020F9F73CFCECE73C203A -:10D38000F9F78BFC0135E3E7BDE8F081000C0140C3 -:10D390000F4B1A6842F001021A6059680D4A0A40A0 -:10D3A0005A601A6822F0847222F480321A601A6875 -:10D3B00022F480221A605A6822F4FE025A604FF466 -:10D3C0001F029A60044B4FF000629A60704700BFE2 -:10D3D000001002400000FFF800ED00E0144A154B79 -:10D3E000516801F00C01042903D0082904D0124926 -:10D3F00014E01249096811E051685068C1F3834193 -:10D40000C00301F1020101D40D4806E0506810F498 -:10D41000003F0A48006818BF40084143196052683D -:10D420000849C2F30312895C1A68CA401A6070473F -:10D43000001002409001002000127A008C010020B0 -:10D4400000093D007C0100201FB5002300930193DB -:10D4500002934FF4E0130393504B1A6842F4803266 -:10D460001A609A6942F010029A611A6802F4003256 -:10D470000192009A01320092019A1AB9009AB2F50B -:10D48000A06FF2D11968454A11F4003101D002228F -:10D4900015E0146844F00104146000911A6802F069 -:10D4A00002020192009A01320092019A1AB9009A7E -:10D4B000B2F5A06FF2D11A68920739D50122029213 -:10D4C000374A384C116841F010011160116821F0A1 -:10D4D00003011160116841F0020111605A685A603D -:10D4E0005A685A605A6842F480625A602E4A11683B -:10D4F000043A21F0704151602C490C605C6824F4BE -:10D500007C145C60546844F000445460D46824F493 -:10D510000044D4609268140449BF254A4FF4E012D5 -:10D520000A604FF480120392029A012A01D117E097 -:10D53000FEE7022A18D168B1039AB2F5801F02D122 -:10D540004FF4A01205E0039AB2F5E01F02D14FF4A8 -:10D55000001203925968039A0A4342F4803202E0AF -:10D560005A6842F460125A601A6842F080721A6077 -:10D5700019680A4A8901FBD5516821F003015160FD -:10D58000516841F0020151605A6802F00C02082A09 -:10D59000FAD1FFF723FF04B010BD00BF0010024016 -:10D5A0000020024000127A00041001408C0100208B -:10D5B000001BB700837930B50168027943B3194B7A -:10D5C000CC431D6802F1804225401D605D6802F574 -:10D5D00082322C405C6014682143116002689C68B0 -:10D5E000D1430C409C60DC682140D960417910290E -:10D5F00006D1996811439960D9680A43DA6030BD51 -:10D6000001F1804303F5823319680A431A6030BD83 -:10D6100002F1804303F582331A6822EA010119609E -:10D6200030BD00BF00040140054B1A685B69034030 -:10D6300004D010420CBF00200120704718467047EC -:10D6400000040140014B5861704700BF00040140D5 -:10D6500008B5154B98420BD14FF48050012100F0D2 -:10D66000B7FDBDE808404FF48050002100F0B0BD88 -:10D670000E4B984207D14FF48040012100F0B4FDD9 -:10D680004FF4804009E00A4B98420BD14FF4004020 -:10D69000012100F0A9FD4FF400400021BDE8084041 -:10D6A00000F0A2BD08BD00BF0030014000380040BE -:10D6B000003C00400B8810B54C88028823438C88BE -:10D6C00002F441522343CC8823430C8923434C89E1 -:10D6D00023438C892343CC89234313439BB2038088 -:10D6E000838B23F400631B041B0C83830B8A03824C -:10D6F00010BD038819B19BB243F0400303E023F04F -:10D7000040031B041B0C0380704781817047808994 -:10D7100080B27047038919420CBF00200120704776 -:10D7200043680A6823F4702323F4807313430A794F -:10D7300010B543EA022343608A68CB6884681A43C1 -:10D74000084B234013434A7943EA420383600B7C2E -:10D75000C26A013B22F47002DBB242EA0353C362A5 -:10D7600010BD00BFFDF7F1FF836811B143F0010365 -:10D7700001E023F0010383607047836811B143F433 -:10D78000807301E023F4807383607047836843F003 -:10D790000803836070478068C0F3C00070478368E7 -:10D7A00043F00403836070478068C0F380007047D3 -:10D7B000836811B143F4A00301E023F4A003836064 -:10D7C0007047092970B50DD9A1F10A0404EB44048E -:10D7D0000725A540A340C66826EA050545EA0304D7 -:10D7E000C4600BE001EB41040725A54003FA04F4F3 -:10D7F000066926EA050545EA04030361062A0CD8F2 -:10D80000013A02EB82021F23934001FA02F2446BB9 -:10D8100024EA03031A43426370BD0C2A0CD8073A6A -:10D8200002EB82021F23934001FA02F2046B24EA06 -:10D8300003031A43026370BD0D3A02EB82021F23F9 -:10D84000934001FA02F2C46A24EA03031A43C26253 -:10D8500070BD000040F0BF60024B40F40030D86063 -:10D86000704700BF00ED00E0C27810B50378FAB150 -:10D87000154A4478D26803F16043D243C2F30222CE -:10D88000C2F1040104FA01F10F2424FA02F28478AF -:10D8900003F5614322400A431201D2B283F8002308 -:10D8A00003780122590903F01F0302FA03F306E08B -:10D8B0005909012203F01F0302FA03F32031034A3E -:10D8C00042F8213010BD00BF00ED00E000E100E0B3 -:10D8D00030B5048C24F001042404240C0484058B4A -:10D8E000048CADB225F0F3052A4342EA03139DB23E -:10D8F000104BA4B2984215D003F50063984211D0A2 -:10D90000B0F1804F0ED0A3F5983398420AD003F5BA -:10D910008063984206D003F58063984218BF24F0D4 -:10D920000A0401D124F0020444F0010421430583D8 -:10D93000018430BD002C014030B5048C24F010046B -:10D940002404240C0484048B058C24F440742405E2 -:10D95000240D44EA022242EA0333144AADB2904253 -:10D960009BB212D002F5006290420ED0B0F1804F0F -:10D970000BD0A2F59832904207D002F58062904217 -:10D9800003D002F58062904207D125F0200545F0D2 -:10D99000100545EA011189B204E025F0A00545F023 -:10D9A000100529430383018430BD00BF002C0140D2 -:10D9B000224A038890429BB212D002F50062904244 -:10D9C0000ED0B0F1804F0BD0A2F59832904207D024 -:10D9D00002F58062904203D002F58062904203D14A -:10D9E0004A8823F070031343154A904208D002F589 -:10D9F0008062904204D023F44073CA889BB21343E0 -:10DA000003808B8883850B8803850C4B98420FD04D -:10DA100003F5006398420BD003F54063984207D0AA -:10DA200003F58063984203D003F58063984201D1E7 -:10DA30000B7A038601238382704700BF002C0140CC -:10DA400000100040038C70B523F001031B041B0C75 -:10DA50000384038C8488028B0D8822F073021204E5 -:10DA6000120C2A434E880D8923F002031B04354310 -:10DA7000ADB21B0C2B43144DA4B2A8420FD005F538 -:10DA80000065A8420BD005F54065A84207D005F512 -:10DA90008065A84203D005F58065A8420ED14D8966 -:10DAA00023F008032B438D8823F004032B43CE89F6 -:10DAB0008D8924F440743543ADB22C4384800283B5 -:10DAC000CA888286038470BD002C0140038C30B567 -:10DAD00023F010031B041B0C0384038C8288048B2B -:10DAE0000D8824F4E6442404240C23F0200344EAA3 -:10DAF00005241B040D891B0C43EA05134D8892B2C3 -:10DB000043EA0513124DA4B2A8429BB203D005F517 -:10DB10000065A84215D14D8923F080039BB243EAEA -:10DB200005134FF6BF751D408B8822F4406245EA0D -:10DB300003138D899BB242EA8502CD8942EA8502B0 -:10DB400092B28280CA8804830287038430BD00BFFA -:10DB5000002C0140038C30B523F480731B041B0C94 -:10DB60000384038C8288848B0D8824F0730424043E -:10DB7000240C23F400732C431B040D891B0C43EA73 -:10DB800005234D8892B243EA0523124D9BB2A84269 -:10DB900003D005F50065A84215D14D8923F4006333 -:10DBA0009BB243EA05234FF6FF351D408B8822F4D4 -:10DBB000405245EA03238D899BB242EA0512CD8982 -:10DBC00042EA051292B28280CA88848382870384E3 -:10DBD00030BD00BF002C0140038C30B523F48053CE -:10DBE0001B041B0C0384038C8488828B0D8822F415 -:10DBF000E6421204120C23F4005342EA05221B04ED -:10DC00000D891B0C43EA05334D88A4B243EA053362 -:10DC10000A4D92B2A8429BB203D005F50065A84216 -:10DC200005D18D8924F4804444EA8514A4B284800B -:10DC30008283CA88A0F84020038430BD002C0140B4 -:10DC40004FF6FF73838000230380C38043800372F9 -:10DC500070470023038043808380C3800381438116 -:10DC60008381C38170470023012203804380828027 -:10DC7000C38003817047038819B19BB243F001034D -:10DC800003E023F001031B041B0C03807047B0F872 -:10DC9000443029B16FEA43436FEA53439BB201E03A -:10DCA000C3F30E03A0F84430704783899BB20AB1D6 -:10DCB000194301E023EA010181817047038B23F0BE -:10DCC00008031B041B0C194301837047038B23F4C7 -:10DCD00000631B041B0C43EA01218BB203837047D2 -:10DCE000838B23F008031B041B0C194381837047AB -:10DCF000838B23F400631B041B0C43EA01218BB2CA -:10DD00008383704781847047038B23F00C031B04CB -:10DD10001B0C0383038B9BB2194301837047038B56 -:10DD200023F440631B041B0C0383038B9BB243EA65 -:10DD300001218BB203837047838B23F00C031B04F8 -:10DD40001B0C8383838B9BB2194381837047838B26 -:10DD500023F440631B041B0C8383838B9BB243EA35 -:10DD600001218BB28383704770B50E880D4604463F -:10DD70004988AA882B893EB9FFF7AAFD2046E98881 -:10DD8000BDE87040FFF7C0BF042E07D1FFF7D4FDF8 -:10DD90002046E988BDE87040FFF7C1BF082EEE8835 -:10DDA000058C39D125F480752D042D0C0584808BCC -:10DDB000258C80B220F0F30040EA03139BB21A4393 -:10DDC000344BADB29C4212D003F500639C420ED09E -:10DDD000B4F1804F0BD0A3F598339C4207D003F5E4 -:10DDE00080639C4203D003F580639C4207D125F4F5 -:10DDF000007545EA012189B241F4807104E025F4FF -:10DE0000206541F480712943A28320462184314654 -:10DE1000BDE87040FFF790BF25F480552D042D0C10 -:10DE20000584808B258C20F440700005000D40EAAD -:10DE30000220184A40EA03339442ADB29BB212D09A -:10DE400002F5006294420ED0B4F1804F0BD0A2F5DF -:10DE50009832944207D002F58062944203D002F5D2 -:10DE60008062944207D125F4005242EA013292B214 -:10DE700042F4805205E047F6FF522A4041F48051B7 -:10DE80000A43A383204622843146BDE87040FFF751 -:10DE90005EBF00BF002C0140808E80B27047008FB3 -:10DEA00080B27047808F80B27047B0F8400080B277 -:10DEB0007047038A828911EA030092B203D01142AB -:10DEC0000CBF002001207047C94389B2018270470E -:10DED000038ACA889BB223F44053134330B50382AC -:10DEE0000D4682890989AB8892B20B43698922F475 -:10DEF000B0520B4322F00C0213439BB28381838AFE -:10DF0000AA899BB223F4407387B0134304468382EB -:10DF100001A800F0EDF81749049A039B8C4208BF52 -:10DF20001346A289192112B25943002A2A684FF0D8 -:10DF30006403B4BF52009200B1FBF2F1B1FBF3F203 -:10DF40001201100903FB1011A08900B2002806DAA3 -:10DF5000C9003231B1FBF3F303F0070305E0090117 -:10DF60003231B1FBF3F303F00F031A4392B2228173 -:10DF700007B030BD00380140838919B19BB243F42A -:10DF8000005303E023F400531B041B0C83817047F0 -:10DF9000C1F3421310B5012401F01F01A34204FA9A -:10DFA00001F101D10C3003E0022B0CBF1030143012 -:10DFB00003680AB1194301E023EA0101016010BDC1 -:10DFC000838A9BB20AB1194301E023EA01018182ED -:10DFD0007047090A01238B40DB439BB203807047E3 -:10DFE000034B044A5A6002F188325A60704700BFFE -:10DFF0000020024023016745024B1A6942F080026B -:10E000001A61704700200240014BD860704700BF82 -:10E0100000200240084BDA68D10709D4DA685207B9 -:10E0200008D4DB6813F0100F0CBF042003207047E6 -:10E0300001207047022070470020024010B50446BE -:10E04000FFF7E8FF012806D11CB1FFF7E3FF013C11 -:10E05000F8E7052010BD002C08BF052010BD00000A -:10E0600038B505464FF43020FFF7E8FF042812D1F9 -:10E07000094C4FF43020236943F0020323616561AA -:10E08000236943F040032361FFF7D8FF226941F67B -:10E09000FD731340236138BD0020024073B5002397 -:10E0A00006464FF400500D460193FFF7C7FF0428C2 -:10E0B0001AD10E4C4FF40050236943F00103236141 -:10E0C000ABB23380FFF7BAFF042808D102360196BD -:10E0D000019B2D0C1D804FF40050FFF7AFFF22690C -:10E0E00041F6FE731340236102B070BD0020024070 -:10E0F0001F4B10B55A6802F00C02042A03D0082AFC -:10E1000004D01C4A14E01C4A126811E05A6859688D -:10E11000C2F38342C90302F1020201D4174906E0A7 -:10E12000596811F4003F1449096818BF49084A4367 -:10E1300002605A681249C2F303128C5C0268E24022 -:10E1400042605C68C4F302240C5D22FA04F484602B -:10E150005C68C4F3C224095DCA40C2605B680949B7 -:10E16000C3F38133CB5CB2FBF3F2026110BD00BF9D -:10E170000010024000127A008C01002000093D00CE -:10E180009801002094010020044B5A6909B1104302 -:10E1900001E022EA00005861704700BF0010024011 -:10E1A000044B9A6909B1104301E022EA000098612A -:10E1B000704700BF00100240044BDA6909B11043F8 -:10E1C00001E022EA0000D861704700BF0010024061 -:10E1D000044BDA6809B1104301E022EA0000D8607C -:10E1E000704700BF00100240044B1A6909B1104388 -:10E1F00001E022EA00001861704700BF00100240F1 -:10E20000024B5A6A42F080725A6270470010024014 -:10E2100008B50B4B984207D14FF400100121FFF7CE -:10E22000E3FF4FF4001006E04FF480000121FFF7F8 -:10E23000DBFF4FF480000021BDE80840FFF7D4BFAA -:10E2400000540040F0B587B00446868801A80D460A -:10E25000314FFFF74DFF039826F03F063604B0FB21 -:10E26000F7F7360C1FFA87FC4CEA0606A6802188D1 -:10E270002A6821F00101294B0904090C9A422180E6 -:10E280000DD85300B0FBF3F39BB20CF1010C032B40 -:10E290001FFA8CFC98BF0423A4F820C022E0E98870 -:10E2A0004BF6FF73994205D102EB4202B0FBF2F349 -:10E2B0009BB206E019235343B0FBF3F39BB243F444 -:10E2C0008043C3F30B020AB943F001034FF4967283 -:10E2D00057434FF47A7297FBF2F70137BFB243F41A -:10E2E00000432784A383238869899BB243F00103F9 -:10E2F00023802388AA8823F4816323F002031B046C -:10E300000A431B0C13439BB223802A89AB89134316 -:10E310009BB2238107B0F0BD40420F00A0860100F0 -:10E3200041F288330360002383804BF6FF72038140 -:10E3300043814FF48043C28083817047038819B1C1 -:10E340009BB243F0010303E023F001031B041B0C09 -:10E3500003807047038819B19BB243F4807303E0D4 -:10E3600023F480731B041B0C03807047038819B1CE -:10E370009BB243F4007303E023F400731B041B0CF3 -:10E3800003807047038819B19BB243F4806303E0B4 -:10E3900023F480631B041B0C0380704783889BB2AB -:10E3A0000AB1194301E023EA01018180704701822B -:10E3B0007047008AC0B2704712B141F0010101E01C -:10E3C00001F0FE010182704702684FF6FE731340B0 -:10E3D00003600023036043608360C3602A4B98425C -:10E3E00022D02A4B984229D0294B984230D0294B31 -:10E3F000984237D0284B98423ED0284B984206D1BD -:10E4000053F8682C42F4700243F8682C7047244B90 -:10E41000984206D153F87C2C42F0706243F87C2C71 -:10E420007047204B984206D153F8042C42F00F025B -:10E4300043F8042C70471C4B984206D153F8182C13 -:10E4400042F0F00243F8182C7047184B984206D15E -:10E4500053F82C2C42F4706243F82C2C7047144B68 -:10E46000984206D153F8402C42F4704243F8402CB5 -:10E470007047104B984205D153F8542C42F4702247 -:10E4800043F8542C704700BF080002401C000240B3 -:10E490003000024044000240580002406C0002403C -:10E4A00080000240080402401C0402403004024084 -:10E4B00044040240580402408A6810B50C6A03689C -:10E4C00014430A6923F4FF4314434A6923F0700399 -:10E4D00014438A691443CA6914434A6A14438A6A12 -:10E4E000224313430360CB6843600B6883604B682F -:10E4F000C36010BD0023036043608360C360036199 -:10E5000043618361C361036243628362704719B1EF -:10E51000036843F0010303E002684FF6FE73134003 -:10E520000360704703680AB1194301E023EA01015F -:10E530000160704741607047406880B270470000DA -:10E54000C3004CBF014B024B5860704700040240AF -:10E550000000024000B5194A20F00043934283B006 -:10E56000014617DDB3F1FF4F04DBF2F7A1FA03B068 -:10E570005DF804FB694601F03BF800F00302012A54 -:10E580000098019911D0022A0AD09AB1012201F013 -:10E59000F3FDECE7002101F0F3F903B05DF804FBB3 -:10E5A00001F0EEF900F10040E1E701F0E5FD00F1D6 -:10E5B0000040DCE701F0E4F9D9E700BFD80F493F9C -:10E5C00030B5C0F3C754A4F17F031E2B83B00146BE -:10E5D00020DC581C1BDB162B4FEAD17509DDC1F37B -:10E5E000160040F40000963CA04005B1404203B044 -:10E5F00030BD114B53F825402046F2F75BFA0190ED -:10E6000001982146F2F754FA20F0004333B9002074 -:10E6100003B030BDF2F71CFD03B030BDC0F31604EB -:10E62000C0F3C75044F40004C0F1960024FA00F08F -:10E63000002DDCD0DAE700BF903E010800B51D4A8E -:10E6400020F00043934283B0014618DDB3F1FF4F41 -:10E6500004DBF2F72DFA03B05DF804FB694600F025 -:10E66000C7FF00F00300012818D002280ED0D0B157 -:10E670000098019901F084F900F10040EBE70021D6 -:10E68000002201F079FD03B05DF804FB00980199C8 -:10E69000012201F071FD00F10040DCE700980199D2 -:10E6A00001F06EF9D7E700980199012201F064FDAD -:10E6B000D1E700BFD80F493F70B58AB0054600F0DA -:10E6C00023FA224C064694F90030013303D0284641 -:10E6D00001F0C4FF10B930460AB070BD284601F001 -:10E6E0006BFF4FF07E51F2F7A9FC0028F3D01849D8 -:10E6F000012200232846009208930191F1F796FE2B -:10E7000002460B461348CDE90423CDE9022301F06C -:10E71000ABFD94F90030CDE90601022B0BD0684621 -:10E7200001F0A0FD38B1089B53B9DDE90601F2F70D -:10E730006BF90AB070BD02F035F821230360F2E7EF -:10E7400002F030F8089B0360EFE700BFA80100204B -:10E75000983E0108A43E010800F03EBB2DE9F041BF -:10E760008AB007460C4600F0C7FB9B4E054696F95B -:10E770000030013303D0204601F070FF18B928465D -:10E780000AB0BDE8F081384601F068FF80460028F5 -:10E7900032D120460021F2F729FC0028EFD08F4A21 -:10E7A0000123384601920093CDF82080F1F73EFE18 -:10E7B000CDE902012046F1F739FE894B96F9004078 -:10E7C0000022CDE90623631CCDE904010DD0022C03 -:10E7D0000BD0684601F046FD002800F09A80089BA7 -:10E7E0001BB101F0DFFF089B0360DDE90601F2F7D2 -:10E7F0000BF90AB0BDE8F08138460021F2F7F6FBCC -:10E8000018B320460021F2F7F1FB8046002855D0CE -:10E810007249012200233846009208930191F1F7D2 -:10E8200005FECDE902012046F1F700FE96F9004011 -:10E8300000220023CDE90401CDE90623002CC8D035 -:10E84000674B0022CDE90623CFE7284601F0B8FE4A -:10E850008046002862D028460021F2F7C7FB002836 -:10E860008DD0384601F0ACFE002888D0204601F05B -:10E87000A7FE002883D0594904220023384600927D -:10E8800008930191F1F7D2FDCDE902012046F1F79D -:10E89000CDFD96F9004000220023022CCDE90401B1 -:10E8A000CDE9062300F08880684601F0DBFC0028F3 -:10E8B00000F08280089B002B97D092E7204601F061 -:10E8C0007FFE00283FF45BAF20460021F2F798FB63 -:10E8D00000283FF454AF414A012338460192009387 -:10E8E000CDF82080F1F7A2FDCDE902012046F1F735 -:10E8F0009DFD3478CDE904010022002C30D0394B45 -:10E90000022CCDE906232ED101F04CFF2123036018 -:10E91000D0E701F047FF2123036060E7384601F0AC -:10E920004FFE002897D0204601F04AFE002892D0E2 -:10E93000284601F093FE0346D8B9284901223846FB -:10E94000089300920191F1F771FDCDE90201204693 -:10E95000F1F76CFD3478CDE90401002C31D10022AF -:10E960000023CDE90623684601F07CFC0028A1D1F4 -:10E97000CAE71A4A0323384600930192CDF8208053 -:10E98000F1F754FDCDE902012046F1F74FFD96F96C -:10E990000030CDE90401384643BB134B4FF06042D1 -:10E9A0000021CDE90623F2F72BFB00283FD196F991 -:10E9B0000030022B7FF478AF01F0F4FE22230360D5 -:10E9C00078E70020002102460B46F1F7ADFE022C4D -:10E9D000CDE9060198D0C6E7A8010020A03E0108B5 -:10E9E0000000F03F0000F0FFFFFFEF471C4B00224C -:10E9F0000021CDE90623F2F703FB0028D7D02046FB -:10EA00004FF07C51F2F75EF9F1F710FD04460D4628 -:10EA100001F030FC02460B4620462946F1F7C2FFC2 -:10EA20000028C4D10F4B0022CDE90623BFE72046C2 -:10EA30004FF07C51F2F746F9F1F7F8FC04460D4629 -:10EA400001F018FC02460B4620462946F1F7AAFFC2 -:10EA50000028ACD1044B4FF06042CDE90623A6E775 -:10EA60000000F07F0000F0FFFFFFEFC770B58AB035 -:10EA7000054600F031FF224C064694F90030013380 -:10EA800008D0284601F0EAFD20B128460021F2F71F -:10EA9000B7FA10B930460AB070BD1A4901220023F6 -:10EAA0002846019100920893F1F7C0FC2478CDE943 -:10EAB0000401CDE902017CB900220023CDE906233F -:10EAC000684601F0CFFB88B1089BA3B9DDE90601D8 -:10EAD000F1F79AFF0AB070BD0020002102460B46F4 -:10EAE000F1F722FE022CCDE90601E9D101F05AFE30 -:10EAF00021230360E8E701F055FE089B0360E5E78A -:10EB0000A8010020A83E0108F8B520F00043B3F1A9 -:10EB10007E5F044610D008DCB3F17C5F11DAB3F1FC -:10EB20000C5F00F384809D48F8BD0146F1F7C0FFFB -:10EB30000146F2F77BF9F8BD002840F3CD800020B4 -:10EB4000F8BD0028C0F2CA8001464FF07E50F1F7B0 -:10EB5000AFFF4FF07C51F2F7B5F8044600F0BCFE71 -:10EB60008F4906462046F2F7ADF88E49F1F7A2FF2D -:10EB70002146F2F7A7F88C49F1F79AFF2146F2F700 -:10EB8000A1F88A49F1F796FF2146F2F79BF88849E8 -:10EB9000F1F78EFF2146F2F795F88649F1F78AFFE3 -:10EBA0002146F2F78FF8844905462046F2F78AF8A5 -:10EBB0008249F1F77DFF2146F2F784F88049F1F7A9 -:10EBC00079FF2146F2F77EF87E49F1F771FF214681 -:10EBD000F2F778F84FF07E51F1F76CFF01462846C6 -:10EBE000F2F724F93146F2F76DF826F47F6525F047 -:10EBF0000F05074629462846F2F764F801462046E5 -:10EC0000F1F756FF294604463046F1F753FF014617 -:10EC10002046F2F70BF901463846F1F74BFF014663 -:10EC20002846F1F747FF0146F1F744FFF8BD0146DA -:10EC3000F2F748F85A490546F2F744F85949F1F70E -:10EC400039FF2946F2F73EF85749F1F731FF2946D7 -:10EC5000F2F738F85549F1F72DFF2946F2F732F867 -:10EC60005349F1F725FF2946F2F72CF85149F1F7FE -:10EC700021FF2946F2F726F84F4906462846F2F7C3 -:10EC800021F84E49F1F714FF2946F2F71BF84C49D9 -:10EC9000F1F710FF2946F2F715F84A49F1F708FF96 -:10ECA0002946F2F70FF84FF07E51F1F703FF0146C6 -:10ECB0003046F2F7BBF801462046F2F703F801466A -:10ECC0004148F1F7F5FE01462046F1F7F1FE014615 -:10ECD0003E48F1F7EDFEF8BD3D48F8BD4FF07E51DE -:10ECE000F1F7E8FE4FF07C51F1F7ECFF2C490446B8 -:10ECF000F1F7E8FF2B49F1F7DDFE2146F1F7E2FFDE -:10ED00002949F1F7D5FE2146F1F7DCFF2749F1F754 -:10ED1000D1FE2146F1F7D6FF2549F1F7C9FE21467C -:10ED2000F1F7D0FF2349F1F7C5FE2146F1F7CAFFFD -:10ED30000646204600F0D0FD1F4905462046F1F763 -:10ED4000C1FF1E49F1F7B4FE2146F1F7BBFF1C4994 -:10ED5000F1F7B0FE2146F1F7B5FF1A49F1F7A8FE29 -:10ED60002146F1F7AFFF4FF07E51F1F7A3FE0146C8 -:10ED70003046F2F75BF82946F1F7A4FF1249F1F7A4 -:10ED800097FE01462846F1F795FE0146F1F792FEFF -:10ED900001461048F1F78CFEF8BD00BFDB0FC93FFC -:10EDA00008EF1138047F4F3A4611243DA80A4E3E21 -:10EDB00090B0A63EABAA2A3E2EC69D3D6133303FA1 -:10EDC0002D57014039D119406821A233DA0FC93FCC -:10EDD000DB0F4940DA0F494021F00042B2F1FF4F0A -:10EDE000F8B5044614DC20F00045B5F1FF4F0646A7 -:10EDF0000EDCB1F17E5F3AD08F1707F0020747EAC9 -:10EE0000D07755B9022F2FD0032F2FD13148F8BD1D -:10EE100008462146F1F74EFEF8BDFAB1B2F1FF4FB8 -:10EE200029D0B5F1FF4F19D0AA1AD2153C2A19DC06 -:10EE3000002938DB2046F1F7F9FF01F0BDFB01F0B6 -:10EE4000A5FA012F2CD0022F22D0002F2FD022493B -:10EE5000F1F730FE2149F1F72BFEF8BD002E15DB4E -:10EE60001F48F8BD1E48ECE71C48F8BDF8BDBDE8DA -:10EE7000F84001F08BBAB5F1FF4F19D0022FF3D053 -:10EE8000032FC3D0012F1BD00020F8BD1548F8BDBB -:10EE90001149F1F70FFE01461048F1F709FEF8BDE0 -:10EEA00000F10040F8BD3C32C4DA0020C9E7F8BDEB -:10EEB000022F0CD0032F08D0012F04D00A48F8BD30 -:10EEC0004FF00040F8BD0948F8BD0948F8BD0948B1 -:10EED000F8BD00BFDB0F49C02EBDBB33DB0F49407F -:10EEE000DB0FC93FDB0FC9BFDB0F493FDB0F49BF5A -:10EEF000E4CB16C0E4CB16402DE9F04F31F00049C9 -:10EF000087B00D460C46074611D020F0004ABAF1F2 -:10EF1000FF4F804605DD514807B0BDE8F04F01F0D6 -:10EF2000B7BBB9F1FF4F07DDBAF17E5FF3D14FF008 -:10EF30007E5007B0BDE8F08F002840DB0026B9F115 -:10EF4000FF4F34D0B9F17E5F4CD0B4F1804F3846DA -:10EF500055D0B4F17C5F1BD001F02EFB0146BAF115 -:10EF6000000F1DD028F04043B3F17E5F18D04FEA68 -:10EF7000D87808F1FF3856EA080166D0B9F19A4FFF -:10EF800074DD374B9A4533DC002C37DB0020D0E7AB -:10EF9000B8F1000FE0DB07B0BDE8F04F00F09CBC1B -:10EFA000002C41DBB8F1000F32DB0846C1E7BAF1B3 -:10EFB0007E5FBCD027DD002CE8DB2846B9E7B9F13D -:10EFC000974F13DAB9F17E5F0ADB4FEAE953C3F1D9 -:10EFD000960349FA03F202FA03F34B4500F0448228 -:10EFE0000026AFE7002C25DB3846A2E70226A6E77D -:10EFF0001C4B9A4540F39D82002CC7DD1A48014600 -:10F00000F1F760FE95E7002CC0DA05F1004090E7CB -:10F01000AAF17E5A56EA0A0A12D10846F1F748FDCB -:10F020000146F1F703FF84E74FF07E50F1F7FEFE53 -:10F030000146B7E739464FF07E50F1F7F7FE78E723 -:10F04000012EB2D101F1004073E739463846F1F79D -:10F050002FFD0146F1F7EAFE6BE700BFA43E010871 -:10F06000F7FF7F3F0700803FCAF24971BAF5000FF2 -:10F0700080F202824FF09741F1F724FE6FF0170201 -:10F080008246B34B4FEAEA51CAF3160A7F399A45D2 -:10F0900001EB020C4AF07E5740F3EB81AD4B9A45F1 -:10F0A00040F3428200220CF1010CA7F50007059203 -:10F0B0000599A94B384653F82130CDF804C01946BC -:10F0C00003920493F1F7F4FC049981463846F1F772 -:10F0D000F1FC01464FF07E50F1F7A8FE03461946B9 -:10F0E00048460293F1F7EEFD7910039A41F0005182 -:10F0F000BB4601F5802120F47F6727F00F070A4403 -:10F100008246114638460392F1F7DCFD0146484637 -:10F11000F1F7CEFC039A814604991046F1F7C8FC3A -:10F1200001465846F1F7C4FC01463846F1F7CAFDDE -:10F1300001464846F1F7BCFC029B1946F1F7C2FDB7 -:10F14000514683465046F1F7BDFD01468146F1F731 -:10F15000B9FD8249034648460293F1F7B3FD804961 -:10F16000F1F7A8FC4946F1F7ADFD7E49F1F7A2FCA5 -:10F170004946F1F7A7FD7C49F1F79CFC4946F1F7B8 -:10F18000A1FD7A49F1F796FC4946F1F79BFD7849D4 -:10F19000F1F790FC029B01461846F1F793FD3946C2 -:10F1A00081465046F1F786FC5946F1F78BFD4946FA -:10F1B000F1F780FC394604903846F1F783FD6D493C -:10F1C0000390F1F777FC0499F1F774FC20F47F6960 -:10F1D00029F00F0949463846F1F774FD49460746BC -:10F1E0005846F1F76FFD634983464846F1F760FCE6 -:10F1F000039A1146F1F75CFC01460498F1F758FCBC -:10F200005146F1F75FFD01465846F1F753FC83463E -:10F2100059463846F1F74EFC20F47F6A2AF00F0A6F -:10F2200050465549F1F74EFD544981465046F1F795 -:10F2300049FD3946034650460293F1F739FC014631 -:10F240005846F1F735FC4E49F1F73CFD029B01466B -:10F250001846F1F72FFC4B4B059A53F82210F1F7A3 -:10F2600029FCDDF804C007466046F1F7D7FC464BA1 -:10F27000059A049053F822B039464846F1F71AFC33 -:10F280005946F1F717FC0499F1F714FC20F47F6A52 -:10F290002AF00F0A04995046F1F70AFC5946F1F793 -:10F2A00007FC4946F1F704FC01463846F1F700FC3B -:10F2B00024F47F6424F00F04013E56EA08068146D8 -:10F2C000214628460CBF314F4FF07E57F1F7F0FB37 -:10F2D0005146F1F7F7FC494606462846F1F7F2FC9D -:10F2E00001463046F1F7E6FB214606465046F1F767 -:10F2F000E9FC054601463046F1F7DCFB0028814673 -:10F30000044620F00048AA4640F3F880B8F1864F42 -:10F3100000F3C28000F0B280B8F17C5F00F3C480DB -:10F320004FF00009C84624F47F6424F00F042046FF -:10F330001749F1F7C7FC514605462046F1F7B8FBDF -:10F3400001463046F1F7B4FB1249F1F7BBFC23E06C -:10F3500071C41C00D6B35D00C03E010842F1533EAB -:10F3600055326C3E05A38B3EABAAAA3EB76DDB3E81 -:10F370009A99193F000040400038763FA0C39D365F -:10F380004F38763FB83E0108B03E0108000080BF0C -:10F390000072313F1872313F864906462046F1F728 -:10F3A00091FC01463046F1F785FB0646314628467A -:10F3B000F1F780FB29460446F1F77AFB0146304617 -:10F3C000F1F776FB214606462046F1F77BFC7A49A9 -:10F3D0000546F1F777FC7949F1F76AFB2946F1F721 -:10F3E00071FC7749F1F766FB2946F1F76BFC75492B -:10F3F000F1F75EFB2946F1F765FC7349F1F75AFB1B -:10F400002946F1F75FFC01462046F1F751FB05461E -:10F4100029462046F1F756FC4FF0804182462846A7 -:10F42000F1F746FB01465046F1F700FD314605462F -:10F430002046F1F747FC3146F1F73CFB01462846F0 -:10F44000F1F736FB2146F1F733FB01464FF07E50D2 -:10F45000F1F72EFB8144B9F5000FC0F2A5804946B3 -:10F460003846F1F72FFC64E502F00102C2F1020612 -:10F4700068E5002205921BE6002202E65349304669 -:10F48000F1F718FB294682464846F1F711FB014681 -:10F490005046F1F7D3FD38B138464D49F1F712FC2B -:10F4A0004B49F1F70FFC44E54FEAE858A8F17E0814 -:10F4B0004FF4000343FA08F32344C3F3C75245480B -:10F4C000C3F31608A2F17F0140FA01F1C2F19602DE -:10F4D00048F4000848FA02F8002C23EA0101284603 -:10F4E000B8BFC8F10008F1F7E3FA8246514630464A -:10F4F000F1F7E0FA4FEAC859044614E7364B98454D -:10F500000ADC7FF409AF2946F1F7D2FA014630460A -:10F51000F1F780FD0028C7D038463049F1F7D2FB1B -:10F520002E49F1F7CFFB04E501234FF400120593B8 -:10F53000BEE54FF07E51F1F7BBFA29490746F1F7D6 -:10F54000C1FB284981463846F1F7BCFB3946824663 -:10F550003846F1F7B7FB4FF07A5183463846F1F75A -:10F56000B1FB01462048F1F7A3FA3946F1F7AAFBAF -:10F5700001464FF07C50F1F79BFA01465846F1F7EF -:10F58000A1FB1A49F1F79EFB01465046F1F790FAAC -:10F59000074639464846F1F78DFA20F47F6A2AF08B -:10F5A0000F0A494650467DE6414601F075F801468E -:10F5B00056E700BF8CBEBF354CBB31330EEADD359C -:10F5C00055B38A38610B363BABAA2A3E3CAA383386 -:10F5D000CAF24971FFFF7F00000016436042A20D8E -:10F5E00000AAB83F70A5EC36ABAAAA3E3BAAB83F2A -:10F5F0002DE9F04FAB4A20F00044944289B0064612 -:10F600000D4664DDA84A94421CDC0028A74940F35B -:10F61000EC80F1F74DFAA64B24F00F049C4206460D -:10F6200064D0A449F1F744FA014628603046F1F766 -:10F630003FFAA049F1F73CFA01236860184609B087 -:10F64000BDE8F08F9C4A944262DDB4F1FF4F46DA88 -:10F65000E715863FA4EBC7542046F1F7F9FCF1F714 -:10F66000DDFA0346014620460593F1F721FA4FF0F3 -:10F670008741F1F727FB8046F1F7EAFCF1F7CEFA74 -:10F680000146044640460694F1F712FA4FF08741CE -:10F69000F1F718FB00210790F1F7A8FC002800F013 -:10F6A000C58020460021F1F7A1FC002814BF0123EA -:10F6B000022382480221019000913A4605A829467A -:10F6C00000F022FA002EC0F2A780034603E00022D9 -:10F6D000286000234A60184609B0BDE8F08F014653 -:10F6E000F1F7E6F9002368602860F4E77449F1F760 -:10F6F000DFF974490446F1F7DBF90146286020463A -:10F70000F1F7D6F96F49F1F7D3F901236860E2E721 -:10F7100000F052FF6C490746F1F7D4FA4FF07C51E4 -:10F72000F1F7C8F9F1F794FC8246F1F777FA5F49EF -:10F730008346F1F7C7FA01463846F1F7B9F95D4952 -:10F7400080465846F1F7BEFABAF11F0F8146494686 -:10F75000404618DC5D4B0AF1FF3253F8223024F0AA -:10F76000FF029A420FD0F1F7A3F907462F603946FE -:10F770004046F1F79DF94946F1F79AF9002E686085 -:10F7800056DB5346A7E7F1F793F9E315C0F3C752E9 -:10F790009A1A082A0746E9DD494958460393F1F7C2 -:10F7A00091FA074639464046F1F782F90446214668 -:10F7B0004046F1F77DF93946F1F77AF941490746B4 -:10F7C0005846F1F77FFA3946F1F772F98146494612 -:10F7D0002046F1F76DF9039BC0F3C7529B1A192B12 -:10F7E000074641DC2860A046C1E7F1F763F9304BDA -:10F7F00024F00F049C42064623D02E49F1F75AF913 -:10F80000014628603046F1F753F92A49F1F752F9D9 -:10F810004FF0FF3368605EE795E80C0003F10041AC -:10F8200002F1004243422A60696054E7032340E743 -:10F8300007F1004700F100402F606860CAF1000343 -:10F8400049E71F49F1F736F91E490446F1F732F945 -:10F85000014628602046F1F72BF91A49F1F72AF9F9 -:10F860004FF0FF33686036E719495846F1F72AFA36 -:10F87000074639462046F1F71BF9804641462046A7 -:10F88000F1F716F93946F1F713F9124904465846CB -:10F89000F1F718FA2146F1F70BF98146494640463F -:10F8A00061E700BFD80F493FE3CB1640800FC93F47 -:10F8B000D00FC93F43443537800F4943483F0108C3 -:10F8C0000044353708A3852E84F9223FC83E01083D -:10F8D00000A3852E32318D2420F00042B2F1FF4F7B -:10F8E000F8B5044603462DD25AB300283DDBB2F5E5 -:10F8F000000F4FEAE0502CD37F38C3F31603C20742 -:10F9000043F4000348BF5B00002740105B003E4605 -:10F9100019244FF08072B5189D4202DC5B1BAE18B3 -:10F920001744013C4FEA43034FEA5202F3D113B1AB -:10F9300007F001031F447F1007F17C5707EBC0500D -:10F94000F8BDF8BD0146F1F7BDF92146F1F7B2F86F -:10F95000F8BD14F400020FD15B00190202F101029C -:10F96000FAD5C2F101021044C6E70146F1F7A0F84A -:10F970000146F1F75BFAF8BD01221044BCE700BF75 -:10F980002DE9F84320F00046B6F1485F05460F46E2 -:10F9900049DAF1F75DFB002800F09D8029462846F2 -:10F9A000F1F790F94E490446F1F78CF94D49F1F71A -:10F9B00081F82146F1F786F94B49F1F779F82146AC -:10F9C000F1F780F94949F1F775F82146F1F77AF92D -:10F9D0004749F1F76DF82146F1F774F94549F1F718 -:10F9E00069F82146F1F76EF9804620464FF07C51C8 -:10F9F000F1F768F9414606462046F1F763F93946C2 -:10FA000004462846F1F75EF901462046F1F750F822 -:10FA100001463046F1F74CF801464FF07E50F1F7C1 -:10FA200047F8BDE8F8830146F1F74CF92C49044644 -:10FA3000F1F748F92B49F1F73DF82146F1F742F982 -:10FA40002949F1F735F82146F1F73CF92749F1F753 -:10FA500031F82146F1F736F92549F1F729F8214621 -:10FA6000F1F730F92349F1F725F82146F1F72AF9A2 -:10FA7000214B80469E42B8DD204B9E4227DC06F19A -:10FA80007F4631464FF07E50F1F712F8814620460E -:10FA90004FF07C51F1F716F93146F1F709F841467C -:10FAA00006462046F1F70EF9394604462846F1F796 -:10FAB00009F901462046F0F7FBFF01463046F0F712 -:10FAC000F7FF01464846F0F7F3FFBDE8F883DFF89B -:10FAD00034900B4EDBE74FF07E50BDE8F88300BF5B -:10FAE0004ED747ADF6740F317CF29334010DD03709 -:10FAF000610BB63AABAA2A3D9999993E0000483F5E -:10FB00000000903E0000383F2DE9F04FDFB00B932E -:10FB1000013B0293D31E48BF131DB84C064668989C -:10FB2000DB1054F8204023EAE3730C93DB4302EB31 -:10FB3000C30308940693089C029B0C9A1D19099113 -:10FB4000C3EB02071DD4699C3D4404EB87090135D2 -:10FB50004FF0000822AC0AE059F80800F1F75EF80F -:10FB60000137AF4244F8080008F1040809D0002F1B -:10FB7000F2DA01370020AF4244F8080008F1040827 -:10FB8000F5D1089A002AC0F2DF82089A0B9B02F195 -:10FB900001089C0022AF4FEA880827440025029AFA -:10FBA000002AC0F2F28105EB070B4FF000094FF07D -:10FBB000000A56F809005BF8041DF1F783F80146C6 -:10FBC0005046F0F777FF09F10409A1458246F0D1CC -:10FBD0004AA840F805A004354545E0D1089A0EAB87 -:10FBE00003EB82030D9391464FEA89030793079A2B -:10FBF0005EAB1344B9F1000F53F850AC23DD0DF1A7 -:10FC000034084AAF174490440DAD4FF06E51504642 -:10FC1000F1F758F8F1F71CFAF1F700F84FF08741C7 -:10FC20008346F1F74FF801465046F0F741FFF1F7F0 -:10FC30000FFA594645F8040F57F8040DF0F73AFF4C -:10FC400045458246E1D15046069900F025FD4FF02A -:10FC500078510546F1F736F800F0BAFC4FF08241D2 -:10FC6000F1F730F801462846F0F722FF0546F1F794 -:10FC7000EFF98246F0F7D2FF01462846F0F718FF69 -:10FC8000069A8046002A40F3678109F1FF310EA8E9 -:10FC900050F82130C2F1080043FA00F202FA00F0F5 -:10FCA0001B1A06989244C0F1070743FA07F70EA8FB -:10FCB00040F82130002F32DDB9F1000F0AF1010ABE -:10FCC00040F375810EAB079A19461144002507E0F1 -:10FCD000C2F5807012B143F8040C01258B420BD0A1 -:10FCE00053F8042B002DF3D0C2F1FF028B4243F8EE -:10FCF000042C4FF00105F3D1069B002B0DDD012BE9 -:10FD000000F03281022B08D109F1FF330EA951F81E -:10FD1000232002F03F0241F82320022F70D04046FA -:10FD20000021F1F763F9002800F08380089A09F1B7 -:10FD3000FF35AA420DDC079A0EAB0D981344002242 -:10FD400053F8041D834242EA0102F9D1002A40F02F -:10FD5000E481089B0EA85A1E50F82230002B40F078 -:10FD6000F18100EB8202012352F8041D01330029C6 -:10FD7000FAD04B4499450A933DDADDF82CA022AA2B -:10FD8000CA44DDF8308002EB8A02C844C9EB03099B -:10FD9000131D03920593699A079B4FEA89094AAF9D -:10FDA00002EB8808CDF810901F44002558F8040F86 -:10FDB000F0F734FF029B039A002B50514FF0000BD9 -:10FDC00013DBDDF814A04FF00009AA4456F809002F -:10FDD0005AF8041DF0F776FF01465846F0F76AFE20 -:10FDE00009F10409A1458346F0D1049A04359542EE -:10FDF00047F804BFDAD1DDF82890F5E66042010843 -:10FE000041464FF07E50F0F753FE8046002D86D0DD -:10FE100006994FF07E5000F03FFC01464046F0F757 -:10FE200047FE804640460021F1F7E0F800287FF4C5 -:10FE30007DAF069B40465942CDF808A000F02CFC4F -:10FE40004FF087410446F1F7EFF8002800F07F817A -:10FE50004FF06E512046F0F735FFF1F7F9F8F0F763 -:10FE6000DDFE4FF087410546F0F72CFF01462046A6 -:10FE7000F0F71EFEF1F7ECF80EAB43F82900284628 -:10FE8000F1F7E6F8069C09F1010508340EA906947D -:10FE900041F8250006994FF07E5000F0FDFB002D43 -:10FEA00004464FDB6E1C4FEA8508C6EB867A0DF1DF -:10FEB00038094AABC1444FEA8A0A98444FF0000B14 -:10FEC00059F80B00F0F7AAFE2146F0F7FBFE4FF0C1 -:10FED0006E5148F80B002046F0F7F4FEABF1040B2E -:10FEE000D3450446ECD1DFF88C92DDF820A0002445 -:10FEF000B34603950497BAF1000FB8BF002515DB90 -:10FF000000263746002501E0A7420FDC58F806100E -:10FF100059F80600F0F7D6FE01462846F0F7CAFD6C -:10FF20000137BA45054606F10406EDDA5EA800EB96 -:10FF300084030134A345A8F1040843F8A05CDAD196 -:10FF4000039D049F689C032C00F29880DFE814F066 -:10FF5000CB009C009C00310010D109F1FF330EA9A9 -:10FF600051F823703F12A5E609F1FF330EA850F8AF -:10FF7000232002F07F0240F82320CEE64FF07C5190 -:10FF8000F1F752F858B90746C9E64FF0000A4AA8F7 -:10FF900040F805A0043545457FF401AE1EE6B9F1F1 -:10FFA000000F4FF002070AF1010A3FF78BAE002560 -:10FFB000A2E6002D40F3DC804FEA850B5EAB36AE47 -:10FFC00005F1FF3A5B4406EB8A0A53F8A08C5446CD -:10FFD0005B4635AABB462F4600E0C84654F8045994 -:10FFE0004146284601920093F0F764FD8146494658 -:10FFF0002846F0F75DFD4146F0F75CFD019AC4F834 +:104520000A464423E5E7104B5B7C1BB153204D2129 +:104530000246DDE70D4B1B7823B13220BDE8F04782 +:10454000FFF7F6BE0A4B28461D70BDE8F04702F0A3 +:104550009FBB00BF25220020C60C0020CC0C0020F1 +:10456000D00C0020CA0C002013220020C90C00200F +:10457000C70C0020014B1870704700BFC90C002009 +:104580000F4B1A78462A17D1598840F24C42914273 +:1045900012D11A79BE2A0FD193F849240020EF2AAC +:1045A0000CD113F8012B5040064A9342F9D1D0F1B7 +:1045B000010038BF0020704700207047704700BFDF +:1045C00000F801084CFC0108C82303801423837001 +:1045D0001E23C370012303716423C3804FF49673B9 +:1045E000038128234381704710B50446272007F034 +:1045F000D9F82070102007F0D5F86070002007F07F +:10460000D1F8A070002007F0CDF84FF4E1336360DB +:10461000A360E36023615223E070237510BD0000A6 +:1046200030B51F4C1F4D85B0204605F03BFF294695 +:10463000204605F051FF05F1240002F05BF905F179 +:10464000680006F0D9FB14F8500C03F0D9F904F116 +:10465000A60004F07FFDA4F14C0005F041FC04F13C +:104660009A0000F0ADFE05F1280001F0AFFF05F162 +:104670004B03009305F13803019304F1A403029363 +:1046800004F15A00A91D2A4604F1A20303F0FEFF1B +:1046900004F1140005B0BDE8304001F09DBF00BF3B +:1046A000182000204C1C002008B5054B4FF48272E6 +:1046B00002FB0030034900F59E70FCF70FFD08BDBA +:1046C0007C1B0020C81F0020F8B5274B46221A701B +:1046D00040F24C425A80BE221A71EF2283F84924DC +:1046E000002283F84A2411461F46BB5C0132594020 +:1046F00040F24C439A42F8D11B4B042683F84A14EB +:1047000009F070FF0025013E16F0FF061ED0342090 +:1047100009F07CFF154CC4F3090363B13A1902F1A7 +:104720007842A2F5FC322046116809F0B9FF04284E +:10473000054607D0E7E7204609F094FF0428054620 +:10474000ECD0E0E70A4B04349C42E4D109F056FF78 +:10475000042D02D1FFF714FF20B90A20BDE8F8406C +:1047600002F086BBF8BD00BF7C1B002000F80108EA +:104770004CFC0108034B9B6818420CBF0020012031 +:10478000704700BF7C1B0020024B9A681043986062 +:10479000704700BF7C1B00202DE9F04FB74AB84D91 +:1047A00085B010685168B74C40F24C4702AB03C368 +:1047B0003A46002128460CF025FB00214FF4827276 +:1047C00020460CF01FFB46232B70022003236B7145 +:1047D000FFF7DAFF4FF41673A5F8F030FA23A5F8C7 +:1047E000F2302A23A5F8EE304FF4FA73A5F8F6302C +:1047F000202385F8F4306E2385F804312B2385F8C7 +:104800000531212385F8063140F26C7300264FF004 +:10481000010840F2DC52A5F8163140F27E43A5F8BB +:104820001221A5F8147185F84864A5F8FA60A5F876 +:10483000F860A5F8FC6085F8E26085F8E36085F82B +:10484000E460A5F8E660A5F8E860A5F8EA6085F8F8 +:10485000ED6085F8EC8085F8076185F8386185F8AA +:104860003A6185F8396185F8106185F8186185F835 +:10487000196185F81A6185F81B6185F81C81A5F816 +:10488000D03040F23A73A5F8D2304FF47A73A5F8DD +:10489000D43040F27E53A5F8D63040F2EA53A5F862 +:1048A000D83040F2B4534FF03209A5F8DA3005F5AC +:1048B00090704FF4C873A5F8DE300192A5F8DC9033 +:1048C000A5F8E09085F81E61FFF78EFE40F6AC5328 +:1048D00008201E21AB81E07417230E20A1732376DC +:1048E000E17363760B215523A0726420A3712172BA +:1048F0002D231421E0777820DFF8B0A123746172B2 +:1049000063772175607350215F48E3755F4B2827FB +:10491000A1774FF00A0B5A21E1726062AE732670E4 +:1049200027716771A67684F807906674E676A67498 +:10493000267784F815B0277384F82180C4F830A056 +:10494000E36323644FF08243E3624FF07C53A3633D +:104950004F4B84F8501063644E4B84F85460A3644A +:104960004D4B84F85560E364412384F8513084F85A +:104970005660019AA062C4F834A004F15C00A4F867 +:10498000582084F8529084F8536002F0F9FC042314 +:1049900084F86030152384F86430404BC4F868A074 +:1049A000E3663F4B3F48236705F58471A4F85A60DE +:1049B00084F8617084F8627084F8748005F04EFFAA +:1049C0004FF44873A4F8A630C82384F8EB304FF4B2 +:1049D0009663A4F8EC3040F2D933A4F8EE3040F6F8 +:1049E0004303A4F8F03084F8A26084F8A36084F84C +:1049F000A47084F8A58084F8A86084F8EAB02346FF +:104A00004FF47F72A4F8AA204FF4FA62A4F8AC2005 +:104A100002A940F2DC52A4F8AE208A5D013684F887 +:104A2000B020082E4FF0FF0284F8B12004F10804F2 +:104A3000E6D101221C4883F8F22083F8F32083F8A2 +:104A4000F420FFF7C1FD0023EA1810330021C02B2A +:104A50001161F9D10024281900F59E7009494FF41D +:104A6000827204F58274FCF739FBB4F5437FF2D10E +:104A700005B0BDE8F04FFFF727BE00BF401F01089B +:104A80007C1B0020C81F0020000020408FC2753D05 +:104A9000CDCC4C3D0000A04000004040F6287C3FBB +:104AA0003D0A773F1E210108BE2000209A99193F38 +:104AB00008B5FFF765FD18B9BDE80840FFF76CBE03 +:104AC00008BD0000024B9A6822EA00009860704717 +:104AD0007C1B002010B5354C48F20103A26813403E +:104AE00033B9334B13401BB94FF40040FFF74CFE72 +:104AF000A36803F42033B3F5203F03D14FF4003013 +:104B0000FFF7E0FFA368DA0311D51B0702D50820E1 +:104B1000FFF7D8FFA368180403D54FF40040FFF750 +:104B2000D1FFA368D90702D50120FFF7CBFFA36807 +:104B30001A070BD5180403D54FF40040FFF7C2FF46 +:104B4000A368D90702D50120FFF7BCFFA26848F28D +:104B50000103134048F20102934203D14FF4004095 +:104B6000FFF7B0FFA3685A0505D51B0403D44FF423 +:104B70008060FFF7A7FFA26848F24003134048F2A5 +:104B80004002934202D14020FFF79CFF094805F004 +:104B9000E7FC094806F084FF074806F0FFFE20B94D +:104BA0000548BDE81040FFF71FBD10BD7C1B00206D +:104BB00008000100841C00209C1C002007B5FFF7A2 +:104BC000DFFC10B90A2002F053F9104B10491846C7 +:104BD00040F24C42FCF782FA90F84824022A84BF43 +:104BE000002280F8482490F848144FF4827202FBA7 +:104BF0000101084801F59E71FCF770FAFFF76AFFA2 +:104C000003B05DF804EBFFF70BBD00BF7C1B002079 +:104C100000F80108C81F002008B5FFF7CFFFBDE866 +:104C200008400F201421012208F08EBE08B5054B64 +:104C300093F84804FFF738FDFFF746FDBDE808404C +:104C4000FFF7EABF7C1B0020014B9868704700BF4C +:104C50007C1B0020884203DB9042A8BF10467047AF +:104C60000846704770B504460E461546FCF7C8F96D +:104C700030B920462946FCF7E1F918B1284670BD45 +:104C8000304670BD204670BD0023036170472DE99A +:104C9000F041066904460136012E0D46066105D134 +:104CA0000023616021608360BDE8F081D0F800805E +:104CB00008464146FBF7FCFE07463046FBF7AEFFD1 +:104CC00001463846FCF7B2F801464046FBF7F2FED3 +:104CD0000646606031462846FBF7EAFE0146384644 +:104CE000FBF7F0FFA168FBF7E5FE2660E060A0603F +:104CF000BDE8F08110B504460069012807DD0138E0 +:104D0000FBF78CFF0146E068FCF790F810BD00202F +:104D100010BD08B5FFF7EEFFBDE808400AF0A8B9DE +:104D200008B5FBF771FB04A3D3E90023FBF7D2FB23 +:104D3000FBF76AFE08BD00BF399D52A246DF913FD6 +:104D40002DE9F041069C002B06460F460CBF4FF0A4 +:104D500020084FF03008234613F8011B09B9154607 +:104D600003E0002AFBDD013AF6E7002D04DD3046C2 +:104D70004146B847013DF8E714F8011B11B1304630 +:104D8000B847F9E7BDE8F081014B186801F042BF70 +:104D9000E00C00202DE9F04788B006460F4603924C +:104DA0001C46039A531C03931178002900F08D8050 +:104DB000252901D0304686E00023911C04930391FD +:104DC0005578302D05D1D31C039395784FF0010809 +:104DD00000E09846A5F13003DBB2092B06D828463F +:104DE00003A90A2204AB00F034F905466C2D05D165 +:104DF000039B5A1C03921D78012200E00022632DC0 +:104E00004FD006D8252D5CD0582D2AD0002D5CD04F +:104E1000C7E7732D4AD002D8642D14D0C1E7752D91 +:104E200002D0782D1DD0BCE704F1040905AD20683F +:104E30000A2122B100222B4600F090F80EE02B460A +:104E400000F0BFF80AE005AD04F104092068294626 +:104E500012B100F0ABF801E000F0DBF84C46009531 +:104E600018E004F1040A0DF11409206810213AB188 +:104E7000B5F15804624262414B4600F06FF806E01B +:104E8000B5F158035A425A414B4600F09AF854463D +:104E9000CDF8009030463946049A4346FFF750FF5C +:104EA0007FE730462178251DB84708E02368304663 +:104EB00000933946049A0023251DFFF741FF2C4635 +:104EC0006FE730462946B8476BE708B0BDE8F08782 +:104ED0000FB407B50A4904AB08680A4953F8042B14 +:104EE00009680193FFF756FF074B186801F0B1FE00 +:104EF0000028F9D003B05DF804EB04B0704700BFA0 +:104F0000DC0C0020D80C0020E00C0020034A044BED +:104F10001A60044B00221A60704700BF894D0008D8 +:104F2000D80C0020DC0C0020014B1860704700BF3B +:104F3000E00C002070B50646B6FBF2F408461546B4 +:104F400014B12046FFF7F6FF05FB1464024B1B5D0E +:104F500000F8013B70BD00BF27210108F0B5012416 +:104F6000B0FBF4F58D4201D34C43F9E70026DCB1E8 +:104F7000B0FBF4F504FB1500B4FBF1F41EB9002DF1 +:104F800001DC002CF3D1092D03F101075FFA85FC48 +:104F900004DD002A0CBF5725372500E03025654485 +:104FA0001D7001363B46E2E71C70F0BD00280B4641 +:104FB00003DA2D2240420A704B1C0A210022FFF71F +:104FC000CDBFF0B50124B0FBF4F58D4201D34C43C5 +:104FD000F9E70026DCB1B0FBF4F504FB1500B4FBE7 +:104FE000F1F41EB9002D01DC002CF3D1092D03F1E1 +:104FF00001075FFA85FC04DD002A0CBF5725372521 +:1050000000E0302565441D7001363B46E2E71C7028 +:10501000F0BD00280B4603DA2D2240420A704B1CDB +:105020000A210022FFF7CDBFA0F13003DAB2092A2E +:1050300001D818467047A0F16103052B01D85738F5 +:105040007047A0F14103052B94BF37384FF0FF3074 +:1050500070472DE9F8430D6804460F46904699467F +:1050600000262046FFF7E0FF002806DB404504DC71 +:1050700008FB060615F8014BF3E73D602046C9F82A +:105080000060BDE8F883931E232B28BF0A22031E6D +:1050900010B50C4603DA2D2001F8010B5842FFF73A +:1050A00049FF00230370204610BD000030B587B0D3 +:1050B00005460C4603A800210C220BF0A3FE28464F +:1050C0000021FBF7BBFF20B128462949FBF7F2FC82 +:1050D00003E028462649FBF7EBFC2649FBF7F2FDE7 +:1050E000FBF7B6FF054685EAE570A0EBE57069467B +:1050F0000A22FFF7C8FF002DACBF20232D236846EE +:105100008DF80C300CF074FA012807D130238DF89B +:105110000D308DF80E308DF80F300CE0022805D1DF +:1051200030238DF80D308DF80E3004E0032804BFD5 +:1051300030238DF80D30694603A80CF05BF903A805 +:105140000CF056FA0338C5B22A4603A920460CF0E3 +:10515000A7FA00236355204607490CF04BF903A931 +:10516000204629440CF046F9204607B030BD00BF68 +:105170006F12033A00007A44B02B01082DE9F04188 +:1051800002780346202A00F10100F9D0092AF7D05D +:105190002D2A02D10346414D04E02B2A08BF0346C5 +:1051A0004FF07E551E460024334616F8012BA2F11F +:1051B0003007F9B209290DD839492046FBF782FD9D +:1051C00004463846FBF72AFD01462046FBF772FCF1 +:1051D0000446E9E72E2A17D1314F334616F8010B62 +:1051E0003038C2B2092A0FD8FBF718FD3946FBF751 +:1051F0001DFE01462046FBF75DFC29490446384662 +:10520000FBF760FD0746E8E71A7802F0DF02452A5F +:1052100038D15A782D2A02D10233012604E02B2AF4 +:1052200014BF013302330026013B002713F8012F7E +:10523000303AD1B2092903D80A2101FB0727F5E743 +:10524000B7F59A7F28BF4FF49A77B8464FF07E5152 +:10525000B8F1070F07D908461249FBF733FDA8F14B +:1052600008080146F4E707F0070737B108460C497C +:10527000FBF728FD013F0146F7E72EB12046FBF77B +:10528000D5FD04E04FF07E512046FBF71BFD0146A3 +:105290002846FBF717FDBDE8F08100BF000080BF86 +:1052A0000000204120BCBE4C014B00229A80704778 +:1052B000E80C0020034BB3F90400D0F1010038BF23 +:1052C00000207047E80C0020014B187A704700BF9F +:1052D000E80C0020014B01221A727047E80C0020F4 +:1052E000064BB3F90400064B1B681B7803EB8303E2 +:1052F0009842D4BF00200120704700BFE80C002076 +:10530000F40C002010B50446FFF7EAFF002814BF94 +:105310002046002000F0010010BD0000074B1A6875 +:10532000074B1178B3F9040053780B4403EB830364 +:105330009842D4BF00200120704700BFF40C002029 +:10534000E80C0020024B9A8801329A80704700BF17 +:10535000E80C002070B5FFF7C3FF30B3134C237A7D +:105360000BB9A38070BD124EB578281C18BF012060 +:10537000FFF7C8FF88B1012373700E4B1A680E4BFC +:10538000518919805189598052899A800B4A126833 +:105390005288DA80E3880133E380FFF7BFFF00B96A +:1053A0001DB9BDE8704000F0CFBB70BDE80C002017 +:1053B00013220020F80C00206E220020F40C0020A4 +:1053C000024B00221860024B9A807047F40C0020B8 +:1053D000E80C0020044B18600448054B03600023D0 +:1053E000C3800372704700BFF80C0020E80C002057 +:1053F0004C210108044B9A8811B21429CCBF143AED +:1054000000229A80704700BFE80C0020032810B5E6 +:105410000D4B0DD80D4A126894888C4208D2D28860 +:105420008A4205D9012202FA00F01A781043187056 +:105430001B780F2B06D1044B00221A70BDE81040D8 +:10544000FFF7D8BF10BD00BFE40C0020F40C002013 +:10545000F0B5854C87B0FFF759FDFFF729FBFFF743 +:10546000ADFBA07B003018BF012001F06FFC94F869 +:10547000073133B103F0F702012A02D18DF8003071 +:1054800004E000238DF8003084F807316846FCF70B +:10549000F1FA0220FFF76EF910B17448FEF7E4FD4F +:1054A0007348744DFEF70AFE0E2004F0CFFF7248D9 +:1054B000B4F8EE1094F8ED20B5F95A3001F0EAFA9C +:1054C0002F4610B9032001F0D3FC6C4B10225A6117 +:1054D00008221A610A26694D1920EB68013E83F003 +:1054E0001003EB60EB6883F00803EB6001F023FC32 +:1054F000012001F0CDFB192001F01DFC002001F07E +:10550000C7FB16F0FF06E6D108232B6110232B61A1 +:1055100002F006FB60795A4903F01CF9FEF746FDDC +:10552000584806F04FFB63790E2B01D0082B03D1AE +:1055300001238DF80B3001E08DF80B6001215148FB +:1055400006F072FA8DF807004020FFF713F98DF886 +:1055500008004FF40040FFF70DF98DF804004FF4F8 +:105560000030FFF707F98DF806000120FFF702F978 +:105570008DF8050003F01EFD97F8F4308DF8090052 +:10558000C3F380038DF80A30B4F8DE304FF4804066 +:10559000ADF80E30B4F8E030ADF810304FF47A7357 +:1055A000ADF81230FFF7E6F820B12F4BB3F8DA3040 +:1055B000ADF81230BDF80E30B3F5FA7F84BF00238A +:1055C000ADF81230B4F81231ADF8143094F8073158 +:1055D000012B04D0092B01D1072300E0002301A8EF +:1055E0008DF80C30FDF778FC2748FFF7F3FE274DC8 +:1055F0002860FEF723FF2448296804F0EBFF4FF4EE +:105600008070FFF7B7F838B1214A1E4894F81E1190 +:10561000A2F1F20304F0B4FC4FF48060FFF7AAF8A3 +:1056200008B101F0E3FA4FF40060FFF7A3F808B106 +:1056300005F06AFC01F054FB164B18606379052BEA +:1056400003D14FF4C87000F0A9FE4FF47A7001F056 +:1056500057F9C82000F0D0FF0F4B01225A730022E7 +:105660005A7007B0F0BD00BF7C1B0020801C0020DA +:10567000621C0020C81F00205E1C0020000C01409E +:105680008C1B00209C1C0020841C0020CC200020AF +:10569000BE200020080D00201322002008B5FFF7CF +:1056A000D7FE00F077FAFCE708B5034BB3F9D40056 +:1056B00003F06CF9FEE700BF7C1B002038B51A4BE5 +:1056C0001A4C5D7D637C15B36BBBA3789BB101F075 +:1056D00001FC174D08B92B781BB101F073FD0023B5 +:1056E0002B70144810F8041C01F08AFD0123124AA3 +:1056F0006374137038BD01F033FEA0B10520322170 +:10570000012208F021F9BDE8384001F05BBD13B17A +:1057100001F0E4FD6574A3782BB9074B1B7813B136 +:10572000034B01221A7038BD2522002013220020CD +:10573000FC0C0020CC1F0020190D002008B5022011 +:1057400004F07AFE18B900F02FFE28B90AE000F044 +:1057500049FF0028F7D108BD01F0D8F880F001001A +:10576000C0B205E0022004F067FE0028F4D001205A +:1057700000F0010008BD0000054B1A683AB900F5B9 +:10578000F42000F590701860024B08225A617047AF +:10579000240D0020000C0140034B00221A60034B33 +:1057A00008221A61704700BF240D0020000C014040 +:1057B000084A136863B1C01A002809DB064903F5DB +:1057C000F423C86803F5907380F00800C860136084 +:1057D000704700BF240D0020000C0140A94B2DE9AB +:1057E000F04FB3F90600A84B85B0B3F858209042AB +:1057F0000FDBB0F5FA6F93F8564007DA811A4C4385 +:10580000A2F5FA6294FBF2F4643403E0C4F1640498 +:1058100000E064249D4A93F85410B2F812C192F942 +:10582000EC2093F8A25093F8A360524293F85530BD +:1058300092B201910021029203930A46914B40F2E9 +:10584000E637CB5E0093CCEB030303F2F31EBE45B9 +:1058500003D8002BB8BF5B4201E04FF4FA73022A71 +:10586000DFF834822CD025B1AB42CCBFC5EB0303AB +:1058700000236427DFF848A293FBF7FE6FF0630B69 +:105880003AF81E900BFB0E3B0EF1010E3AF91EA0EA +:105890000FFA89FECEEB0A0E0EFB0BFE9EFBF7FE07 +:1058A000CE4428F801E0DDF8048003FB08FE784BC5 +:1058B0009EFBF3F33B449BB2634393FBF7F714E087 +:1058C00026B1B342CCBFC6EB03030023DDF808E0EA +:1058D00003FB0EF7A8F80470039F002BB8BF5B42D0 +:1058E0007B436B4F93FBF7F76437674BDFF8D4814B +:1058F00002EB030E9EF80490642307FB09F999FB61 +:10590000F3F902F808909EF80E909EF818E007FB55 +:1059100009F907FB0EF7DFF8B08199FBF3F902F8FC +:105920000890DDF8008097FBF3F35A4FE045D3551C +:10593000594F02DA7B5A5B427B520132032A01F152 +:1059400002017FF47BAF514C4FF4FA62B4F81411AA +:10595000FFF780F9B4F814314FF47A74C01A444355 +:10596000C3F5FA63B4FBF3F464214C4894FBF1F300 +:105970006FF0630630F8132006FB0344013330F95F +:10598000130013B2C31A5C4394FBF1F1444C0A4474 +:10599000637A414DFA80002B38D0424B1888424B35 +:1059A0001B88C01A00B2FFF7BBF9064609F0D4F80D +:1059B0000746304609F044F90646B5F90200FBF700 +:1059C0002DF98046B5F90000FBF728F939468146E4 +:1059D000FBF778F9314682464046FBF773F90146FA +:1059E0005046FBF765F8FBF733FB39462880404605 +:1059F000FBF768F9314607464846FBF763F901466D +:105A00003846FBF757F8FBF723FB68800220FEF7C8 +:105A1000B1FE264D88B1264A13780133DBB21370EC +:105A20000622B3FBF2F102FB113313F0FF0F04D196 +:105A3000FEF7E2FAFEF702FB28702878003018BF64 +:105A40000120FEF701FDA3781BB11A4B08225A6111 +:105A500042E0FFF773FE20B1164BDA6882F00802CD +:105A6000DA6001232370637B0BB90D4A1370124B6C +:105A70005B7D0BB1002323702378104D33B3FFF708 +:105A80008BFE26E06E220020C81F00207C1B002019 +:105A90000CFEFFFF2B2100203C220020442200208E +:105AA0001322002032210020DA200020040D0020E3 +:105AB000100D0020000C014025220020000D0020C8 +:105AC0005C2200202E210020282100202868FFF7DA +:105AD00053FE2868FFF76CFE05F0F6F98020FEF70C +:105AE00049FEA8B1134B144A1B681168591A0029C2 +:105AF0000EDB03F543435033A07813600F4B0030A7 +:105B000018BF0120B3F90210B3F90020FDF7DAF84D +:105B100006F068F8202004F08FFC18B1054B1868D7 +:105B200004F016FC064B9B680BB10648984705B07D +:105B3000BDE8F08F000D0020140D0020D00F0020D4 +:105B40000C210020D0200020024B9A780AB10022BC +:105B50009A707047132200200B4B19781A4651B1E6 +:105B6000997879B9597831B901229A70074B1A8816 +:105B7000074B1A807047937823B90220FF21012236 +:105B800007F0E2BE704700BF132200203221002040 +:105B9000DA2000202DE9F84F8F4F04F065FD3868BA +:105BA00004F08AFD8D4C002800F03D82386804F036 +:105BB00033FE4FF48040FEF7DDFD20B1884B1B78AB +:105BC0000BB9FFF7C1FF04F05DFE4FF40070FEF764 +:105BD000D1FD88B13B68834A834D934208D92B6835 +:105BE0001B681B6A984718B92B681B685B6A984743 +:105BF0002B681B685B6998470022B4F81451B4F80D +:105C00001661134679489B08115E0232A942C4BF4F +:105C100063F07F03DBB2B142B8BF43F04003082A10 +:105C20008146EFD1724EDFF8E48132789A4205D195 +:105C300098F80020F92A04D8013200E0002288F800 +:105C400000204FF480403370FEF794FD58B1B4F853 +:105C50001211B4F8DC20B9F90630881A834202DD4B +:105C60000A4493420ADB4FF48040FEF783FDC8B933 +:105C7000B9F90620B4F814319A4213DA01F084FB22 +:105C800001F08AFB5B4BB3F876305BB1544B1A786A +:105C9000594B002A00F03B831A78002A00F0378322 +:105CA000FFF75AFF98F80030142B40F0C380524B96 +:105CB000504D93F802B09A46BBF1000F18D0B5F8DA +:105CC000763023B933785F2B01D1FFF73DFF94F88D +:105CD0001A31002B00F0AE80B5F87630002B40F082 +:105CE000A98033787D2B40F0A580FFF72DFFA1E040 +:105CF0003378572B18D14FF47A7000F001FE4FF42F +:105D00008070FEF737FD08B103F08CFA042004F030 +:105D100093FB10B10A2000F06FFC082004F08CFB0C +:105D2000F0B9364B18801BE00420FEF723FDB8B114 +:105D30002F4B1B785A2B13D1314B1A782AB183F889 +:105D400000B0304B01221A700AE02F4A137883F01A +:105D5000010313700BB1022000E00320FEF70AFCE0 +:105D600033785D2B00F0DA825B2B00F0D9825E2B5A +:105D700000F00083B5F876302BB932786F2A02D163 +:105D8000FFF7EAFE13E094F81A211AB113B9337839 +:105D90007E2BF5D03378972B04D14FF4C87000F0E8 +:105DA000FDFA04E0A72B04BF01238AF80E303378F4 +:105DB000BB2B03D1B5F85E30023304E0B72B05D11D +:105DC000B5F85E30023BA5F85E3028E0BE2B1FD14F +:105DD000B5F85C30023320E0000D00207C1B002071 +:105DE00025220020404B4C00CC2000206E220020B9 +:105DF000130D0020C81F0020132200203221002094 +:105E0000290D0020180D0020120D00202E0D00205D +:105E1000BD2B0FD1B5F85C30023BA5F85C3094F88F +:105E20004804FEF741FCFEF74FFCFEF7F5FE0023A9 +:105E300088F800300420FEF79DFC48B37E4A7F4B73 +:105E4000117871B17E49897859B1B9F90600B4F871 +:105E50001411884205DD197819B97A483225058070 +:105E600011705B7C53B1784B1A782AB9774A127853 +:105E700012B9744A32211180012208E0734B1A785A +:105E800032B16F4A92781AB91A70714B01221A70A6 +:105E900070480123002230F8021F5E1EA1F2155542 +:105EA000B5F5C77F8CBF002501259D4009B22A4367 +:105EB00040F21355A942CCBF00250125B5402A4325 +:105EC00040F2A465A942D4BF002101215D1CA94074 +:105ED00003330A430D2B92B2DDD100235E49574EA6 +:105EE00001EB4301B1F876100A420CBF00210121F9 +:105EF00099550133162BF1D17378514D23B10220FE +:105F000004F09AFA68B914E04FF40070FEF732FC1E +:105F100078B1524B1B681B689B6898470028EED1EC +:105F200007E0EB783BB901F02FFA454B0122DA701C +:105F300001E00023EB70B3784BB10023EB702B79B9 +:105F400033B901F021FA3E4B01221A7100E02B71A6 +:105F5000EA78434B12B93A4A127912B110225A61C7 +:105F600001E010221A61042004F066FA10B3F378FD +:105F70008BB1AB7983B9324A01219171394A1168E9 +:105F8000394A1160394AD188394A1180394A136037 +:105F9000394A136000E0AB714FF40050FEF7EAFBA2 +:105FA00040B133792BB1EB7B23B9254B0122DA7356 +:105FB00000E0EB73022004F03FFA10B1737933B9BB +:105FC0000FE0082004F038FA0028F7D119E06B79C7 +:105FD00043B91B4B01225A71284B1A88284B1A804F +:105FE00000E06B71B3792BB16B7A23B9144B0122AA +:105FF0005A7200E06B72F3791BB1204B1A88214B67 +:106000001A80202004F018FA08B104F045F9337B17 +:1060100003B10123AB726379082B01D00E2B6BD136 +:1060200000236B7268E0184D2B68042B64D8DFE8FE +:1060300003F02D37424C5700120D0020252200207E +:10604000132200202C0D0020110D0020290D00200E +:10605000180D002074220020C81F0020CC20002032 +:10606000000C014054210020582100203C22002037 +:106070002A0D0020141000202810002032210020BA +:1060800020210020DA2000201C0D00200123082000 +:106090002B6004F0D1F918B1A24800F0A5FB58BB61 +:1060A0002B68042001332B6004F0C6F918B138685E +:1060B00000F0A8FA00BB2B68042001332B6004F029 +:1060C000BBF910B102F0DEF9B0B92B684FF4807063 +:1060D00001332B60FEF74EFB10B103F0C9F80BE063 +:1060E000002310202B6004F0A7F908B100F08CFD0C +:1060F0004FF40050FEF73EFB00F0F2FDA28938603D +:10610000894B22B11968411A0029C0F2F28010446B +:10611000186001F02DFFFFF761FB00F0E1FD834BFC +:1061200083491A683860821A18600A80FFF7C6FA35 +:10613000082004F081F97F4E002830D07E4A9188F3 +:10614000154601F145039BB28A2B7C4A7C4B24D82F +:106150007C4847790FB31F881388407BFA1A92B2A4 +:1061600093B21FB2B337BCBF02F5B4739BB21AB27D +:10617000B32AC4BFA3F5B4739BB294F8EC2070B1FA +:1061800052B252425343327B1BB253436FF01D0253 +:1061900093FBF2F31944A98001E01B8813800420CB +:1061A00004F04AF9002879D0664B9A79002A75D014 +:1061B0001F7C614D002F69D196F8A510624896F8B2 +:1061C000A420624BB5F806E029B3B0F900000FFA3D +:1061D0008EF1C0EB010CBCF1000FB8BFCCF1000C8C +:1061E00094450FDD8142C8BF5242DFF884C11FFAD7 +:1061F0008EFEC8BF92B2CCF80070724401271F70A7 +:10620000EA804BE01A78002A34D0514A1F70116896 +:10621000504A11602EE007880FFA8EFC38B2C0EBAE +:106220000C0CBCF1000FB8BFCCF1000C944518DD8C +:10623000494ADFF82081B2F800C0F444C7EB0C0CE7 +:106240000FFA8CFC4FF4FA6ED8F800709CFBFEF14C +:106250000F440EFB11C111800122C8F800701A70A2 +:1062600008E01A7832B13A4A19701768394A17604B +:10627000394A1180394BB4F8D0101B686431184486 +:10628000B4F8D220FEF7E6FCE88007E0334B6A88DA +:1062900094F91C111B6801FB03236B8096F8A8304E +:1062A00053B1284BDA780AB91B792BB1224B2C4A0F +:1062B0001188DA880A44DA80202004F0BDF840B161 +:1062C000204BDA790AB91A7A1AB11B7B0BB103F0A9 +:1062D00041FF2448244B00F14C01B4F8F6201D681E +:1062E00000F15803A84702F063FB02F0DFFA02F066 +:1062F00039FB1E4B1B78002B4DD14FF40060FEF78D +:1063000039FA002847D0BDE8F84F04F027BE9B7843 +:10631000002B3FF4C7ACFFF717FCC3E401222AE0CF +:10632000022228E07A1C00200C0D0020080D00201D +:10633000200D0020C81F00203C220020202100202A +:1063400032210020132200202A0D0020280D0020D9 +:106350005421002058210020060D00202810002084 +:106360002C100020CC1F0020180000202C1600202C +:106370001410002003225FFA82FB0BF1FF3384F834 +:106380004834FEF7A1F9FEF719FC022028215A46ED +:1063900007F0DAFAEEE4BDE8F88F00BF014B188091 +:1063A000704700BF3C0D0020034B1888D0F101005E +:1063B00038BF0020704700BF3C0D0020204B00225A +:1063C0002DE9F0411968804613461E4C1E4E258863 +:1063D0001E4FB5F5C87F04BF0025F550F05832F9BF +:1063E00007C0194D844446F803C0043300260C2B23 +:1063F000D6538E5202F10202E7D12388012B19D124 +:106400002B68404603F1C8024FF4C87392FBF3F2C5 +:106410000A806A68C83292FBF3F24A80AA68C832DE +:1064200092FBF3F30A4A12889B1A8B8000F0A8FFB4 +:10643000FEF7FCFB2388013B2380BDE8F08100BF11 +:10644000400D00203C0D0020440D00204C21002078 +:10645000120000202DE9F041354D04462B88322BE7 +:106460000ED1344B1A68344B1188198051889288A8 +:1064700059809A80314B02881A8042885A8001E004 +:10648000002B34D02B490022D1F800C013460F4610 +:10649000298832292A4904BF0020C8502948CE58EB +:1064A00032F900804644CE50043300210C2B1152A7 +:1064B0002CF8021002F10202EAD12B88012B13D131 +:1064C000214A02201170214A1370FEF753F81A4A2C +:1064D0003B68118819805188928859809A80174B9F +:1064E0001A885B88228063802B88013B2B80184BA5 +:1064F0001A78DAB1124900221A700E4B08681B682C +:10650000322290FBF2F01880486890FBF2F058803D +:106510008968204691FBF2F20E490988521A9A8046 +:1065200000F02EFFBDE8F041FEF780BBBDE8F08132 +:106530002C0D0020400D0020300D0020380D0020D3 +:10654000500D00204C210020110D0020290D0020AD +:10655000180D002012000020064B028819888A1AA4 +:106560001A80598842888A1A5A80998882888A1A99 +:106570009A8070474C2100200F4B10B55B68044691 +:106580000E4898470E4B0D481A780146FDF72CFE31 +:106590000C4B1B8813B12046FFF710FF0420FEF7B9 +:1065A000E9F810B12046FFF755FFBDE81040064B53 +:1065B0001868FFF7D1BF00BFDC2000204C2100206D +:1065C000360D00203C0D0020400D0020014B1860CE +:1065D000704700BF400D0020014B1860704700BF9E +:1065E00000210020034B1888D0F1010038BF0020A3 +:1065F000704700BF6C0D0020014B1880704700BF32 +:106600006C0D00202DE9F041224D2B68C31A002BA0 +:106610003CDB214E28603378204C012B10D12369BC +:106620009847636898472B6822881D4813442B605D +:106630001C4963699847002333700220BDE8F0814C +:10664000A3689847E3689847174818490068D1F845 +:106650000080134B0078D3F800C008F10103834297 +:1066600008BF0023124A1348176840F828C050F8A2 +:106670002300BC44C0EB0C070B6017602B686288DA +:106680000120134430702B60BDE8F0810020BDE88C +:10669000F08100BF640D0020780D0020E82000206C +:1066A000680D0020700D002000210020600D0020EA +:1066B000800D0020880D0020F8B51E4C1E4A23686E +:1066C00010681B781D4D013BB0FBF3F0FAF7A2FAFE +:1066D0001B49FAF7ABFB1B4908F042FB01464FF0A0 +:1066E0007E50FAF7E5F91849FAF7ECFA08F06AFA79 +:1066F000236807465C682868FAF790FA2146FAF79B +:10670000E1FA124B06461868381AFAF787FA21465A +:1067100007464FF07E50FAF7CBF901463846FAF7B4 +:10672000D1FA01463046FAF7C5F908F04BFA28606D +:10673000F8BD00BF00210020800D00207C0D00204E +:1067400080E6C547B1DC423ED048874A740D002040 +:1067500010B5154B154A1B6811681878144B013891 +:106760001B68B3FBF0F0082391FBF3F4091B08440A +:10677000106090FBF3F0FAF751FA0E49FAF756FB66 +:106780000D4908F0EDFA01464FF07E50FAF790F906 +:106790000A49FAF797FAFAF75BFC094B1860094BBC +:1067A0001A88013A1A8010BD00210020840D0020B3 +:1067B000800D002080E6C547B1DC423ED048874AC4 +:1067C000740D00206C0D002038B5054C1025656156 +:1067D000FCF750F9034B012225611A7038BD00BF48 +:1067E000000C01405F0E0020F8B5374B374D1B6899 +:1067F0002A6804469A1A002A63DB03F5C333A033E0 +:1068000033482B60FCF7FCF83148324B01461A78CC +:10681000FDF7EAFC304B314A997B184679B129687B +:10682000002311600021E1520E4629492C4F595A8C +:10683000D9532C4FD9530233062BF3D186732A4BED +:106840001B7863B1224B21881888411A1980588817 +:106850006188411A59809888A188411A99801368E3 +:10686000002B2CD02A681E48D31A204A1D49934277 +:1068700016D81F4BDA6882F00802DA600023144A47 +:10688000C55E9A5A14B2A542C4BF154D5A53CD5E87 +:10689000A542BCBF134C1A530233062BEFD10EE0B6 +:1068A0000E4A00231360C55ECA5E2A44022592FB8D +:1068B000F5F2E2522B44062BF5D1FEF7B7F9012091 +:1068C000F8BD0020F8BD00BF000D0020500E0020D4 +:1068D000042100205E0E002013220020540E002010 +:1068E000480E0020580E00205F0E00207FC3C90113 +:1068F000000C0140014B1860704700BF600E002083 +:10690000014B1880704700BF640E0020034B1888AD +:10691000D0F1010038BF0020704700BF640E002096 +:106920003C4B2DE9F74F5B683B4898473B4B3A4857 +:106930001A780146FDF758FC394B374F1A889846AC +:10694000DFF8E8A0002A3CD0364B00251B68364E05 +:1069500093F800B02C46B8F80030DFF8D490B3F5C7 +:106960007A7F05D10023304649F80430FEF78CF9D0 +:10697000785F59F80430034449F80430FAF74EF9C7 +:1069800001463046FEF783F900237B532AF8053091 +:10699000B8F80030012B25D13046FEF7BAF903468E +:1069A000BBF1000F0FD058460193FAF737F9019B5E +:1069B00001461846FAF742FB28B1194B4FF47A7298 +:1069C0001A8000231BE059F804304FF47A7203F563 +:1069D000FA7393FBF2F30A200F2101222AF8053003 +:1069E00006F0B2FF04340C2C05F1020506F1140682 +:1069F000B1D1B8F80030013BA8F80030E1E7F95A0E +:106A00003AF803208A1AFA520233062BF7D103B060 +:106A1000BDE8F08F0C21002034210020B00E0020B2 +:106A2000640E0020600E0020740E0020EC0F002089 +:106A3000680E002038B505460A4C00230A4829464E +:106A40002370FAF7D5FF48B907482946FAF760FDE1 +:106A500020B905482946FAF789FE08B101232370B9 +:106A600038BD00BFB00E00200C21002003780BB110 +:106A7000054A137043780BB1044A137083780BB145 +:106A8000034A1370704700BFB00E0020360D00207F +:106A90005E0E00202DE9F7438146084614469846CD +:106AA000FFF7C8FF0746002800F08A80464E002303 +:106AB0003370464D072C38D8DFE804F00808192455 +:106AC0002F373704022003F0C9FC2EE08DF8043084 +:106AD00001A84FF448733E49ADF80630FAF75CFC64 +:106AE00018B101232B7004233370012C1DD03848BA +:106AF000FAF72EFF30B102232B70022C4FF0010366 +:106B0000337012D03248FAF7A3FD30B103232B7053 +:106B1000032C4FF00203337007D02D48FAF79EFC88 +:106B200018B104232B70012333702B782BB90CB1CF +:106B30001C46BBE7022003F091FC2648FBF7DCFA79 +:106B400030B92448FBF710F910B9042003F086FC93 +:106B50004846FFF78BFF022003F06EFC10B11C4B80 +:106B60001B6898471C4B1B689847FBF735FF18B10B +:106B70001A4B03221A7002E0082003F06FFC082071 +:106B800003F05AFC164C0546C0B1642798FBF7F693 +:106B90003046FAF743F8814607FB168000B2FAF751 +:106BA0003DF81049FAF78EF801464846F9F782FF9A +:106BB0000D49FAF787F82F46206001E00023236093 +:106BC000384603B0BDE8F083360D00205C0D002090 +:106BD000DC200020E82000200C2100205E0E002098 +:106BE000341000208988883C0000204108B501202D +:106BF000FCF7EAF8102003F029FC024B00221A608F +:106C000008BD00BF1C2100200148FCF747B900BFA8 +:106C10001C21002008B503681B68984708BD38B5DB +:106C200005460C4614F8011B19B12846FFF7F2FF80 +:106C3000F8E738BD08B503685B68984708BD08B534 +:106C400003689B68984708BD08B50368DB689847E8 +:106C500008BD08B503681B69984708BD08B50368F7 +:106C60005B69984708BD0000034B4FF4805208B1A0 +:106C70005A6170471A61704700080140034B4FF496 +:106C8000805208B11A6170475A617047000801408C +:106C900008B5024B1B68984708BD00BFB40E002022 +:106CA000064B00201A68064B9A4208BF054A064B5D +:106CB00018BF064A1A60FFF7EBBF00BF940100201F +:106CC000001BB7007D6C0008B40E0020696C000842 +:106CD000024B1A6801321A60704700BFB80E0020DC +:106CE00010B5094A094913688C6812689342F8D1B3 +:106CF000074A106811684FF47A725043001BB0FBCA +:106D0000F1F002FB030010BDB80E002010E000E01F +:106D1000BC0E0020014B1868704700BFB80E002061 +:106D200038B50446FFF7DCFF0546FFF7D9FF401BE7 +:106D3000A042FAD338BD10B504462CB14FF47A7096 +:106D4000FFF7EEFF013CF8E710BD000070B53A4DCB +:106D50008CB006AC06460FCD0FC495E8030084E85E +:106D60000300304606F072FE3448012107F026FD8C +:106D700044F61D20012107F015FD0120014607F012 +:106D800005FD2F4D07F03EFD00238DF802300CACC1 +:106D90004FF6FF732B48694624F8303DFBF744FF5C +:106DA00028466946FBF740FF27486946FBF73CFF4A +:106DB000264B07AC5A6842F000725A60FFF770FF2A +:106DC00008232B6110232B610DAD214B1A68214B39 +:106DD0009A4204D1A378142B04BF1023A37054F853 +:106DE000040C21460834FBF71FFFAC42EDD101A88B +:106DF00007F080FC019B184AF021B3FBF2F3174A1D +:106E000017481360174B1A684FF47A73B2FBF3F20A +:106E1000154B013A5A60154A82F8231000229A60F5 +:106E200007221A60FBF72AFCFBF72CFA6420FFF715 +:106E300082FF0CB070BD00BF481F01080700400072 +:106E4000000C01400008014000100140000001401A +:106E500094010020001BB70040420F00BC0E002030 +:106E6000005800409801002010E000E000ED00E034 +:106E700040F2DB14604308B50D4B10225A61082222 +:106E80001A61841E0A4B2046DA6882F01002DA602A +:106E9000DA6882F00802DA60FFF74DFF0120FFF7A1 +:106EA000F7FE1920FFF747FF0020FFF7F1FEE9E7A3 +:106EB000000C014010B1034A034B1A60034A044B13 +:106EC000DA607047EFBEADDEF04F00200400FA0537 +:106ED00000ED00E0034B1878D0F1010038BF00202E +:106EE000704700BFD80E00202DE9F04F9F4B87B0B0 +:106EF0001B780591013B012B00F233819C4B1E78DE +:106F0000864240F02E819B4B1B78022B00F029819A +:106F1000994D00232B80994B31F916009B5D04930A +:106F2000049A974B1A70974A127803922AB9964B93 +:106F300040421A6802F100421A60F9F76FFE934965 +:106F4000F9F774FF91490446F9F7BCFEFAF780F8A7 +:106F50008D4F80B2D7F800B08C49029068805846B7 +:106F6000F9F7B0FEFAF774F8894AA880136800218F +:106F700018460193FAF73AF8DFF80892DFF810A202 +:106F80004FF00008834F019B002855D03B682046F6 +:106F900019460193FAF752F8019B38B17E4B029AD9 +:106FA000C3F800B0744B3C60DA80C0E0184641463C +:106FB000FAF744F8002800F0BA80784F3B78002BAD +:106FC00032D120465946F9F773FD4FF07C51FAF75C +:106FD00017F8734C28B160687249F9F773FE606066 +:106FE0000FE060687049F9F76DFEDFF8D4B10190E9 +:106FF0005946FAF705F8019B08B9636001E0C4F847 +:1070000004B001233B70694B049A1B68CAF80080E6 +:10701000134400229A72039A82F0010389F8003027 +:107020005C4BC3F8008082E0594B1C60FFF772FE96 +:107030005F4BFA3018607AE020461946F9F7E0FF16 +:1070400020B1029B4C4ACAF80040D3803868DAF875 +:107050000010F9F72DFD8346FFF75CFE544B1B68CB +:10706000C01A00280DDA58464FF07C51F9F7E6FFB8 +:1070700000285CD0464B20461968F9F7DFFF00284E +:1070800055D0454B38681968F9F7D8FF444C48B1DA +:107090000123206844492B80F9F714FE4149206000 +:1070A000A06809E0022358464FF07E512B80F9F783 +:1070B000C5FF28B1A0683C49F9F704FEA06004E0D0 +:1070C00020683849F9F7FEFD2060384B2C4A1B68D0 +:1070D0002E49206892F800B00193F9F7F3FDF9F713 +:1070E000DDFF019B03F80B00A0689B44F9F7D6FF76 +:1070F00099F800308BF8140083F0010389F8003010 +:10710000264BCAF800801A78C7F800800132D2B244 +:10711000032A01D01A700AE000221A70204B254978 +:107120005868F9F7CFFDF9F7B9FF8BF80A0016B9DF +:107130002B8864332B8099F800300BB11E4B00E094 +:107140001E4B114A1360059B33F91600F9F766FDD3 +:107150000E49F9F76BFE0C4A01461068F9F7A8FCD6 +:1071600000E0104607B0BDE8F08F00BFD80E002049 +:10717000340F0020E10E0020D220002074210108ED +:10718000D90E00203C0F0020300F002000002041CD +:10719000C40E0020C00E0020D40E0020E00E0020FF +:1071A000C80E00200AD7833FEC51783FDC0E002048 +:1071B000380F002000007A440000A0410000A0C168 +:1071C0006F12833A044B00221A60044B00221A709B +:1071D000034B01221A707047300F0020D80E002098 +:1071E0001400002001464C220148F9F777BF00BF88 +:1071F000E40E002001494C22F9F770BFE40E002094 +:10720000254B264A1B7870B5032B04460E46137097 +:1072100003D1BDE87040FFF7EDBF012B204D03D136 +:10722000FFF7E0FF002302E0022B01D101232B70C6 +:107230001C4A012313701C4A13701C4A002313605C +:107240001B4A13601B4B1C4A1C601C4B1E702B7886 +:107250001B4DD65C1B4B1C4A1E701C4BA05D1A605C +:10726000F9F7DCFC1A49F9F7E1FD34442860A07A0B +:10727000F9F7D4FC1749F9F7D9FD6860207DF9F7D3 +:10728000CDFC1549F9F71EFDA860F9F707FF0023AB +:107290002075A37270BD00BF14000020D80E00201E +:1072A000340F00203C0F0020E00E0020C40E002010 +:1072B000C00E0020DC0E002074210108E10E002029 +:1072C000C80E0020D90E00200000A041300F002081 +:1072D0000000204100007A445555553FF8B5194B40 +:1072E000194D1A78511E012921D8184B184F1C68C6 +:1072F000184B194978681E78F9F7E4FCF9F7CEFEC7 +:1073000026441649B072B868F9F7DCFCF9F7C6FEF6 +:1073100030752078F9F782FC0146F9F7CBFBF9F7D5 +:10732000BDFEA37AA0702373237DA37505E0032A15 +:1073300003D100221A70012301E02B7801332B7056 +:10734000F8BD00BFD80E002014000020DC0E002085 +:10735000C80E0020D90E002000007A449A99993F67 +:10736000064B10B5186800214FF00104F9F73EFEF6 +:1073700008B14FF0000404F0010010BD300F0020F0 +:107380000023038043807047024B00221A605A603A +:10739000704700BF880F0020054B00221A605A601A +:1073A0009A60044B00221A605A609A60704700BFCE +:1073B0007C0F0020400F0020044B987818B1587CB7 +:1073C000003018BF012000F0010070471322002098 +:1073D0002DE9F04F87B00593884B0492B3F9022052 +:1073E000B3F90030002AB8BF5242002BB8BF5B424D +:1073F00000249A42B8BF1A46804603922546A14609 +:1074000027460294019426467D4BDA7812B91B79FF +:10741000002B54D0022E52D0784BDDF810C0E85E1D +:10742000784BCCF10001EB5E624603EB4000FDF7C8 +:1074300011FCDFF8F8A1DDF814C035F90AB03CF909 +:107440000530CBEB000000EB030BFFF7B5FFA0B15D +:107450006D4B5846F35C0093F9F7E0FB6B49F9F785 +:10746000E5FC009B024651461846FFF73DFD674983 +:10747000F9F728FCF9F7ECFD834698F8070098F82F +:107480001B2000FB0BF064236FF0040190FBF3F072 +:10749000514302EB8202FDF7DDFBDFF894A101907E +:1074A00054F80A005A49584442F21072FDF7D2FBD0 +:1074B00098F8113044F80A00584300130290504BDA +:1074C000DA781AB11B790BB9022E33D14B4B50200D +:1074D000EF5EDFF844A1784318F8063035F90A204A +:1074E000DFF8509190FBF3F0042392FBF3F3C01A02 +:1074F00054F809304FF47A5218444649FDF7AAFB74 +:1075000035F90A3049F80400002BB8BF5B42B3F5E7 +:10751000206FC4BF002349F8043059F804207D23AC +:1075200092FBF3F908EB06039B7A03FB09F940236E +:1075300099FBF3F9324B1A79D2B1022E18D0DDF84B +:107540000CC04FF4FA710CFB07F2CCF5FA73DDF8BE +:1075500004C003FB0C22DDF80CC092FBF1F20CFB23 +:1075600009F0DDF808C003FB0C0393FBF1F308E01E +:10757000DB780BB1022E02D14B463A4601E0029B6A +:10758000019A2549DFF8B0B0695A04200FFA81FC4E +:1075900016F80BB09CFBF0FA0BFB0AFB6FF04F0ADE +:1075A0009BFBFAFA02EB0A0B1C4A35F902A0A9521E +:1075B000CAEB0C0C9CFBF0F0194ADFF880C054F8C1 +:1075C00002A054F80C10A050164A5144B25C014479 +:1075D0005143202291FBF2F15B1A134801369B4480 +:1075E000032E44F80CA025F800B004F1040405F1C2 +:1075F00002057FF409AF07B0BDE8F08F3C22002000 +:1076000013220020021300207621010800002041EF +:10761000F0D8FFFF80C1FFFFE00F00209C0F00208B +:10762000BC0F00202B21002022210020D00F0020A1 +:10763000880F00207C0F00202E210020580F0020F2 +:107640002DE9F04F89B006936E4B8046188805915E +:10765000F9F7E0FA6C49F9F735FB00240490474646 +:1076600025462646022EDFF8E4910BD1059AB9F99A +:10767000040053790A335843F9F7D0FA6349F9F70C +:10768000D5FB44E0624B39F90500EB5E61491844D3 +:107690004FF4FA72FDF7DEFADFF8B4A1069B35F974 +:1076A0000A20595F801A0844F9F7B8FA5A49F9F7DD +:1076B000BDFB8346FFF780FE30B1584A5146905DCE +:1076C0005A46FFF711FC8346DFF888A19AF8032099 +:1076D000C2B9059B39F905001A7914325043F9F7FC +:1076E0009DFA4A49F9F7A2FB9AF8043081467BB12A +:1076F000D8F848105846F9F7E5FA01464846F9F730 +:10770000D9F904E05846D8F84410F9F7DBFA814675 +:10771000434B0136585FF9F781FA424B0437D96879 +:10772000F9F7D0FA824651464846F9F7C1F9F969A6 +:107730008346F9F7C7FADFF8209104990790584675 +:10774000F9F7C0FAB96AF9F7BDFA54F80910F9F770 +:10775000B1F9354A3549FDF785FA44F80900DFF8F3 +:10776000FC90834654F809105046F9F7A1F944F803 +:1077700009A0024604994FF07E500192F9F756FB9A +:10778000019A01461046F9F79DFA294B294A54F807 +:1077900003C0A1588146604601920293CDF80CC007 +:1077A000F9F788F94946F9F785F9DDF80CC0029B2D +:1077B000019A214944F8039044F802C0F9F736FBD6 +:1077C000796BF9F77FFA1D4A1D49FDF74BFA5946C7 +:1077D00081460798F9F76EF94946F9F769F907F014 +:1077E000F1F918494FF47A72FDF734FA164B032E6B +:1077F000585304F1040405F102057FF433AF09B0D6 +:10780000BDE8F08F200D0020BD37863500004842CE +:10781000021300200CFEFFFF00002041762101082A +:10782000E00F00200C21002000007A4300007AC302 +:10783000700F00204C0F00200000404000009643D5 +:10784000000096C318FCFFFF222100203C220020EC +:10785000D00F002013220020400F0020A40F002092 +:107860002DE9F04F002485B007468A4693460393DE +:1078700006462546022DDFF87C814FEA450907D1EF +:107880009AF80520B8F904301B3253435B1144E0E9 +:107890004D4A38F9150032F91520CBF1000102EB01 +:1078A00040005A46FDF7D6F9484B33F91520039BA3 +:1078B000801A33F9151042180192FFF77DFD019AE5 +:1078C000B8B14349104615F801C0CDF800C0F9F72A +:1078D000A5F94049F9F7AAFADDF800C002463B498C +:1078E0006046FFF701FB3B49F9F7ECF9F9F7B0FB0C +:1078F00002463949C87868B99AF8040038F909305D +:107900001B30434309791B1139B1797C4A4303EB9E +:10791000222302E0FB795A431311304A785D32F991 +:107920000980042298FBF2F8C8EB030800FB08F07A +:10793000DFF8C4C0C0110290BCF80000284B00FB67 +:1079400008F0E258B17AC01201FB00202549E0504E +:107950004FF400120193CDF800C0FDF77BF9019BB5 +:10796000DDF800C0E050204B4FF6FF72E15844F8BC +:107970000380BCF80030C1EB08011B09B2FBF3F334 +:107980005943DFF878C0194B891154F8038054F833 +:107990000C20E150029B424403EB6030337D0A44EB +:1079A0005A430135124B00EB2222032D44F80C8080 +:1079B00023F8092006F1010604F104047FF45AAF0C +:1079C00005B0BDE8F08F00BF02130020D00F0020EB +:1079D000762101080000204113220020E00F002042 +:1079E0007C0F00200000E0FF900F0020640F0020BB +:1079F000222100203C220020200D0020B00F00207A +:107A00000128054B03D0022803D0044A02E0044AAF +:107A100000E0044A1A60704718000020D173000883 +:107A200061780008417600082DE9F84F384E044689 +:107A30003768384607F090F80546384607F000F9F1 +:107A400076688046304607F087F88346304607F070 +:107A5000F7F8D4F80490064629464846F9F732F973 +:107A6000A768824641463846F9F72CF90146504648 +:107A7000F9F71EF8216882465846F9F723F941467E +:107A800004464846F9F71EF93146F9F71BF9014655 +:107A90002046F9F70FF8314604463846F9F712F94F +:107AA0002946F9F70FF901462046F9F703F8014690 +:107AB000504607F053F91749F9F704F9F8F7B6FCFF +:107AC00011A3D3E90023F8F72FFE134B04461868DF +:107AD0000D46F8F7ABFC02460B4620462946F8F760 +:107AE00047FB00220D4BF8F71FFEF8F78DFF07F05C +:107AF00069F883B21A0444BF00F5B4739BB218B29C +:107B0000BDE8F88FAFF30080182D4454FB210940E5 +:107B1000D80F00200000E144341000200000244071 +:107B200010B5294C2088F9F779F82849F9F7CAF8EF +:107B300007F048F8264B18802088F9F76FF80146BF +:107B40002448F9F773F92449F9F770F9234B1860C1 +:107B5000234BB3F8A600F9F761F801462148F9F77D +:107B600065F9F8F763FC12A3D3E90023F8F7B2FC38 +:107B7000F8F74AFF1C4B18601C4BD868F8F756FC06 +:107B80000DA3D3E90023F8F7A5FC0DA3D3E9002347 +:107B9000F8F7A0FCF8F738FF154B1860082002F042 +:107BA0004BFC18B1BDE81040FEF70EBE10BD00BF83 +:107BB0003B597E90A9E78140399D52A246DF913F13 +:107BC000000000A0F7C6B03E12000020C903683FC5 +:107BD000D40F00200AE81C4100401C464821002028 +:107BE000C81F002000006144642100200C210020F7 +:107BF00068210020AFF300802DE9F04104460068C1 +:107C00000D460146F9F75EF8D4F804800646414671 +:107C10004046F9F757F801463046F8F74BFFA7689A +:107C2000064639463846F9F74DF801463046F8F72A +:107C300041FF07F01DFA00210646F9F7D7F970B9A0 +:107C400020683146F9F7F2F8314628606068F9F7A4 +:107C5000EDF831466860A068F9F7E8F8A860BDE87B +:107C6000F0812DE9F04F0C68836889B0D0F800A04E +:107C7000D0F804800646204603938B4606F06CFF3E +:107C80000746204606F0DCFFDBF80440814620462C +:107C900006F062FF0546204606F0D2FFDBF808201A +:107CA00004461046019206F057FF019A834610469B +:107CB00006F0C6FF394602905846F9F703F83946F0 +:107CC00004900298F8F7FEFF594605904846F8F7E9 +:107CD000F9FF029906904846F8F7F4FF2946079005 +:107CE0005846F8F7EFFF01465046F8F7EBFF2146FC +:107CF00083460698F8F7E6FF01460598F8F7DAFE9E +:107D000001464046F8F7DEFF01465846F8F7D2FE36 +:107D1000214683460498F8F7D5FF01460798F8F7FF +:107D2000C7FE01460398F8F7CDFF01465846F8F71D +:107D3000C1FE3060029905F10040F8F7C3FF01462B +:107D40005046F8F7BFFF214683460798F8F7BAFF79 +:107D500001460498F8F7ACFE01464046F8F7B2FF3A +:107D600001465846F8F7A6FE214683460598F8F7DF +:107D7000A9FF01460698F8F79DFE01460398F8F71B +:107D8000A1FF01465846F8F795FE2146706050461F +:107D9000F8F798FF2946044609F10040F8F792FFEA +:107DA00001464046F8F78EFF01462046F8F782FE6E +:107DB000394604462846F8F785FF01460398F8F748 +:107DC00081FF01462046F8F775FEB06009B0BDE8B6 +:107DD000F08F80EAE073A3EBE0738B4206DB0028B0 +:107DE00001DD401A704702D00844704700207047F8 +:107DF0002DE9F041524B86B01A685B6802F10042EF +:107E000003F1004301934F4B0646B3F90000009283 +:107E1000F8F704FF00F10040F8F708FB46A3D3E9A8 +:107E20000023F8F757FBF8F7EFFD474C0290B4F941 +:107E30000000F8F7F3FE0390B4F90200F8F7EEFE45 +:107E40000490B4F90400F8F7E9FE404D0590694646 +:107E500003A8FFF706FF95F87430012B15D13C4BB2 +:107E60003C4C9B7863B92368402093FBF0F0181AD0 +:107E7000F8F7D4FE0599F8F71DFEF9F7E9F8206048 +:107E80002068402390FBF3F001E0334B1888F8F7AB +:107E9000C5FE01460598F8F70BFE05903046F8F749 +:107EA000B9FE2E490746F8F705FE01463846F8F7B1 +:107EB000BDFFDFF8B8800746D8F800400598214696 +:107EC000F8F7F6FD01463846F8F7FCFE0146204675 +:107ED000F8F7F0FD224C0746C8F800000398D4F8E4 +:107EE000008006F06FFE95F86210FFF772FF4044C5 +:107EF00020600498D4F8048006F064FE95F86210BF +:107F0000FFF767FF404460603846D4F8088006F009 +:107F100059FE95F86110FFF75CFF124B40441A6858 +:107F2000A06016441E60104B1A6801321A6006B039 +:107F3000BDE8F081AFF30080399D52A246DF913F4A +:107F4000D80F0020322100205C210020C81F002013 +:107F50001322002010100020120000203661823C05 +:107F60003C210020F80F00202410002038100020B1 +:107F70002DE9F04F89B0FEF7D3FC022002F05CFA45 +:107F80009B4D9C4F002800F0B2819B48FEF7F4FA0D +:107F9000FEF7A6FE994C06462368C3EB0009484647 +:107FA000F8F738FE964B1968F8F78CFE954A26606C +:107FB00092F860300026039002933446B246285F60 +:107FC000F8F72CFE0399F8F77DFE029A0DF11408DC +:107FD00048F806005AB31046F8F720FE01464FF065 +:107FE0007E50F8F723FFDFF850B2024611464FF0FB +:107FF0007E500092F8F75CFD56F80B10F8F762FE21 +:108000008446385FCDF804C0F8F708FE009A1146A0 +:10801000F8F758FEDDF804C001466046F8F74AFD5F +:108020004BF80600F9F714F8774A105302E0395B71 +:10803000754AA152744A0436A15E0234062C01FB33 +:1080400001AA9346BBD1714A6424128804FB0AF347 +:1080500052436F48414693FBF2F4FFF702FE0820BB +:1080600002F0EAF920B16B484146FFF7FAFD07E05C +:1080700069484146FFF7F5FD67480146FFF7BCFD3B +:10808000493C664EA4B23B2CB6F8F00006D9082055 +:10809000B6F8F24002F0D0F948BB53E0F8F7BAFD69 +:1080A0004FF07E518046F8F705FD01464FF07E50B7 +:1080B000F8F7BCFE00240746DFF854A140465AF802 +:1080C0001410F8F7FFFD03463BF904000193F8F79D +:1080D000A5FD019B01461846F8F7ECFC3946F8F778 +:1080E000F1FD4AF814000234062CE5D1CFE74B4BE2 +:1080F000B3F8F200F8F78EFD80462046F8F78AFDC7 +:108100004FF07E51F8F7D6FC01464FF07E50F8F75D +:108110008DFE002407463F4E404656F81410F8F7EF +:10812000D1FD3F4B8246185FF8F778FD0146504677 +:10813000F8F7C0FC3946F8F7C5FD46F814000234DC +:10814000062CE8D1374B324CB3F90000F8F766FD46 +:10815000A668014630464FF00107F8F76FFF00B9F7 +:108160000746314B314660685F7306F0F7FD2F4ECE +:10817000D4F808A03060206800F10047606801462C +:10818000F8F7A0FD514680465046F8F79BFD0146A2 +:108190004046F8F78FFC06F06BFF0146384606F0C4 +:1081A000DDFD70603068F8F741F90FA3D3E90023D3 +:1081B000F8F790F9F8F728FC06F004FD1C4F38801A +:1081C0007068F8F733F908A3D3E90023F8F782F9C8 +:1081D000F8F71AFC06F0F6FC7880082002F02CF97B +:1081E000144E58B30B482AE03B597E90A9E78140D2 +:1081F000342100204C21002024200020E80F002002 +:1082000068210020C81F00205C21002012000020EF +:108210006C210020041000201C0000207C1B00208A +:1082200004210020D40F002013220020D80F0020AA +:10823000D00F002032210020181000204048FFF706 +:10824000F3FB30804846FFF7D3FD3E4A92F8A83052 +:10825000002B4FD0206867680146F8F733FD394698 +:1082600006463846F8F72EFD01463046F8F722FC60 +:10827000A468064621462046F8F724FD014630460C +:10828000F8F718FC06F0F4FE01462046F8F7CEFD9C +:108290002D490646F8F7BEFE2C4C10B10023238072 +:1082A00028E0304606F00AFD294B1968F8F70AFD68 +:1082B00006F088FCB0F5617FA8BF4FF46170F8F755 +:1082C000A3F81DA3D3E90023F8F72EFAF8F79CFBD7 +:1082D00006F0B6FC1B4B064693F8A800F8F79EFC88 +:1082E0003146F8F7EFFC06F06DFC208002E03880A4 +:1082F0007880B880174B5B79012B174B06D02A8802 +:108300001A806A885A80AA889A8010E0134AB5F9C0 +:108310000410B2F9000001EB4001032091FBF0F1E1 +:1083200089B211802A8899801A806A885A8009B097 +:10833000BDE8F08FAFF30080A2EB0FE5DD169640AD +:108340001C000020C81F00208FC2753C2C1000208C +:10835000642100207C1B0020E00F0020D60F0020AD +:10836000044A0023136053609360034A1360034A76 +:10837000136070473C21002024100020F80F0020DB +:10838000028840F23E6302F21F3292B29A4208D84B +:10839000408800F21F3080B298428CBF002001203C +:1083A00070470020704700002DE9F04707462D4830 +:1083B00089469046FFF7E4FF002851D02A4B4FF43E +:1083C000FA721868294B2A491B682A4CC01AFCF714 +:1083D00041FC0A21FFF7FDFCE3798022584326493E +:1083E00090FBF2F04FF49672FCF734FCC71B607BF5 +:1083F00020237843204990FBF3F04FF49672FCF76A +:1084000029FCE37D1D4D5F43082397FBF3F72B68A1 +:108410004FF448321A498246F8182860FCF71AFCD3 +:108420000646286094F82100F8F7F8FB4146044618 +:108430004846F8F73FFB01462046F8F743FC4FF06B +:108440007251F8F73FFCF8F703FE6FF095019622A2 +:10845000FCF700FC4FF4806396FBF3F6301A5044AF +:10846000BDE8F087D00F00205821002054210020C3 +:108470000CFEFFFFC81F0020D4FEFFFF14100020D9 +:1084800000E0FCFF2DE9F04F85B0FEF729FC674BBB +:1084900046F2A7121E68861B964240F2C280186000 +:1084A000FEF7A0F8624C28B9FEF752F9614A0023A2 +:1084B00023601360FEF700F95F4B604918600246C5 +:1084C000086800930192F8F7A5FB5D490746F8F7A5 +:1084D000F9FB5C4982468868F8F7A0FB5A490546D3 +:1084E0000868F8F79BFB01462846F8F79FFC5749B8 +:1084F00005460968F8F7E6FB3946F8F7E3FB4FF065 +:108500007C510390F8F7DEFB5146F8F7DBFB276858 +:10851000844651463846CDF808C0F8F7D3FBDFF85B +:108520004CB1DDF808C0DFF80C81DBF87090014633 +:108530006046F8F7BFFAD8F80010F8F7BBFA4946DA +:10854000F8F7C0FB019A82461046F8F767FB4946E8 +:1085500002464FF07E500192F8F7AAFA019A0146BE +:108560001046F8F7AFFB01465046F8F7A3FAC8F8F3 +:108570000000F8F76DFD364A039910603846F8F7A9 +:1085800099FA344F2060FFF7EBFE009B3868D3F870 +:108590000080C0EB0800F8F741FB2F49F8F792FB89 +:1085A00081463046F8F736FB01464846F8F73EFC70 +:1085B000F8F74EFD4FF496722849C7F80080FCF793 +:1085C00049FB0A21FFF705FCDBF86C602168804657 +:1085D0003046F8F777FB07464046F8F71FFB314671 +:1085E00080464FF07E50F8F763FA01464046F8F7B0 +:1085F00069FB01463846F8F75DFA206006F0E2FABA +:1086000005210646FFF7E5FB154C164B2946186079 +:1086100022683046FFF7C8FE134B25601860012022 +:1086200000E0002005B0BDE8F08F00BFCC0F0020B7 +:10863000C80F0020301000207C0D0020F80F002013 +:10864000BD3786353C210020241000204821002021 +:1086500054210020FC0F002000247449D4FEFFFFA9 +:1086600000100020F40F002028100020C81F002058 +:1086700010B5054C00202188FAF770FD61880120B3 +:10868000BDE81040FAF76ABD2800002010B5094C7B +:1086900020600948016009490A60094A1360094AD3 +:1086A000029B1360084A039B1360084A049B1360F3 +:1086B00010BD00BF3C100020181100201C1100202C +:1086C00048100020441000205010002014110020F9 +:1086D0000A4B1A6802EBC002D379FF2B07D0084976 +:1086E0000978994203D9074A32F8130004E00728B1 +:1086F000D4BF908840F2DC5000B270473C1000209C +:108700006A2200206E220020054B1B6803EBC0008C +:1087100090F9063019420CBF01204FF0FF3070472E +:108720003C10002010B500244FF48040FCF722F8E4 +:1087300008B1054B00E0054B1B68054A9B88A35216 +:108740000234182CF0D110BD181100201C1100208B +:10875000902100202DE9F0413B4BDFF80481C4005B +:10876000187008EB04035B78384E054620200F464E +:108770003360FBF7FFFF424608B101233360162D3B +:108780001AD1002438590021F8F730FC28B14FF4F1 +:108790008040FBF7EFFF48BB24E02D4E3B192644F9 +:1087A0000FCB86E80F002B4B10341A78C02C02F147 +:1087B00001021A70E6D1EAE7144412F83570254B2D +:1087C000D4F804E01F70BEF1000FE0D00024BC42DA +:1087D000DDDA1F4E23011E4473440FCB013486E8BB +:1087E0000F00F4E7082D1C4B24D125E0194B1F780E +:1087F000012FF7D9194C0026BE4204F11004F1DA1A +:1088000054F8100C4FF07C51F8F75CFA4FF07C51A3 +:1088100044F8100C54F8140CF8F754FA4FF07C514B +:1088200044F8140C54F80C0CF8F74CFA013644F8E0 +:108830000C0CE1E70E2D01D1012200E000221A7498 +:10884000BDE8F041FFF76EBF40100020201100206E +:10885000541000204E100020132200205C10002035 +:10886000582301082DE9F0418C46461C00230022C4 +:108870004CF803201033C02BF9D10B4B03EBC6028D +:10888000576898466FB1002418F836309C4208DAD1 +:1088900023010CEB03053B440FCB013485E80F00AB +:1088A000F2E7BDE8F08100BF58230108284B10B55E +:1088B0001B68002B4AD0274B1B78013B142B3DD85B +:1088C000DFE803F00B3C3C24403C3C1C3C3C3C3C83 +:1088D0003C2C3C3C3C3C3C242C001F4B1B685B78F4 +:1088E00033B11E4B00205989BDE81040FAF736BC61 +:1088F0001B4B98780028F4D10146F5E7174C00206F +:10890000E188FAF72BFC01202189EDE7134C0020C8 +:108910002189FAF723FC01206189E5E70F4C00204B +:10892000E188FAF71BFC01202189FAF717FC0220E5 +:108930006189FAF713FC0320A189D5E72020FBF712 +:1089400019FF18B1BDE81040FFF792BE10BD00BF7F +:108950002011002040100020481000202800002096 +:108960001322002010B50023D8B25C1C054B1B78E5 +:10897000834206D9044B33F81010FAF7E3FB234681 +:10898000F2E710BD4E10002078210020064B1A7827 +:108990000023D9B2914204D2044921F813000133D3 +:1089A000F7E7FFF7DFBF00BF4E100020782100205F +:1089B0002DE9F74FA94E3378032B0FD9A84BA94CBB +:1089C000B3F904206FF06301002AB8BF5242891A3C +:1089D000B4F904006432FCF73DF9A0803778012F28 +:1089E0001ED8A14AA14C13789046013B142B00F2EB +:1089F000D281DFE813F09100D001D00168009F0020 +:108A0000D001D0012901D001D001D001D001D00185 +:108A1000BD00D001D001D001D001D0019201A90147 +:108A20008F4B9349B3F806A08E4B0968B3F80280C8 +:108A3000B3F80090B3F904B08E4C01910025BD420B +:108A400004F11004CDD20FFA8AF0F8F7E7F854F8E1 +:108A5000101CF8F737F903460FFA88F00093F8F77F +:108A6000DDF854F8081CF8F72DF9009B014618466C +:108A7000F8F720F803460FFA89F00093F8F7CEF8DC +:108A800054F80C1CF8F71EF9009B01461846F8F73D +:108A900011F8019A034692F90000009340420BFB43 +:108AA00000F0F8F7BBF854F8041CF8F70BF9009B3A +:108AB00001461846F7F7FEFFF8F7CAFA6E4B23F89F +:108AC00015000135BBE702210420FFF71DFE654DAF +:108AD0000121AF8878431FFA80F90420FFF714FEC4 +:108AE0006D8800FB05901FFA80F90420FFF7F0FD68 +:108AF0004844208102210520FFF706FE784301212A +:108B000087B20520FFF700FE00FB057087B2052045 +:108B1000FFF7DEFD38440BE005200121FFF7F4FDEF +:108B2000504B9D88684385B20520FFF7D1FD28444E +:108B3000608130E1514B00201D68FFF7C9FDDFF86F +:108B4000549195F90630B9F902203227534393FB2B +:108B5000F7F3184420800120FFF7BAFD95F90E3095 +:108B6000B9F90020534393FBF7F73844608012E1D2 +:108B7000434B9A789946434B1B6812B99B88E38113 +:108B800007E0374A1988B2F906005A88FCF762F8FC +:108B9000E081394BE2893C4F1A803B68374D1B78A6 +:108BA00043B30220FFF794FD2B68B3F91010B3F91B +:108BB0001220FCF74FF8354B1B685989344B081AC3 +:108BC0001A8800B20FFA82FE864503DA3868007808 +:108BD000024403E003DD38680078121A1A802A681C +:108BE000B3F9003092F916205343642293FBF2F359 +:108BF0001944A18099F80A3063B1194B1A88D5F845 +:108C000000A0E28022819A88184F62815B88032548 +:108C1000A38101E0134BF1E70AEBC50393F906309A +:108C2000B7F90690284609FB03F9642399FBF3F989 +:108C3000A7F80690FFF74CFD01354844072DF88052 +:108C400007F10207E8D1A6E00D4B9A781F460D4BBD +:108C50001B680ABB9B88E38126E000BF4E10002002 +:108C60003C2200202221002040100020280000206B +:108C70004810002054100020782100203C100020D3 +:108C8000132200201C11002044100020501000204E +:108C90004C100020D00F0020B54A1988B2F9060008 +:108CA0005A88FBF7D7FFE081B24BE289B24D1A80B8 +:108CB000BB7A032001211BB1FFF726FDAC4F02E078 +:108CC000FFF722FDAD4FB7F80290022100FB09F03B +:108CD0001FFA80FA0320FFF717FD3F88012100FBF0 +:108CE00007A0E8800420FFF70FFD00FB09F0022138 +:108CF0001FFA80F90420FFF707FD00FB0790288189 +:108D00000320FFF7E5FCE3881844E0800420FFF728 +:108D1000DFFC2389184420813DE001210420FFF776 +:108D2000F3FC964D6F88784387B204202781FFF7C4 +:108D3000CFFC3844208101210520FFF7E5FC2D8878 +:108D4000684385B26581EFE68C4B0325B3F804A038 +:108D5000994628460221FFF7D7FC00FB0AF00121C3 +:108D600087B22846FFF7D0FCC5F106035B0839F847 +:108D7000133000FB037087B224F815702846FFF704 +:108D8000A7FC384424F815000135072DE1D1784BB4 +:108D9000DA88784B1A802020FBF7ECFC784F00280B +:108DA00049D00020FFF794FC208081460120FFF786 +:108DB0008FFC744B704D1B7A6080002B3BD0724B44 +:108DC0001B681B7813F0020F704B1ED0D7F800E021 +:108DD000B3F900109EF90E209EF906E0B3F90230B7 +:108DE0004A43CEF1000E03FB0EF3322192FBF1F267 +:108DF0006FF0310E92B293FBFEFE9644F14493FB6A +:108E0000F1F1A5F800900A4413E03968B3F902E0E3 +:108E100091F90620B3F900300EFB02FE32229EFBD0 +:108E2000F2FEF144A5F8009091F90E104B4393FB2C +:108E3000F2F21044688000253B68605F03EB850216 +:108E400033F92510B2F90220FBF704FF6053023515 +:108E5000102DF1D14C4B1B681B785B0704D4454D9A +:108E600032782F8801231CE098F800300E2B0AD0AE +:108E7000082B08D0464A02EBC3035B78002B14BFD3 +:108E80000225002500E004250024424B601903EB75 +:108E90004403C0B219890134FAF760F9042CF4D103 +:108EA000DDE7934208D235F913103FB2B942A8BFAB +:108EB0000F46BFB20133F4E70024A1463378994549 +:108EC00074D2DFF8E0803AB2D8F800305B889A427A +:108ED00003DD2A5BDB1B13442B534FF48040FBF76D +:108EE00049FCDFF8C4B02B4BC0B1B3F90620DBF866 +:108EF00000305B899A42284B06DD1A68D8F80030AA +:108F00005188285F5A8805E0D8F800201B689188AE +:108F1000285F1A88FBF79EFE28531FE0D8F8002030 +:108F2000285F118852880093FBF794FE009B28531A +:108F3000B3F90620DBF80030DFF868A09B8905EB69 +:108F400004089A420ADA1020FBF714FCDAF8003021 +:108F500008B91B8800E09B88A8F800300F4B9B786D +:108F600013B90F4BE35A2B5309F101090234A5E75A +:108F70003C2200207821002028000020222100200F +:108F80003C1000202522002014110020D00F0020CA +:108F9000582301086E2200201811002013220020FF +:108FA000902100201C1100205010002003B0BDE8CB +:108FB000F08F00BF024B1868003018BF01207047C7 +:108FC0002011002044F25063984203DDA0F50C40CC +:108FD000A0387047034B9842BCBF00F50C40A0304E +:108FE000704700BFB0B9FFFF10B5044C00232070DC +:108FF0002361FDF78FFE606110BD00BF601300208C +:1090000010B5F7F70BFE00210446F8F717F808B182 +:10901000204601E004F100400549F7F707FF054944 +:10902000F7F750FE05F098FD034B186010BD00BF28 +:109030008096184B35FA8E3C38000020F8B5101A8F +:109040000C461F46F7F7EAFD0546381BF7F7E6FD25 +:10905000174B079E1968F7F735FE29460446284640 +:10906000F7F730FE214607462046F7F72BFE01466C +:109070003846F7F71FFD05F0FBFF0E49F7F722FE14 +:10908000F8F70CF8069B2146186005F1004005F042 +:1090900065FE0949F7F716FE0849F7F70BFDF7F7E4 +:1090A000D7FF0028BCBF00F50C40A0303060F8BDF1 +:1090B000380000202C7D8E3FA00CB34500A00C464C +:1090C000F8B51D4614460E46F7F7A8FD6968F7F790 +:1090D000F9FD3146F7F7F6FD2168F7F7EBFC206064 +:1090E000F7F7B6FFED68074605F10040F7F7B0FF68 +:1090F00006462846F7F7ACFF314602463846FBF7EE +:10910000A9FDF7F78BFD2060F7F7A2FFF8BD00007F +:1091100030B5002213460E49CC5C0D469CB12E2C76 +:1091200004D1013378B11D4400242C540A24624335 +:10913000C95CA1F13004092C9CBF303A52180E2BA7 +:1091400003D80133E7E7104630BD002030BD00BF33 +:1091500007130020014B1860704700BFD412002095 +:10916000F8B52B4B2B4C1B7813B1012B0AD04CE0DC +:109170006278294B03EB0213284A59681068FDF7FF +:1091800063FD3FE0254D2868FDF763FD2E4600286E +:109190003BD02378012B1ED1FDF7BCFD6369064649 +:1091A000C31A632B33D92369042B12D81A4F2868AA +:1091B00007EB03135968FDF747FD6378286807EB51 +:1091C0000317B968FDF72BFD23696661013323613D +:1091D0001BE0022017E023693BB962780E4B286838 +:1091E00003EB02135968FDF72FFD2369094D8B2B03 +:1091F00008D80B4A3068D15CFDF70CFD2B690133B0 +:109200002B6102E00320FFF7EFFE00236360F8BD4F +:10921000011300206013002008280108CC12002050 +:109220007A27010810B50B4CE37A8BB10A4B1B78F7 +:10923000042B0DD9094A0A4B1068526818605A600D +:10924000FFF7DEFE074B1A88074B1A8001232373B2 +:1092500010BD00BF1322002000220020E8210020C2 +:10926000CC21002032210020EC1200200000000060 +:109270002DE9F04F994B8BB01B68BBB9984C237804 +:10928000013B032B00F2CB85DFE813F08F058F0540 +:10929000A90592052068FDF7D2FC924B04461B7885 +:1092A000012B00F0DD8008D3022B06D08B4C206808 +:1092B000FDF7C0FC0028EDD1E0E7242C07D18A4A55 +:1092C00000231370894A1370894A1370C4E02C2C50 +:1092D00002D02A2C40F08380844E864B3278824D17 +:1092E000002098542A788449B2B90A701A78472A1B +:1092F00068D15A78502A65D19A78472A40F07E85FD +:10930000DA78472A40F07A851A79412A40F0768542 +:1093100001220A7000F072BD097801293AD1022AAF +:1093200005D1184601F02EF8744B18604AE0032A64 +:1093300007D11B78532B45D1704B1A6852421A60E3 +:1093400040E0042A05D1184601F01CF86B4B586028 +:1093500038E0052A07D11B78572B33D1674B5A6861 +:1093600052425A602EE0062A07D11A78644B302AFE +:1093700094BF00220122DA7224E0072A04D1FFF709 +:10938000C7FE604B18701DE0092A1BD1FFF7C0FE15 +:109390005D4B16E0022915D1072A0CD10120FFF7F9 +:1093A000B7FE41F2184358434FF47A72B0FBF2F320 +:1093B000564A138006E0082A04D10120FFF7A8FED0 +:1093C000534B18802B782A2C03F101032B704FF09C +:1093D0000003337037D14F4B01221A703CE00D2C43 +:1093E0004C4B01D00A2C24D11A78F2B141490878AB +:1093F0004978A0F13002D2B2092A84BFA0F1370225 +:10940000D2B202F00F021001A1F13002D2B2092A49 +:1094100084BFA1F13702D2B2354902F00F020244F3 +:109420000978D2B28C1A62426241002119707AB96D +:1094300012E02E490A780E2A03D8501C08702D49D4 +:109440008C541B7843B92A4B1A7854401C7003E0A3 +:10945000294B1B78012B00D0002303F0010358E1B6 +:109460002D4B00221978082900F25281DFE801F023 +:109470000A05111927607D96A100622801D10222F8 +:1094800005E01A70B52C40F043811A7801321A7049 +:109490003EE103221A70214B1870214B1870214BAA +:1094A0000BE01F4904221A701E4B0A7818782244D8 +:1094B000D2B20A7002441A701B4B1C7028E1184982 +:1094C00005221A70174B0A7818782244D2B20A7013 +:1094D00002441A70154B1C801AE100BFCC12002008 +:1094E00060130020011300205413002006130020F5 +:1094F000D01200200713002000130020E8210020D4 +:109500001322002000220020BA210020BE210020CA +:10951000B4120020841100204E1100205C130020A2 +:10952000C8120020EA1200204D110020E81200208D +:10953000624906221A70624B0A7818782244D2B225 +:109540000A7002441A705F4B1A8802EB0424A4B21A +:10955000B4F5007F01D81C8003E000221A805A4B2A +:109560001A705A4A00231380D3E05448544A0178B1 +:1095700015782144C9B201702944117053490A88F1 +:10958000C72A9CBF52488454013292B20A804D4986 +:109590000988914240F0BC80072278E708221A70BF +:1095A000464B1B78834200F0B380474A0023137078 +:1095B000AFE01A70424B1B78834240F0A980454BC4 +:1095C0001B78062B39D004D8022B12D0032B24D0C1 +:1095D0009EE0122B44D0302B40F09A803C4B1A79FD +:1095E0003D4B102A88BF10221A701978384A002380 +:1095F00044E0374B394A59685160996811601A69DB +:109600004FF47A7392FBF3F2354B1A80354B1A788C +:10961000354BDA720122354B20E02D4A537913F095 +:10962000010303D01379D81E434243412D4A1370DE +:10963000002B38D12C4AD37235E0254BDA7A12F060 +:10964000010203D09A7AD11E4A424A4125490A7042 +:109650000AB92549CA7293F82F20254B1A7022E0C7 +:109660001B4B24495A690A809A6942F2107392FB93 +:10967000F3F2214B1A800122204BEFE78B4202F1DB +:109680000C0210DA12F8044C1D481C5412F8034C5A +:109690001C481C5412F8014C1B481C5414781B48DD +:1096A0001C540133EAE711490B788BB3134B1A783A +:1096B00072B300221A700A7001232AE0C812002037 +:1096C000EA120020E81200204E110020961300201C +:1096D000EC1100204D11002001220020E821002083 +:1096E000BA2100208013002013220020DC12002069 +:1096F00000220020BE210020B41200205D130020B3 +:10970000A8210020D6210020F021002002220020E4 +:109710000023002B3FF4CAAD8B4CA368E360FDF738 +:10972000F9FAA060202000F091FE884B884C1A784E +:10973000012A0CBF002201221A70E37A002B3FF4A9 +:10974000B5AD844B1B78042B7FF6B0ADA37803B97D +:109750002373227B12B90BB1FFF764FD7E4B4FF0F0 +:10976000050E1A787D4D013292FBFEFE0EEB8E0E39 +:10977000CEEB020E83F800E0794B1B780593794B12 +:1097800003EB8E0E0023784A78499858DFF81C8244 +:10979000774E585090FBF8F19951764EDFF81092C1 +:1097A00006FB010003EB830A5EF80A6053F80970B8 +:1097B00042F2107CBF1B90FBFCFC05264EF80A0011 +:1097C000384443F8090090FBF6F008FB01016A48B1 +:1097D0001FFA8CFC1950059803EB020B012825F8A1 +:1097E00002CF164606D1ACF1020CBCF5797F98BFCA +:1097F000CBF800100433082BC5D1FDF78BFA5F4F6F +:109800005F4D3B68C01AF7F705FA5E49F7F70EFBA4 +:109810002860FDF77FFA38602F684FF07E51384698 +:10982000F7F7EEFB08B94FF07E5706AA2F60564BAC +:10983000009207AA019296E803000CCBFFF7FEFB0B +:10984000069A64235149B2FBF3F207980A80504A02 +:1098500090FBF3F31380237B0BB90B801380DFF8AD +:1098600054A14C4F9AF80030002B36D029684FF0A5 +:109870007E50F7F7DBFA3B6880463068C01AF7F78E +:10988000CDF94146F7F71EFAF7F7E2FB7B681FFABE +:1098900080FB70680FFA8BFBC01AF7F7BFF93E4BDD +:1098A0001968F7F70FFA4146F7F70CFAF7F7D0FB0C +:1098B0003A4B00B2B3F902204FF0020E8118B3F90F +:1098C000002037485A4491FBFEF192FBFEF289B228 +:1098D00092B24180028059801A8001238AF80030B8 +:1098E00071683068237A7960386023B9184BDB7966 +:1098F000002B3FF4DBACDFF8C0B0DFF8C080294CB0 +:10990000CDF800B0CDF8048094E80C00FFF796FB8A +:1099100073686068244FC01AF7F780F91E4BBA4687 +:109920001968F7F7CFF9F7F793FB22683368786087 +:10993000D31A3B600A4B93F90030012B40D0022B25 +:1099400000F0D980B2E400BF60130020841300202F +:109950001322002000220020941300201413002062 +:109960004C11002024110020E82100207813002051 +:1099700030130020806967FF7C110020F412002062 +:109980002C13002000007A44CC210020C8210020A4 +:10999000D4210020E01200203800002038130020DD +:1099A0003C130020F81200208C13002080969800B1 +:1099B0004813002098130020501300204413002067 +:1099C0007D4D00245AF81460DFF830923046F7F7E6 +:1099D00025F97A4B7A4F1968F7F774F9F7F738FBDE +:1099E00034F809B0774BCBEB00001FFA80FB24F86A +:1099F00003B00FFA8BFB5846F7F710F93968F7F701 +:109A000061F9F7F725FB704A1FFA80F811680BEB34 +:109A100006002A463B46FFF753FB6C4EBF686A4B75 +:109A200040445AF814B0A053686804971F68C0EB0C +:109A30000B00F7F7F3F83946F7F7F8F9644B2861AC +:109A40001B6884469878D5F80880CDF80CC0F7F7E5 +:109A5000E1F8F6F7EBFC56A3D3E90023F6F73AFD5D +:109A60000B4602465B490020F6F75EFEF6F7CCFF98 +:109A70003946F7F71FF801463846F7F7D7F9DDF80A +:109A80000CC0074641466046F7F712F801463846D3 +:109A9000F7F718F901464046F7F70CF8C5F804B097 +:109AA00001462861A8600498F7F70CF9F7F7D0FA97 +:109AB00049494FF4FA62FBF7CDF834F809304749C9 +:109AC00031339BB2622B335B98BF0020184480B2C5 +:109AD000305340F6B83200B2FBF7BCF80A226243BA +:109AE000305355F8141B3E4B0234042CD1507FF4F4 +:109AF00069AFFFF7DBBB364BDBF800701B68394CF6 +:109B0000B3F908607B089E4228BF1E46B4F8009057 +:109B1000B6B232B20FFA89F39A4208DD32492868A8 +:109B2000F7F7D0F8F7F794FA484486B226802F4B1F +:109B3000D8F800401B682E4DC3EB04084046FFF7E1 +:109B400041FA0028D8BF404241F293139842CCBF5B +:109B500000200120002853D04046F7F75FF8254940 +:109B6000F7F7B0F805F06CF880463846F7F752F88A +:109B700001464046F7F7A6F8F7F76AFA1E4B80B29F +:109B80001880164900B240F6B832FBF763F848F681 +:109B9000A0432044984203DDA0F50C40A03804E027 +:109BA0000028BCBF00F50C40A030286029E000BFB1 +:109BB000182D4454FB21194054110020B8120020E4 +:109BC0001C130020401300202C13002088110020BB +:109BD000D41200200000F03F30F8FFFF48F4FFFFF0 +:109BE0009C110020821300200000C842581300205E +:109BF000F0120020D3023739861100203C130020D8 +:109C00002C6028688A4DC0F50C502830F7F706F80C +:109C10008849F7F757F8044604F09EFF099020465C +:109C200005F00EF80024089030B2F6F7F7FF08AB05 +:109C300053F81410F7F746F87F4B0746185FF6F70E +:109C4000EDFF01463846F6F733FFF7F701FADFF884 +:109C50002C9280B24FF47A7224F80900774900B24E +:109C6000FAF7F8FF80B20FFA80FA754F24F809006E +:109C70005046F6F7D3FF3968F7F724F8F7F7E8F915 +:109C8000DFF8FC8180B22A463B46D8F800100490E9 +:109C90005046FFF715FABF68844634F909A0686892 +:109CA0000597D8F80070C0EB0A00CDF80CC0F6F7A5 +:109CB000B5FF3946F7F7BAF8DFF8C8912861D9F847 +:109CC000003083469878F6F7A5FFF6F7AFFB56A36A +:109CD000D3E90023F6F7FEFB0B4602465949002064 +:109CE000F6F722FDF6F790FE3946F6F7E3FE014659 +:109CF0003846F7F79BF8D5F808800746414658469E +:109D0000F6F7D6FE01463846F6F7DCFF0146404638 +:109D1000F6F7D0FEDDF80CC0049F01462861A8606C +:109D2000C5F804A005986744F6F7CCFFF7F790F95B +:109D30003844454F80B2E053444940F6B83200B24F +:109D4000FAF788FF0A226243385355F8141B404B38 +:109D50000234042CD1507FF467AFD9F800301A795F +:109D600032B13C4A1168642291FBF2F13A4A118007 +:109D70003A4A1B8812689A420ED9394B1868394BF7 +:109D80001B68C01AFFF71EF942F210730028B8BF13 +:109D9000404298427FF78AAA334B01221A70334B14 +:109DA0001A882D4B1A80FFF781BAFFF7D9F936E0F0 +:109DB000636805220133636063780133DBB2B3FB70 +:109DC000F2F202EB82029B1A6370FCF7A3FF284AAF +:109DD00000231370274AA060D37201200BE0FCF728 +:109DE00099FFA36840F6C412C01A904217D92020E8 +:109DF00000F034FB0420FFF7F7F810E09B781E4AD0 +:109E0000522B7FF4DFAAD3784D2B7FF4DBAA137992 +:109E1000432B7FF4D7AA02230B70FFF7D3BA0BB002 +:109E2000BDE8F08FAFF30080182D4454FB2119409A +:109E30009C110020D30237393C13002018FCFFFF8F +:109E40008C1100200000F03F8811002048F4FFFF33 +:109E500054110020F0120020202100205013002077 +:109E600044130020581300204C110020EC12002055 +:109E7000002200201322002007130020401300209E +:109E80002C130020D412002010B500231A460E49CE +:109E9000002050520D490E4C50520E495052002194 +:109EA00019511C446060A1600B4C023219511C44D2 +:109EB0006060A160094C042A19511C446060A160D3 +:109EC00003F11403E3D110BD02130020D8120020C7 +:109ED000C411002088110020541100209C11002082 +:109EE00070B504460079F6F795FE1E49F6F79EFF19 +:109EF0001D4D1E4E2860A07BF6F78CFE1949F6F723 +:109F000095FFEE6068606079F6F784FE1849F6F711 +:109F10008DFF184D2860E07BF6F77CFE1149F6F7BF +:109F200085FF6860607EF6F775FE1349F6F77EFFE1 +:109F3000EE60A860A079F6F76DFE0D49F6F776FFA2 +:109F40000E4D2860207CF6F765FE0649F6F76EFF99 +:109F50006860A07EF6F75EFE0749F6F767FFEE60E1 +:109F6000A86070BD0000C842B81200200000FA448A +:109F7000000020411C13002000007A448C110020B6 +:109F80002DE9F7439946214B214C18600025C36801 +:109F90006570204E06EB05104068B046984206D02A +:109FA0000135EDB2042DF4D90023637000E0657033 +:109FB000194B1A4E002031701A60FFF715F8FCF7A4 +:109FC000A9FE33780025AB42A06048460CBF0127AC +:109FD00003276560FFF784FF66783B4608EB0616AB +:109FE000009510202946726801F084FD0C4B186022 +:109FF00030B94FF4807003B0BDE8F043FAF762BDAA +:10A00000012003B0BDE8F043FEF7EEBF8813002047 +:10A010006013002008280108D4120020011300203A +:10A02000CC120020F7B5244B1D78032D3ED1202003 +:10A0300001F034FC214E044638B101F0DDFD3368F7 +:10A0400020461969FCF700FE09E0336800902146BC +:10A050001A6920202B4601F04DFD044640B3184BF1 +:10A0600008221A6110221A61164D2868FCF7E2FDD9 +:10A0700050B1134E082777612868FCF7E0FD0146D0 +:10A080002046FCF7C7FD37612046FCF7D3FD0028CA +:10A09000EAD00B4E1027776120462D68FCF7CFFDE4 +:10A0A00001462846FCF7B6FD3761DDE7022000E0F7 +:10A0B000284603B0F0BD00BF6013002088130020C5 +:10A0C000000C0140CC120020F7B50368174C184D66 +:10A0D00023600B68174E63600068FEF791FF95E8F8 +:10A0E0000300154B0196009394E80C00FEF7A6FFC1 +:10A0F0003668124B60681E606B68114FC01AF6F725 +:10A100008DFD104B1968F6F7DDFDF6F7A1FF22680B +:10A110002B687860D31A3B600B4B1E600B4B1B689F +:10A12000DA880B4B1A8003B0F0BD00BFF812002094 +:10A13000E82100204413002050130020F0120020DA +:10A140008C1300203800002058130020D412002067 +:10A15000821300202DE9F84F484BDFF834A1B3F902 +:10A160000000F6F75BFD4649F6F7ACFD044604F047 +:10A1700067FD0746204604F0EFFCDAF8003006469B +:10A1800093F80390DFF80C813E4DB9F1000F43D0F6 +:10A190003D4CB8F90200B4F802B00FFA8BF3C01AC4 +:10A1A000FEF710FFC9F100014A46FAF753FDB4F873 +:10A1B000009058446080B8F900000FFA89F3C01A83 +:10A1C000FEF700FFDAF80030DA785142FAF742FD84 +:10A1D00048441FFA80F9A4F80090B4F90200F6F799 +:10A1E0001DFD80460FFA89F0F6F718FD314604464A +:10A1F0004046F6F767FD394681462046F6F762FD90 +:10A2000001464846F6F754FC2049F6F70FFEF6F7EC +:10A210001FFF288040461DE0B8F90200F6F7FEFC5B +:10A220008146B8F90000F6F7F9FC31460446484685 +:10A23000F6F748FD394680462046F6F743FD0146CD +:10A240004046F6F735FC1149F6F7F0FDF6F700FF4A +:10A25000288048463946F6F735FD31460746204600 +:10A26000F6F730FD01463846F6F724FC0749F6F7C5 +:10A27000DDFDF6F7EDFE6880BDE8F88F32210020A5 +:10A2800035FA8E3C02130020D81200200000204135 +:10A29000D41200208811002038B5244CE37A2546DA +:10A2A000002B3CD0224B1B78042B38D9214B9A7AB7 +:10A2B0007AB1E379002B37D101221F48E2711F4A9E +:10A2C000011D13702372FFF7FFFE1D4B02221A704F +:10A2D00038BDDB7AE271BBB11A4B1B68588900F0BC +:10A2E000CBF888B1237AFBB9144A17481370174B7F +:10A2F00001251A685B68011D436025720260FFF743 +:10A30000E3FE0F4B1D7038BD00232B720B4B1A78E8 +:10A3100052B901221A70BDE83840FFF7B5BD084AAE +:10A320000023EB712B72137038BD00BF1322002085 +:10A330000022002025220020CC2100203C0000200B +:10A340004C110020D4120020C0210020E821002060 +:10A35000094B1A68821A002A0DDB084A1278042A6F +:10A3600009D900F5123000F5F8701860044BDA686E +:10A3700082F01002DA6070475011002000220020A5 +:10A38000000C0140294BF0B51D68024600F1100792 +:10A3900016781446AB195978013201F0040101F026 +:10A3A000FF0369B1BA42F3D10020F0BD1BB103EB4A +:10A3B00083035B00DBB210F8012B303A1344DBB2AD +:10A3C000221A022AF2DC002184420AD919B101EBD7 +:10A3D00081014900C9B210F8012B303A1144C9B2C9 +:10A3E000F2E72E2E14D1013404200022267802EB4D +:10A3F0008202AF197F7852007F0792B203D5303ABC +:10A400003244013492B2013810F0FF00EED100E086 +:10A410000022074806244143642000FB021205483D +:10A42000B2FBF4F200FB0320F0BD00BFB40100203A +:10A4300040420F0080969800034B1B6818420CBFE7 +:10A4400000200120704700BF9C130020024B1A68B7 +:10A4500010431860704700BF9C130020024B1A681D +:10A4600022EA0000186070479C130020014B186816 +:10A47000704700BF9C130020094BB3F90020002A4D +:10A48000B8BF5242824209DAB3F90230002BB8BF9A +:10A490005B428342ACBF0020012070470020704720 +:10A4A0003C22002010B544780078002303FB03F120 +:10A4B0001939614301F6C4115943414340F6C412AE +:10A4C00091FBF2F1034A22F813100133072BEDD16F +:10A4D00010BD00BF5C2200202DE9F0478278C678CD +:10A4E0001E4BC2F1640802EB820C54425FFA88F8FA +:10A4F0004FEA4C0CC6F16409A4B203F11807A5B2E7 +:10A5000028B2002804DC002D14BF1546012500E008 +:10A51000454600FB00FA6D430AFB06FA9AFBF5F587 +:10A520004D4468434FF00A0A90FBFAF0604480B251 +:10A5300058800D88B1F802A000B2C5EB0A0A00FBF2 +:10A540000AF04FF47A7A90FBFAF0054423F8025FA0 +:10A550000A34BB42A4B2D2D1BDE8F0874222002027 +:10A56000014B1860704700BF28140020074B1B6880 +:10A570001B7A032B09D8DFE803F00202040600F07F +:10A58000F3BB00F037BA00F01BBB70472814002063 +:10A5900008B5037A032B12D8DFE803F00202070C98 +:10A5A0000A490B4A00F0E8FB08E00849084A00F0B5 +:10A5B00029FA03E00549064A00F00AFB28B90820F9 +:10A5C000FAF780FA024B00221A6008BD6A220020C6 +:10A5D00020140020174B10B5186004460023608932 +:10A5E000154A98520233242BF9D1144B08201960D4 +:10A5F000FAF7C0F810B12046FFF7CAFF4FF48030D9 +:10A60000FAF7B8F820B120460D490E4A00F09AF941 +:10A610000120FAF7AFF828B109480A49BDE810400F +:10A6200000F09EB94FF40040FAF7A4F80028F3D1E7 +:10A6300010BD00BF281400206E2200201C14002032 +:10A640006A22002020140020037A032B09D8DFE8B7 +:10A6500003F00202040600F0C9BB00F001BA00F0EA +:10A66000D7BA00207047000010B5104C0023082016 +:10A670002370FAF77FF820B10D4B1868FFF7E4FF5D +:10A6800020704FF48030FAF775F810B100F050F9EF +:10A69000207023784BB14FF40070FAF76BF820B1BB +:10A6A000044B1B681B681B68984710BD24140020CE +:10A6B000281400201C140020054B1B782BB9054BD7 +:10A6C0001B68C01AC043C00F70470120704700BF0D +:10A6D000241400202C1400200E4A0F4B127802F094 +:10A6E000030202EB800223F8121003EBC00233F8DE +:10A6F000301053880B449188D2880B441344074A86 +:10A700009BB222F810301BB2042293FBF2F080B20D +:10A71000704700BFA0130020BA130020A21300202E +:10A720002DE9F04740F20120FAF724F828B1F8F7B4 +:10A73000F1FD8246F8F7FAFD01E04FF0010A00262C +:10A74000234BF4B21B78A34240D9224B224F1B6803 +:10A75000DFF88C802BB9D8F800305B8927F81430EB +:10A7600032E0D8F80020072C94BF12F80490A146DC +:10A7700017484946984705464FF40070F9F7FAFF25 +:10A7800048B1BAF1000F06D0144B48461B68294661 +:10A790001B68DB699847A5F2EE2240F2DC5392B2C7 +:10A7A0009A4288BFD8F8003048F2010088BF5D891E +:10A7B000F9F7E0FF10B927F8145005E020462946C4 +:10A7C000FFF78AFF27F814000136B9E7BDE8F087E4 +:10A7D0006A220020201400206E2200201C14002079 +:10A7E0002814002010B5064C237843B1054B1B6894 +:10A7F0001B681B689847FFF793FF0023237010BD69 +:10A80000241400201C140020024B1A7801321A7004 +:10A81000FFF786BFA013002008B500F59C400D4B44 +:10A82000203018604FF40070F9F7A4FF20B10A4BF4 +:10A830001B681B681B69984748F20100F9F79AFFEB +:10A8400018B9BDE80840FFF7CDBFBDE80840FFF7E5 +:10A85000DBBF00BF2C1400201C140020F8B50546F7 +:10A860000F46441E14F8011F49B1054E304606F04C +:10A87000E7FD0028F6D0861B631BBB55F2E7F8BD49 +:10A880005828010810B51F4B1A681C46127C3AB1B3 +:10A8900023681B7C5BB11C4A013B32F813001BE0B0 +:10A8A0004FF40030F9F766FF0028F1D110BD4FF4E6 +:10A8B0000030F9F75FFF78B1F8F7FEFC114B80B27A +:10A8C0001B685B7C012B07D103B2B3F57A7FC8BF4D +:10A8D000002000F57A7080B200B24FF47A72002145 +:10A8E000A0F57A70FAF7B6F9F6F798F90749F6F78E +:10A8F0009DFA0749F6F7E6F9F6F7D0FB054B188005 +:10A9000010BD00BF281400206E22002000007A44F1 +:10A9100000C07F446C220020014B33F811007047C7 +:10A920006E220020014B01221A7070473014002063 +:10A93000034B187810B100221A700120704700BF35 +:10A940003014002008230B700AB1024B1360012061 +:10A95000704700BF19A900080846F8F793BD00002A +:10A96000084B10B50B6004464FF40040F9F702FFA6 +:10A9700008B1082323700120F9F7FCFE08B10C236D +:10A98000237010BD59A90008034B53F8210040085B +:10A9900000F5777080B270473C14002038B504464B +:10A9A000FCF79EF90F4B40F6C4111A681860821A22 +:10A9B0008A420D4A84BF0021117013780BB90F2C05 +:10A9C0000FD10A48002101704BB1094D182B1D44CD +:10A9D00005F8014C03D101231170037038BD013318 +:10A9E000137038BD341400203814002039140020AE +:10A9F0006C140020024B4360836003234373704751 +:10AA0000A0860100F7B50025074605230E4614462B +:10AA10000E49009508200E4A01F06CF879890D4B1B +:10AA2000A1F57771186049002B460B4A9950043301 +:10AA3000302BFAD10CB1094B236000304FF00C03DE +:10AA400018BF0120337003B0F0BD00BF9DA90008FE +:10AA5000A0860100881400203C14002089A9000869 +:10AA6000344B10B51A780AB9002010BD00221A70B4 +:10AA7000314B9A7D1207F7D4587819782F4A00F095 +:10AA8000070441EA04211160997801F03F04640150 +:10AA900044EAD0005060D878800040EA91101979DB +:10AAA00001F0010440EA84209060587900F00F041E +:10AAB000E40144EA5101D160997901F07F04240155 +:10AAC00044EA10101061D879400040EAD111187A98 +:10AAD00000F0030441EA44215161597A01F01F0456 +:10AAE000A40144EA90009061987AC00040EA5111B4 +:10AAF000187BD161D97A00F0070441EA0421116280 +:10AB0000597B01F03F04640144EAD0005062987B15 +:10AB1000800040EA9110D97B1B7C01F0010403F016 +:10AB20000F03DB0140EA842043EA51019062D162C5 +:10AB3000012010BD391400206C1400203C140020AA +:10AB4000024B53F82100C0F3CF007047BC14002023 +:10AB500010B50446FCF7C4F8144B1A681860821A42 +:10AB6000B2F57A6F124A84BF00211170137823B9AD +:10AB7000A82C1AD10F490B7006E0022B02D10E4906 +:10AB80000C7001E0242B01D80C49CC540133DBB20A +:10AB90001370094A127852000532934205D1044BD2 +:10ABA00000221A70034B01221A7010BD8C14002071 +:10ABB000FC140020B61400209014002091140020F2 +:10ABC0004FF4E13343608360012343737047000017 +:10ABD00037B5002300930D46012314460820094988 +:10ABE0004FF4E13200F086FF074B18600CB1074BC1 +:10ABF000236000304FF0100318BF01202B7003B00A +:10AC000030BD00BF51AB0008B814002041AB0008B4 +:10AC1000134B10B51A780AB9002010BD00221A7023 +:10AC2000104B5B78012BF7D10F4B1A78102A84BF99 +:10AC300010221A700D4A19780023D8B2884202F106 +:10AC400002020AD212F8010C12F8024C40EA042463 +:10AC5000074840F823400133EFE7012010BD00BF53 +:10AC6000B6140020911400209014002094140020A9 +:10AC7000BC140020114B10B501221A700446FCF7D9 +:10AC80002FF80F4A014613681160C31A0D4841F2AC +:10AC90008832934203600C4B84BF00221A701B78E9 +:10ACA0000A4AE4B20F2BD45403D1094B01221A7083 +:10ACB00010BD054A0133137010BD00BF38150020C8 +:10ACC0005015002000150020041500203B15002021 +:10ACD000FE1400202DE9F0411C4B04781A781D4623 +:10ACE000FAB11B4B1E781B4B1F7802231A4803F145 +:10ACF0000108C25C324102F00F02A2420CD20B2AC0 +:10AD00000AD810F803C010F808000CEA070C00EB92 +:10AD10000C2C124840F822C00233102BE6D100233D +:10AD20002B708C420ED90E4B187860B10D4B1A78EF +:10AD30000A4B53F8210002B1400800F5777080B249 +:10AD4000BDE8F0810020BDE8F08100BFFE140020C6 +:10AD5000FD1400203A1500203B15002008150020A6 +:10AD600038150020391500204FF4E133436083602B +:10AD7000012343737047000013B5037A14465BB197 +:10AD8000012B13D1134A03201070134A07201070AF +:10AD9000124A13700C2308E00E4A022010700E4A6B +:10ADA000032010700D4A137007230B7000230093CB +:10ADB000082001230A494FF4E13200F09BFE094BC1 +:10ADC00018600CB1084B2360003018BF012002B09E +:10ADD00010BD00BFFD1400203A15002039150020D9 +:10ADE00075AC00084C150020D5AC0008014B187854 +:10ADF000704700BFFE140020014B1860704700BF71 +:10AE000058150020034B1B681878D0F1010038BF9B +:10AE10000020704758150020034B1B681878431E0C +:10AE200058425841704700BF58150020034B1B681B +:10AE30001878831E58425841704700BF58150020AB +:10AE400008B54FF40060F9F795FC20B10420BDE887 +:10AE5000084000F007BE08BD084B1B7863B1084BE3 +:10AE60001B685B7813B1074B187D01E0064B98789F +:10AE7000003018BF01207047012070475415002092 +:10AE800058150020252200201322002008B5FFF7C6 +:10AE9000B9FF18B1BDE8084000F082BAFFF7BCFF67 +:10AEA00018B1BDE8084000F04DBC08BD08B5FFF77B +:10AEB000A9FF08B100F0B0F8FFF7AEFF18B1BDE888 +:10AEC000084000F015BB08BD38B50D4B1B78B3B179 +:10AED000FFF7C2FF0B4B04461A781D4682420ED084 +:10AEE00050B1FFF78FFF08B100F0AEF8FFF794FF05 +:10AEF00020B100F03DFB01E0FFF7D8FF2C7038BD1A +:10AF00005C1500205515002008B50121042000F033 +:10AF1000B5FD0F4B1870FFF793FF0E4B1870FFF73E +:10AF200071FF18B10C4B186800F070F8FFF774FF50 +:10AF300018B1094B186800F0F3FAFFF777FF18B162 +:10AF4000054B186800F001FCBDE80840FFF7BCBFE6 +:10AF5000541500205C1500205815002008B50C4B36 +:10AF60001B789BB1FFF778FF80B1FFF74BFF08B16B +:10AF700000F0ACF8FFF750FF08B100F02BFBFFF733 +:10AF800055FF18B1BDE8084000F0E0BB08BD00BFA8 +:10AF90005C15002038B5064C05465E212068FBF79D +:10AFA00039FE20682946BDE83840FBF733BE00BFB4 +:10AFB00070150020024B5E211868FBF72BBE00BF06 +:10AFC0007015002010B50A4C5E280146206805D196 +:10AFD0005D21FBF71FFE20683E2105E05D2903D1BE +:10AFE000FBF718FE20683D21BDE81040FBF712BEBC +:10AFF0007015002010B50446C0B2FFF7E3FFC4F39C +:10B000000720BDE81040FFF7DDBF0000014B1860CE +:10B01000704700BF6815002010B5084B084C197820 +:10B020002068FBF71BFE074B20681968FBF70CFE36 +:10B0300020680421BDE8104000F05CBC67150020CA +:10B04000701500206015002073B5042000F026FC68 +:10B05000144C01462060144E144D90B143794FF4C6 +:10B060001651337083682B60FBF7EEFD20680221D8 +:10B07000FBF7F4FD2068042102B0BDE8704000F049 +:10B0800029BC0B4B4FF416521B6804209B7800938D +:10B09000022300F02FFD43792060337083682B601A +:10B0A00002B070BD701500206715002060150020EB +:10B0B0006815002008B5044B1868FBF7BBFDD0F1FC +:10B0C000010038BF002008BD701500202DE9F843AD +:10B0D000FFF7F0FF002800F04481FBF71BFEA24BB6 +:10B0E0001A68821A7C2A40F23C81A04E186033789C +:10B0F00000240133337004F12400C0B2FFF74AFF8B +:10B100009B4B33F91400F5F789FD9A4B05461888D7 +:10B11000F5F784FD01462846F5F788FE9649F5F7D0 +:10B12000D1FDF5F795FF013400B2FFF763FF032C63 +:10B13000E1D13020FFF72EFF904BB3F90000FFF76D +:10B1400059FFFFF737FF307810F0030729D18C4DF6 +:10B150001020FFF71FFF2B68642493FBF4F000B26C +:10B16000FFF748FF2120FFF715FF2B6893FBF4F052 +:10B1700004FB103484EAE470A0EBE47000B2FFF743 +:10B1800039FF1420FFF706FF7E4BB3F90000FFF7ED +:10B1900031FF1C20FFF7FEFE3846FFF72BFFFFF7BD +:10B1A00009FF33785B0740F0B6800220FFF7F2FE1C +:10B1B000754B0A25B3F9000090FBF5F0FFF71AFF75 +:10B1C0000220F9F7D7FA00284CD0DFF8CC816F4F76 +:10B1D00098F800303A7840F63401B2FBF3F24A4373 +:10B1E0006B4C2A21B2FBF1F22188062091FBF3F986 +:10B1F00003FB19194FEA09191FFA89F949EA0229CB +:10B200001FFA89F9C2F3032249EA0209FFF7C2FED5 +:10B210000FFA89F0FFF7EEFE228898F8003001322D +:10B2200092B292FBF3F103FB112323803B786E244F +:10B230005C43152394FBF3F43A204FF06408FFF7C6 +:10B24000A9FEB4FBF8F708FB17443846A4B2FFF791 +:10B25000D1FE05343B20FFF79DFE94FBF5F000B2D4 +:10B26000FFF7C8FE2020FFF7E7F8002851D0494C2F +:10B270001320FFF78FFE2368DFF82081002BB8BF73 +:10B280005B4293FBF8F000B2FFF7B4FE1B20FFF720 +:10B2900081FE23680A27002BB8BF5B4293FBF7F3BC +:10B2A00042F2107593FBF5F205FB123000B2FFF786 +:10B2B000A1FE2320FFF76EFE2368002BACBF4E20BB +:10B2C0005320FFF797FE1220FFF764FE6368002B00 +:10B2D000B8BF5B4293FBF8F000B2FFF78BFE1A2079 +:10B2E000FFF758FE6368002BB8BF5B4293FBF7F78C +:10B2F00097FBF5F305FB137000B2FFF77BFE2220EE +:10B30000FFF748FE6368002BACBF45205720FFF7CE +:10B3100071FEFFF74FFE3378282B22D1134B00220A +:10B320001A70FBF7F7FC4FF47A763C24B0FBF6F684 +:10B330001720FFF72FFEB6FBF4F5B5FBF4F004FB86 +:10B340001050000200B2FFF755FE1820FFF722FE52 +:10B3500004FB156000B2FFF74DFEBDE8F843FFF7B0 +:10B3600029BEBDE8F88300BF6C15002066150020DB +:10B370005C2100201200002000007A44F40F00201D +:10B380007C0D002032210020D0200020781B0020DE +:10B3900064150020E821002010000020A086010094 +:10B3A0004FF416507047000010B5054C2068FBF7AD +:10B3B00041FC18B12068FBF742FCF6E710BD00BF66 +:10B3C000B8150020DFF890C02DE9F043204E91FB26 +:10B3D000FCF406FB04180627C90F07FB08F84172A6 +:10B3E00092FBFCF106FB01261A4B04EB840498FB4C +:10B3F000F3F903FB19887E434FFA89F904EB8404BF +:10B4000009EB8404A4B28472240AC47296FBF3F498 +:10B4100003FB146301EB810164B201EB810164253C +:10B4200004EB810198FBF5F893FBF5F389B280F802 +:10B430000C80D20F4FEA2828C1734374090A1B12EB +:10B4400080F80D80827301748374BDE8F08300BFBF +:10B45000806967FF40420F008096980010B5174B37 +:10B46000174A1B78D27A0446837612B92D23C37605 +:10B4700010BD042B8CBF33233223C376114B93E8CA +:10B480000600FFF79FFF104B1A886423B2FBF3F30B +:10B4900003EBC3039B009BB2E3711B0A23720B4BAC +:10B4A0001B88E3741B0A2375094B1B8863751B0AF1 +:10B4B000A375084B1B88237710BD00BF0022002016 +:10B4C00013220020E8210020BE210020C8210020F6 +:10B4D000BA210020D4210020044A0023127883706E +:10B4E00003718277C377027543757047781B00201C +:10B4F00010B5084B084C19782068FBF7AFFB074BD9 +:10B5000020681968FBF7A0FB20680421BDE8104003 +:10B5100000F0F0B9BE150020B8150020A8150020D5 +:10B52000F8B5104C104B2C271860002120463A46E5 +:10B5300005F068FC8E2363707C26E0237D25E37094 +:10B54000267084F82B50094C002120463A4605F01D +:10B5500059FC8A236370A0232670E37084F82B5073 +:10B56000F8BD00BF7C150020C4150020C8150020C0 +:10B5700073B5042000F092F9134C01462060134E7D +:10B58000134D90B143794FF49641337083682B602B +:10B59000FBF75AFB20680121FBF760FB20680421C0 +:10B5A00002B0BDE8704000F095B900904FF49642AB +:10B5B0000123042000F09EFA4379206033708368F1 +:10B5C0002B6002B070BD00BFB8150020BE15002072 +:10B5D000A81500202DE9F843FBF782FB4C4D4D4A9E +:10B5E0002B680446C31A934206D94B48FFF774FFF1 +:10B5F0004A48FFF733FF2C60494E4A4F96F80090B7 +:10B60000B9F1000F0ED1DFF82881D8F80000FBF760 +:10B6100011FB012806D90228434D46D0FFF7C4FE8E +:10B6200001232B703D68DFF8FCC0002D6ED0377809 +:10B630003B4A3E4E3FB1336840F6B731E31A8B4286 +:10B640000BD8BDE8F88301231370394B0221186829 +:10B65000FBF704FB374B1F7024E0374F34483B782F +:10B660004BB900680121CCF800301370FBF7F6FAF3 +:10B67000FFF79AFE16E0013BD9B239702D4A2F4BE5 +:10B6800019B911784D1C157006E015F8011B1778D3 +:10B69000CCF800500F4417701A78006801321A7005 +:10B6A000FBF7B8FA3460BDE8F8832A78244B1AB166 +:10B6B0001C6085F80090B5E71B68E31AB3F57A6F54 +:10B6C000B0D30123D8F800002B70FBF7B8FA054679 +:10B6D000D8F80000FBF7B3FA802DA3D18A2802D056 +:10B6E0008E280AD09EE72020FEF7A6FE002899D0DB +:10B6F0003378002B96D1094B03E03378002B91D19E +:10B70000054B3B600C4B2D221A708BE7BDE8F8838C +:10B71000B01500203F0D03007C150020C815002047 +:10B72000B4150020781500203D000020AC15002045 +:10B73000B815002074150020BC150020BD15002090 +:10B74000C01500204FF496407047704702F0E6B8ED +:10B7500010B500230C245C430549DAB2615C8142D8 +:10B7600003D00133042BF5D11A46104610BD00BF9B +:10B7700040000020037A0022D0B2013213B1581EDB +:10B780000340F9E70A7AD9B2013312B1511E0A40D7 +:10B79000F9E7884294BF00200120704700487047B5 +:10B7A000AC28010800230549DAB2595C814203D074 +:10B7B0000133092BF7D11A4610467047612801085A +:10B7C0002DE9F74F137C81460E461446032B40D8D3 +:10B7D0000C225A43214903F1010A01EB020898F8AF +:10B7E000080019EA000F31D08B5C43B1012B06D061 +:10B7F000022B04D0032B14BF0425032500E01D46B3 +:10B80000174B4FEA051B402003EB0B070193F8F79A +:10B81000B1FF019B20B913F80B30023B012B15D966 +:10B82000737B13B13A7B134210D071687A689142EE +:10B830000CD3B168BA68914208D82570A760C4F8E3 +:10B840000480E66084F810A0204603E05FFA8AF3E3 +:10B85000BCE7002003B0BDE8F08F00BF400000202F +:10B860006C28010870B50A4C06460D46204600219A +:10B87000142205F0C7FA074804210C22064B05F0F4 +:10B880000BFB304629462246BDE87040FFF798BFC3 +:10B89000F41500204000002075B700080B4AA2F103 +:10B8A0003003197A81420BD00C339342F9D1084B03 +:10B8B000197A014004D10C339342F9D108467047FC +:10B8C0000BB1586870471846704700BF70000020E1 +:10B8D0004000002010B50023054A1A4454688442F1 +:10B8E00003D00C33302BF7D10022517210BD00BFB2 +:10B8F000400000200023064A1A445168814203D0C8 +:10B900000C33302BF7D1002200235372704700BF55 +:10B910004000002038B5002205461D491301585C3F +:10B92000A84204D00132062AF7D1002038BD194CB4 +:10B930000B44042D0FCB84E80F001BD007D8012D3A +:10B940000FD0022D21D1144B1B689B6810E0102DE5 +:10B9500015D0202D09D0082D17D12046FEF706FE60 +:10B9600011E00D4B1B685B680CE00B4B1B681B69FF +:10B97000636007E0FFF78AFA6060A06003E0064BAF +:10B980001B68DB68A360204638BD024838BD00BF95 +:10B99000B42801081C16002018160020214B10B5F1 +:10B9A00018600120FFF7B6FF01460120FFF75AFF9C +:10B9B00008B9002010BD0220FFF7ACFF01460220AD +:10B9C000FFF750FF0028F4D01020FFF7A3FF014637 +:10B9D0001020FFF747FF04464FF48070F8F7CAFEC7 +:10B9E00008B1002CE5D00820FFF794FF014608209D +:10B9F000FFF738FF04460820F8F7BCFE08B1002C1A +:10BA0000D7D00420FFF786FF01460420FFF72AFF66 +:10BA100004464FF40060F8F7ADFE08B10CB9C8E772 +:10BA2000012010BD1816002070B50E4600240C4DE4 +:10BA30000023605DE95CEA18814203D01033602B7B +:10BA4000F8D100221146FFF70DFF83681B78B3423F +:10BA500004D01034602CEAD1002070BD012070BDEC +:10BA6000B428010810B50446FFF754FF01462046EC +:10BA7000FFF7F8FE003018BF012010BD38B50546AD +:10BA80000C46FFF747FF01462846FFF7EBFE28B1BB +:10BA900043681B7A1C420CBF0020012038BD000007 +:10BAA000F8B505460020FFF753FE104E0C272B7803 +:10BAB0000F4C07FB0060E35C03720120FFF748FEB8 +:10BAC0006B7807FB0060E35C03720220FFF740FE27 +:10BAD000AB7807FB0060E35C03720320FFF738FEDE +:10BAE000EB7807FB0060E35C0372F8BD40000020C8 +:10BAF000612801082DE9F04F87B0984682460F462D +:10BB000016469DF84040FFF705FF0DF1080E05466B +:10BB1000034600F1100C18685968724603C20833D6 +:10BB200063459646F7D12B7B0BB903960496504696 +:10BB300002A9FFF797FE054640B14368586830B147 +:10BB4000504602A92A46FFF73BFEF4E730E0AB6817 +:10BB500095F800B093F80090B9F1030F28D8DFE80A +:10BB600009F002050E100094134801E013480094F8 +:10BB7000394632464346F7F713FF04460BE00020F0 +:10BB800000E00120394623463246F7F7F7FC4146EC +:10BB90000446FBF763F854B1094B84F8049043F86A +:10BBA0002B406B6820465C605146FFF793FE2046B1 +:10BBB00007B0BDE8F08F00BF0038014000440040EE +:10BBC0000816002038B5064C05462060FFF768FFD0 +:10BBD000284601F095FD2068BDE8384000F0E6BE3B +:10BBE00018160020034B1B780BB100F0E7BD01F0E5 +:10BBF00021BE00BF2C16002010B504462046FBF7DE +:10BC000028F818B90A20FBF796F8F7E710BD0000EE +:10BC1000232801D100F0D2BD044B1B681B7D834259 +:10BC200002D10120FBF746B9704700BF181600206B +:10BC300010B5441E14F8011F21B1034B1868FAF720 +:10BC4000E9FFF7E710BD00BF641600200148FFF7C9 +:10BC5000EFBF00BFA02A010810B50748FFF7E8FFB3 +:10BC60000024064B06481A19E15852680C34F9F7BB +:10BC70002FF9C02CF5D110BDDE2A0108BC2901081E +:10BC8000F42A010870B5FBF745F8244B4FF47A719C +:10BC90001A78234BB0FBF1F11B782248F9F718F919 +:10BCA000FEF7E4FB204B05461968204B2048B1FB0A +:10BCB000F3F1F9F70DF900241E4AE3B252F823100C +:10BCC00049B1012202FA03F32B4202D01A48F9F7D4 +:10BCD000FFF80134F0E70220FEF7AEFB68B1174B26 +:10BCE00017481A78174B53F82210F9F7F1F8164B4A +:10BCF000197A11B11548F9F7EBF81548FFF798FFD5 +:10BD0000144B1C88F6F762FE2146024640F24C4373 +:10BD10001148BDE87040F9F7DBB800BF781B002080 +:10BD200010000020FC2A01089801002040420F006A +:10BD30003A2B0108A8390108582B01085C0D002096 +:10BD40005C2B01087C2A0108DC200020662B0108FE +:10BD5000CC2D0108200D00206A2B010838B50C6895 +:10BD60000546204605F044FC214602462868BDE809 +:10BD7000384005F06DBC000037B5037904460D4628 +:10BD8000052B34D8DFE803F003060A0D111483688D +:10BD900019782DE0836893F9001029E083681988E9 +:10BDA00026E08368B3F9001022E0836819681FE079 +:10BDB000836869461868F9F779F901461248F9F776 +:10BDC00087F8F5B1E068F4F729FF6946F9F76EF9ED +:10BDD00001460E48F9F77CF82069F4F71FFF694621 +:10BDE000F9F764F901460948F9F772F809E000210A +:10BDF0000748F9F76DF825B10648E1682269F9F7B7 +:10BE000067F803B030BD00BF632B0108622B010847 +:10BE1000A02B01089C2B010808B50648FFF708FF76 +:10BE2000054B1868FFF7E8FEBDE808400020FBF767 +:10BE300041B800BFA32B01086416002008B50748CD +:10BE4000FFF7F6FE064B93F84804F8F72DFCF8F7D9 +:10BE50003BFCBDE80840FFF7DFBF00BFB22B010885 +:10BE60007C1B00207FB5044605F0C2FB082825D1C5 +:10BE700000231F49E25C09681144497801F003017D +:10BE8000022908BF203AE2540133082BF1D10025E2 +:10BE9000665D1848314605F0D3FA28B101356019BE +:10BEA000314605F0CDFA18B11348FFF7C1FE1DE089 +:10BEB000082DEDD120461149FEF7D0FC1048FFF7C0 +:10BEC000B7FE00230F4A04A91A4492F808210A4435 +:10BED0000849595C0133082B02F80C1CF2D10023ED +:10BEE000094801A98DF80C30F8F7F2FF04B070BDD5 +:10BEF000B401002058280108BC2B0108841C002034 +:10BF0000DC2B01087C1B0020F72A010808B5FEF78E +:10BF100089F8022802D0032800D008BD0248BDE8F5 +:10BF20000840FFF785BE00BFF12B01082DE9F04165 +:10BF3000054605F05DFB0446F8F786FE06468CB91B +:10BF40002948FFF775FE294B53F8241041B101230E +:10BF5000A340334202D02648F8F7BAFF0134F2E793 +:10BF6000244821E028462449224605F071FB58B9AF +:10BF70002248FFF75DFE224C54F8041F0029EFD041 +:10BF80001B48F8F7A5FFF7E72B7800262D2B03BFFA +:10BF9000013504F1FF344FF001084FF00008134B56 +:10BFA00053F8267027B91748BDE8F041FFF740BEA7 +:10BFB00028463946224605F04BFB98B90120B0408F +:10BFC000B8F1000F03D0F8F77DFD0F4802E0F8F755 +:10BFD000DBFB0E48FFF72CFE39460D48BDE8F0416B +:10BFE000F8F776BF0136DAE7172C010814290108A3 +:10BFF000582B0108CC2D0108863701082A2C01088E +:10C00000102901083F2C0108592C0108632C010854 +:10C01000F72A010810B504460848FFF709FE084A48 +:10C0200000231370074A1360074A1370FCF77AFB6A +:10C030002046BDE81040FFF701BF00BF6C2C01088F +:10C040002D160020601600202C16002008B504488C +:10C05000FFF7EEFDF8F7A0FBBDE80840FFF7DCBEF8 +:10C06000842C01082DE9F04389B0044605F0C0FA9C +:10C07000C6B2002E6CD17B48FFF7DAFD7A4C2069FE +:10C080000021F4F7B3FF40BB013678483146F8F79A +:10C090001FFF206904A9F9F709F801467448F8F769 +:10C0A00017FF606904A9F9F701F801467048F8F72D +:10C0B0000FFFA06904A9F8F7F9FF01466C48F8F7EB +:10C0C00007FFE06904A9F8F7F1FF01466948F8F7AE +:10C0D000FFFE0C2E04F11004D1D10025664C2F4632 +:10C0E0002B464FF00008B04504F1100415DA18464D +:10C0F00054F8101CF4F7DEFC54F80C1C814628465A +:10C10000F4F7D8FC54F8081C05463846F4F7D2FC7E +:10C1100008F101084B460746E5E7584801930295A8 +:10C120000397FFF785FD002401ABE058544920F048 +:10C130000040F4F783FF534B534A0434002814BFE4 +:10C1400010461846FFF774FD0C2CEDD14F4871E0F6 +:10C1500020464F49052205F07BFA38B9424B0022B0 +:10C1600003441030C0281A61F8D177E020464949CD +:10C17000042205F06DFA054620460DBB202105F08E +:10C180005FF900286AD0461C304605F031FA2C468B +:10C190000746414B53F824500DB940484AE0304619 +:10C1A0002946FAB205F054FA40B920463C49FCF75A +:10C1B00059FB3C482946F8F78BFE47E00134E8E795 +:10C1C00004F0CCFD461E0B2E074643DC2046202102 +:10C1D00005F036F9054640B1451C2846F8F7CEFF74 +:10C1E000214B3F01D851012400E00446284620217C +:10C1F00005F026F9054640B1451C2846F8F7BEFF74 +:10C20000194B013403EB061358612846202105F031 +:10C2100017F9054640B1451C2846F8F7AFFF124B09 +:10C22000013403EB061398612846202105F008F934 +:10C2300018B91D48FFF7FCFC10E00130F8F79EFF2D +:10C24000094B032C03EB0616F061F2D11748FFF7F8 +:10C2500009FF03E016480C21F8F73AFE09B0BDE8E3 +:10C26000F08300BFA52C01087C1B0020D02C010806 +:10C27000D62C0108F72A0108901B0020DA2C0108AF +:10C280000AD7233CA12C01089D2C0108CC2D0108C4 +:10C29000E92C0108EF2C010860290108F42C0108A1 +:10C2A0008C1B00200C2D01081F2D01080B300108EC +:10C2B000592D0108F8B5074605F09AF9044638B932 +:10C2C0001A4B1B485A791B4B013A53F8221028E0AD +:10C2D00038461949224605F0BBF960B91748FFF7FF +:10C2E000A7FC174C54F8041F19B11648F8F7F0FDD5 +:10C2F000F8E7154805E000250E4B53F8256026B9F0 +:10C300001248BDE8F840FFF793BC38463146224654 +:10C3100005F09EF901350028EED1044B0C485D7103 +:10C320003146BDE8F840F8F7D3BD00BF7C1B0020C4 +:10C33000812D01086029010886370108952D010823 +:10C340005C290108582B0108CC2D0108F42C0108A8 +:10C35000A82D01082DE9F047074605F049F94D4D94 +:10C36000064620B1012818D13B782A2B15D14A481E +:10C37000FFF75EFC002429594848F8F7A9FD281961 +:10C380003146FFF7F9FC4648FFF752FC143440F6FB +:10C39000EC139C42EFD1BDE8F08738463D2105F013 +:10C3A0004FF800285BD0441C204604F0D7FC82469E +:10C3B0002046F8F7E3FE002406464FF0140909FB77 +:10C3C00004F955F80980404605F012F94146024645 +:10C3D000384605F03DF9002839D12E4F4F44F86812 +:10C3E000F4F71CFC01463046F4F71EFE00282CD062 +:10C3F0003869F4F713FC01463046F4F70BFE20B31E +:10C400003B79052B4FF0140303FB0454227918BF2A +:10C410005646052A0FD8DFE802F003030606090C8A +:10C42000A268167007E0A268168004E0A268166091 +:10C4300001E0A3681E6041461A48F8F749FD20460E +:10C440000021BDE8F047FFF797BC174803E001342F +:10C450007F2CB2D11548BDE8F047FFF7E9BB044691 +:10C460002E593946304605F0A1FA58B10B483146ED +:10C47000F8F72EFD074800212044FFF77DFC08480F +:10C48000F8F726FD143440F6EC139C42E8D1BDE8E1 +:10C49000F08700BFC8390108BA2D0108942F0108A0 +:10C4A000CC2D0108CF2D0108DA2D0108FF2D010840 +:10C4B00010B50446204605F09BF810F0FF0F07D199 +:10C4C0000B4B0C4893F84814BDE81040F8F700BD3A +:10C4D000204604F043FC022808D8054B064C83F89C +:10C4E0004804F8F7F1F8F8F769FBE3E710BD00BF7F +:10C4F0007C1B00201C2E01080B30010870B504467F +:10C5000005F076F808B9204830E020461F4905F0CC +:10C510004DFB00242646254678B12CB1012C06D1CE +:10C5200004F01CFC064602E004F018FC054617491E +:10C530000020013405F03AFBEEE70B2D05D9BDE8EC +:10C54000704013480C21F8F7C3BC012C08DC114BD8 +:10C55000294633F915201048BDE87040F8F7B8BCFB +:10C56000A6F57A73B3F57A7F04D90C48BDE870401C +:10C57000F8F7AEBC0A4829463246F8F7A9FC054B45 +:10C5800023F8156070BD00BF322E0108D52F0108B9 +:10C590006C2E010890210020922E0108AA2E01087D +:10C5A000CC2E010838B5054605F022F8C0B268B9AE +:10C5B0000446124B214603EB44031148B3F876209E +:10C5C0000134F8F785FC162CF3D138BD284604F069 +:10C5D000C5FB152804460BDC2021284604F030FF5B +:10C5E00004F0BCFB054B03EB4404A4F8760038BD13 +:10C5F00004481621BDE83840F8F76ABCC81F00207F +:10C60000E52E0108F12E01082DE9FF47584C594845 +:10C61000F8F75EFC5848FFF7C5FF6279574B013ABF +:10C6200053F822105648F8F753FC20690021F4F71C +:10C63000DDFC274600285AD10546266900213046F0 +:10C64000F4F7D4FC00284ED101354E482946D4F8E1 +:10C6500014A0D4F81890D4F81C80F8F739FC3046B0 +:10C660000021F4F7CDFC10B14748F8F731FC6946DA +:10C670003046F8F71BFD01464448F8F729FC5046C0 +:10C680000021F4F7BDFC10B13F48F8F721FC6946E2 +:10C690005046F8F70BFD01463C48F8F719FC4846B0 +:10C6A0000021F4F7ADFC10B13748F8F711FC6946EA +:10C6B0004846F8F7FBFC01463448F8F709FC4046C9 +:10C6C0000021F4F79DFC10B12F48F8F701FC6946F2 +:10C6D0004046F8F7EBFC01462D48F8F7F9FB0C2D26 +:10C6E00004F11004A9D12B48691CF8F7F1FBF8F705 +:10C6F000ABFA294C054654F8041F19B12748F8F73E +:10C70000E7FBF8E70C46264B53F8241041B1012310 +:10C71000A3402B4202D02348F8F7DAFB0134F2E7BA +:10C72000CB1993F8083104AA13441F4A8A5C0131DB +:10C73000082903F8102CF3D100241C4869468DF811 +:10C740000840F8F7C5FB1A4D1A486159F8F7C0FBC5 +:10C7500028190021FFF710FB1748FFF769FA143476 +:10C7600040F6EC139C42EED104B0BDE8F08700BF68 +:10C770007C1B0020172F01080B30010860290108DD +:10C78000472F0108522F0108D52F0108632B0108FC +:10C79000F72A01085A2F0108102901086C2F0108F7 +:10C7A000142901087A2F010858280108872F010849 +:10C7B000C8390108902F0108CC2D01082DE9F04758 +:10C7C0006C4B86B01A7899466B4F7AB9012338685A +:10C7D000022189F80030FFF77DF83868F8F7A4FBEC +:10C7E0006648FFF725FA6648FFF722FA3868FAF735 +:10C7F00021FA002800F0BB805F4B624C1868FAF702 +:10C800001EFA0928014601D03F2852D14FF00008F6 +:10C81000D4F800A05C4E4546BAF1000F05D05B4845 +:10C820003168524604F014FF10B9B04605B93546D8 +:10C83000574B0C369E42EFD3CDB1D5F800E0D8F877 +:10C8400000C053461EF803601CF80300B04201D03C +:10C8500023600CE05A1C4D4930B92D2B04D82026FA +:10C86000CE542260885402E0CE541346EAE723688F +:10C870001BB1454501D1554611E04648FFF7D8F9AF +:10C88000454508D855F80C0BFFF7D2F9386809214F +:10C89000FAF7C0F9F4E73A48FFF7CAF90025236828 +:10C8A0009D42A3D2394B3868595DFAF7B3F9013587 +:10C8B000F5E723682BB9042836D13448FFF7AAFBE3 +:10C8C00055E00C2801D134488BE70A2901D00D2905 +:10C8D00044D13248FFF7ACF92C4D22680023AB5409 +:10C8E00004932F4B03A80093274910220C23039590 +:10C8F00004F038FA064638B1006804F079FE0130D9 +:10C90000B3682844984702E02648FFF791F91F488A +:10C910000021302204F076FA0023236099F80030D9 +:10C92000002B7FF460AF22E00C28CCD07F2903D10C +:10C930005CE72F2B3FF65AAFA1F12002D2B25E2A5C +:10C940003FF654AF13B920293FF450AF5A1C226070 +:10C950000E4A3868D154FAF75DF947E77F29E8D1E4 +:10C960000A4A013B00212360D1540F483CE706B03E +:10C97000BDE8F0872C160020641600209A2F0108CD +:10C98000D22F010860160020BC2901082D160020B6 +:10C990007C2A0108D72F0108DC2F0108CC2D0108C3 +:10C9A0005DBD0008E72F01080830010837B50546CE +:10C9B0000220FEF773FF064C0146206030B900905C +:10C9C000AA6802200323FFF795F8206003B030BD6A +:10C9D00064160020F8B5154E154C164D0746C1B229 +:10C9E00030682170FAF716F922782B78C7F30721FF +:10C9F000534030682B702170FAF70CF922782B78AD +:10CA0000C7F30741534030682B702170FAF702F9E1 +:10CA100022782B78390E534030682B702170FAF74A +:10CA2000F9F82B78227853402B70F8BD7816002047 +:10CA30006816002070160020F8B50C4E0C4D0D4CF9 +:10CA4000C1B2074630682970FAF7E4F82A782378EB +:10CA5000C7F307215340306823702970FAF7DAF8DA +:10CA600023782A7853402370F8BD00BF7816002041 +:10CA7000D416002070160020054B10B50446214640 +:10CA80001868FAF7C7F8034B1A7854401C7010BDA9 +:10CA90007816002070160020034A1378591C117074 +:10CAA000024AD05C704700BF711600209416002027 +:10CAB00010B5FFF7F1FF0446FFF7EEFF04EB00208F +:10CAC00080B210BD10B5FFF7F3FF0446FFF7F0FF8B +:10CAD00004EB004010BD000038B5044624200D468C +:10CAE000FFF7CAFF4D20FFF7C7FF002C0CBF3E2009 +:10CAF0002120FFF7C1FF064B284600221A70FFF7DE +:10CB0000BBFF044B1878BDE83840FFF7B5BF00BF46 +:10CB1000701600207C16002001460020FFF7DCBFC5 +:10CB200001460120FFF7D8BF014B1878FFF7A4BFDB +:10CB30007016002070B5064608460D46FFF7ECFF5C +:10CB40000024E3B29D4204D0305DFFF795FF01342D +:10CB5000F7E770BD10B5441E14F8010F10B1FFF7D0 +:10CB60008BFFF9E710BD00002DE9F04700270124F5 +:10CB70000025154B1B789D421DDA144B144E15F8F9 +:10CB800003800C2303FB0863586804F031FDB246B0 +:10CB900081460CB9264601E007440AE04E4508DA12 +:10CBA0000C2303FB08A35B68985DFFF765FF013664 +:10CBB000F4E70135DDE724B1F8B2FFF7ADFF00245B +:10CBC000D6E7BDE8F08700BF721600207D16002072 +:10CBD00070000020F8B5D94B1B787B2B00F04983FF +:10CBE00000F2C6806E2B00F0BC8360D8682B00F08A +:10CBF0005C8325D8652B00F04E8219D8642B40F059 +:10CC000066850720CE4CFFF787FFE620FFF734FF4D +:10CC10006079FFF731FF0020FFF72EFF94F81B012A +:10CC2000C84BC94A00280CBF1046184600F02CBD5E +:10CC3000662B00F0B382672B40F04985C34835E38B +:10CC40006B2B00F06C8323D8692B00F055836A2B83 +:10CC500040F03D851020FFF75FFFBD4BBD4CD87AFB +:10CC6000FFF70AFFBC4B1878FFF706FF2068FFF7B5 +:10CC7000B1FE6068FFF7AEFEB84BB3F90000FFF7F6 +:10CC8000DBFEB74BB3F90000FFF7D6FEB54B65E30B +:10CC90006C2B00F056836D2B40F019850620FFF7B2 +:10CCA0003BFFB14B1868FFF795FEB04B56E3732B73 +:10CCB00000F023843DD8702B00F08383C0F06283A2 +:10CCC000712B00F0F183722B40F001859C4C1620F3 +:10CCD000FFF722FF0020FFF7AFFEB4F9D000FFF707 +:10CCE000ABFEA34DB4F9D200FFF7A6FEB4F9D40011 +:10CCF000FFF7A2FEB5F9EC00FFF79EFE0020FFF75C +:10CD00009BFE0020FFF766FEB5F95A000A2390FB50 +:10CD1000F3F0FFF791FE94F80401FFF7ADFE94F8ED +:10CD20000601FFF7A9FE94F80501FFF7A5FE00F044 +:10CD300013BC762B00F0EC830DD8742B00F0CB8362 +:10CD4000752B40F0C4842F20FFF7E6FE8948FFF7DB +:10CD500001FF00F0BFBC772B00F0C083782B40F0C0 +:10CD6000B684834C3820FFF7D7FE04F140054EE22D +:10CD7000D02B00F0248400F29B80CA2B00F00681A7 +:10CD800039D8A42B00F0838411D8A02B40F09F84C5 +:10CD90000C20FFF7C1FE784B1868FFF71BFE774B9E +:10CDA0001868FFF717FE764B186800F06DBCC82BAB +:10CDB00000F0B580C92B40F08A84FFF76DFE644B0C +:10CDC000644CD872FFF768FE634B1870FFF77AFE69 +:10CDD0002060FFF777FE6060FFF76AFE5F4B188008 +:10CDE000FFF766FE5E4B1880664B1A7842F002022F +:10CDF0001A7000F030BCCD2B00F0E88324D8CB2B88 +:10CE000000F08B80CC2B40F06284FFF745FE584C3D +:10CE100084F85000FFF740FE84F85100FFF73CFE15 +:10CE200084F85400FFF738FE84F85500FFF734FE0D +:10CE300084F85600FFF730FE84F85200FFF72CFE0E +:10CE400084F8530000F007BCCE2B00F0C883CF2B32 +:10CE500040F03D84FFF72CFEFFF72AFE384C444D8E +:10CE6000A4F8D000FFF724FEA4F8D200FFF720FEBC +:10CE7000A4F8D400FFF71CFEA5F8EC00FFF718FE9D +:10CE8000FFF720FEFFF714FE00EB80004000A5F83E +:10CE90005A00FFF701FE84F80401FFF7FDFD84F856 +:10CEA0000601FFF7F9FD84F80501FFF7F5FDD2E370 +:10CEB000D52B00F0EC8111D8D22B00F0D880C0F037 +:10CEC0004F83D32B00F0E280D42B40F00084284C19 +:10CED0000020FFF721FE04F14005ACE1F02B00F04B +:10CEE000C6830FD8D62B00F0B980EF2B40F0EF832C +:10CEF000FFF7DEFD1E4CA4F85E00FFF7D9FDA4F895 +:10CF00005C00A8E3FA2B00F09983FE2B40F0DF834E +:10CF10000820FFF701FE0024A1E300248EE0002496 +:10CF2000FFF7C6FD184B18530234102CF8D100201F +:10CF3000FFF7F2FDFDF7F6FCCCE300BF7C16002006 +:10CF40007C1B00201C0000801400008028000020B2 +:10CF500013220020E821002000220020BA21002016 +:10CF6000BE210020B412002054210020F40F002024 +:10CF7000C81F0020B4430108E8F7FF1FECF7FF1FAC +:10CF8000F0F7FF1F841300206E220020C94B1A788F +:10CF90001C46022A42D103F1200503F12C06FFF7BB +:10CFA0007BFDF3F737FEC449F3F740FF45F8040F64 +:10CFB000FFF772FDF3F72EFEC049F3F737FFE86085 +:10CFC000FFF76AFDF3F726FEBD49F3F72FFFB542E1 +:10CFD000A861E4D10325072D12D1FFF75DFDF3F71A +:10CFE00019FEB549F3F722FFA064FFF755FDF3F7EB +:10CFF00011FEB149F3F71AFFE064FFF74DFD09E0B8 +:10D00000FFF74AFD66193071FFF746FDB073FFF771 +:10D0100043FD307601350A2DDDD11CE35C1E03F1A2 +:10D020000905FFF739FD01342071FFF735FDA073C5 +:10D03000FFF732FDAC422076F3D10CE3A14B1B7815 +:10D040009C4280F00883A04BE55CFFF731FD994BD3 +:10D05000013403EB4505A5F87600EFE70024FFF760 +:10D0600027FD9A4B18530234102CF8D1F3E2984B59 +:10D070009C78002C40F0EF82FFF70EFD954B0228C4 +:10D0800094BF83F8480483F84844E0E2FFF710FDBA +:10D09000914B1880DFE20B20FFF73EFD8F4BB3F979 +:10D0A0000000FFF7C9FCF5F791FC00B2FFF7C4FCE4 +:10D0B0000220FDF7C1F905460420FDF7BDF904463D +:10D0C0000820FDF7B9F9800040EA44042020FDF76C +:10D0D000B3F92C43A4B244EAC00084B21020FDF797 +:10D0E000ABF944EA001000B2FFF7A6FC784A002032 +:10D0F0001479D378A40044EA430493781C439379C9 +:10D1000044EAC304537944EA4314537A44EA831447 +:10D11000734BD97944EAC114197A44EA0124597A43 +:10D1200044EA4124D17944EA8124117A927A44EA8A +:10D13000C12444EA02345A7B44EA42349A7B44EAEA +:10D1400082341A7C44EA02441A7944EA02145A7C72 +:10D1500044EA42449A7C44EA8244DA7C44EAC24487 +:10D160001A7D5B7D44EA025444EA4354554B1978D6 +:10D1700003468B420CD2544A9D5C012202FA05F50B +:10D18000254218BF9A4003F1010318BF1043F0E78E +:10D19000FFF720FC4F4B93F84804DEE11220FFF725 +:10D1A000BBFC504B504C1B88B3F5806F22D9002537 +:10D1B000605F082390FBF3F00235FFF73DFC062D7E +:10D1C000F6D14A4CB4F90000FFF736FCB4F902007E +:10D1D000FFF732FCB4F90400454CFFF72DFCB4F91D +:10D1E0000000FFF729FCB4F90200FFF725FCB4F9B1 +:10D1F000040046E2B4F90000FFF71EFCB4F9020097 +:10D20000FFF71AFCB4F90400FFF716FCD9E7B4F9EC +:10D21000AA00FFF711FCB4F9AC00FFF70DFCB4F95C +:10D22000AE00FFF709FC083494F8A800FFF724FCCF +:10D23000AC42ECD14EE2FFF73BFCA4F8AA00FFF7AA +:10D2400037FCA4F8AC00FFF733FCA0F57A7307288D +:10D250009BB298BF84F8B100B3F57A7F98BFA4F869 +:10D26000AE00FFF719FC083484F8A800AC42E2D104 +:10D2700030E20820FFF750FC00240E4B234493F8C3 +:10D28000B1000834FFF7F8FB402CF6D122E2002071 +:10D29000FFF742FC0024FFF7FFFB064B2344083452 +:10D2A000402C83F8B100F6D114E212481021FFF7A8 +:10D2B00041FC0FE2C81F0020000020410000C842CE +:10D2C00000007A44721600207D1600209021002074 +:10D2D000132200207C1B002020210020200D002094 +:10D2E00025220020120000205C210020E00F0020F9 +:10D2F0000421002078210020BC4D00242878400023 +:10D3000000F0FE00FFF708FC2B789C4280F0E281E1 +:10D31000B74B33F91400FFF78FFB0134F4E7052016 +:10D32000FFF7FAFBB34BB3F90000FFF785FBB24BF5 +:10D33000B3F90000FFF780FBB04B187800F0010054 +:10D340000BE1AF4C0620FFF7E7FBB4F90000FFF755 +:10D3500073FBB4F90200FFF76FFBAA4BB3F90000AF +:10D360008FE10720FFF7D8FBA74B1878FFF784FB66 +:10D370000020FFF761FBA54BB3F90000FFF75CFB52 +:10D3800000207EE1A24C0720FFF7C6FB94F8500076 +:10D39000FFF772FB94F85100FFF76EFB94F854000E +:10D3A000FFF76AFB94F85500FFF766FB94F8560008 +:10D3B000FFF762FB94F85200FFF75EFB94F853000E +:10D3C000CBE01E20FFF7A8FB914B1A781C46022ADF +:10D3D0005AD103F1200503F12C0655F8040F8D49AD +:10D3E000F3F770FC01F0EEFBFA220021F7F732FCB4 +:10D3F000C0B2FFF741FB8849E868F3F763FC01F02E +:10D40000E1FBFA220021F7F725FCC0B2FFF734FB5D +:10D410008249A869F3F756FC01F0D4FB002164228D +:10D42000F7F718FCC0B2FFF727FBB542D5D10325AB +:10D43000072D1BD17749A06CF3F744FC01F0C2FB28 +:10D44000FA220021F7F706FCC0B2FFF715FB71497D +:10D45000E06CF3F737FC01F0B5FB0021FA22F7F797 +:10D46000F9FBC0B2FFF708FB002007E0661930792E +:10D47000FFF702FBB07BFFF7FFFA307E0135FFF7C5 +:10D48000FBFA0A2DD4D125E15C1E03F10905013414 +:10D490002079FFF7F1FAA07BFFF7EEFA207EFFF785 +:10D4A000EBFAAC42F3D115E15D4D00242878400041 +:10D4B00000F0FE00FFF730FB2B789C4280F00A81E1 +:10D4C000584BE25C524B013403EB4203B3F9760054 +:10D4D000FFF7B2FAF0E7FFF747FBFBE0504D0024FF +:10D4E0002878FFF719FB2B789C4280F0F3804D4B96 +:10D4F000185DFFF7C1FA0134F5E70820FFF70CFBD0 +:10D500000124E0B20134FFF7B7FA092CF9D1E1E0C8 +:10D51000FFF7C2FA06461220FFF7FEFA0EB9424B99 +:10D5200002E0102E03D1414B1D685C6801E000242D +:10D5300025463046FFF7A0FA2846FFF74BFA20466B +:10D54000FFF748FA3A4B1868FFF744FA0020FFF754 +:10D5500073FA0020FFF770FA0020FFF78DFAB9E0A8 +:10D56000FFF79AFA0546FFF7ADFA0746FFF7AAFA62 +:10D570000646FFF7A7FA0446FFF79AFAFFF798FA6C +:10D58000FFF78AFA5DB9284B01225E601F60294BC4 +:10D59000DD711A73002C5ED0254B1C605BE0102DF2 +:10D5A00059D1224B1F605E600CB1214B1C601F489B +:10D5B000214B0222011D1A70FCF786FD4BE01D4B2A +:10D5C0009B78002B47D1F7F7E7F842E0194B9B789F +:10D5D000002B40D14FF4C870F8F7E0FE3BE0154B4C +:10D5E0009A78002A37D101229A7334E06A22002007 +:10D5F0006E220020C8210020D421002084130020A6 +:10D60000D00F002032210020781B00206C22002047 +:10D61000C81F0020000020410000C84200007A44DA +:10D62000721600207D160020CC210020C021002091 +:10D6300058210020132200204C110020274B9B78FA +:10D64000002B44D1264B93F84804F7F72DF8F7F751 +:10D650003BF8F7F7B3FA0020FFF75EFA3AE0214B08 +:10D66000185F0234FFF7E8F9082CF8D132E01E4CBD +:10D670000420FFF751FAB4F95E00FFF7DDF9B4F9C1 +:10D680005C00FFF7D9F925E0FFF7A4F922E0174D78 +:10D690000024287880000130C0B2FFF73DFA2878D6 +:10D6A000FFF7EAF92B789C4214D2114B185DFFF773 +:10D6B000E3F9104B185DFFF7DFF90F4B185DFFF72B +:10D6C000DBF90E4B185DFFF7D7F90134EAE70020CC +:10D6D000FFF726FABDE8F840FFF726BA132200202C +:10D6E0007C1B0020D2200020C81F00200122002027 +:10D6F000A8210020D6210020F021002002220020B5 +:10D700002DE9F341474DFF2116220746284603F035 +:10D7100079FB002302202B70FCF78EFE012418B148 +:10D7200002236C70AB7003240420FCF785FE68B103 +:10D7300003234FF40050661C2B55F7F71BF820B15C +:10D74000384B042202349A5500E034460220FCF79C +:10D7500073FE48B12A19052306212B55A31C5170CD +:10D760000722EA54033404E00820FCF765FE002891 +:10D77000F0D12020F6F7FEFF10B108232B5501341D +:10D780004FF48070F6F7F6FF28B10A222A55631C81 +:10D790000B22EA540234244A53799046082B01D0D4 +:10D7A0000E2B02D10C232B5501340D230420661CB3 +:10D7B0002B55F6F7DFFF18B11A4B11229A55A61C0C +:10D7C00098F839011323003018BF0120741CAB55A1 +:10D7D000F6F7D0FF18B1134B14221A55B41C1523B9 +:10D7E0002B55124B01341C70114B00221A601D4640 +:10D7F0007A6800240021009101200323FEF77AF9C2 +:10D8000020B94CB94FF496420124F3E72A68002A64 +:10D81000EED1074B1860EBE702B0BDE8F041FDF731 +:10D82000BDBF00BF7D1600207C1B002072160020AB +:10D830007816002010B5304C2068F9F7FBF9002865 +:10D8400058D02068F9F7FBF92C4C034622786AB9C6 +:10D85000B0F12402534253412370002BEBD1284BEB +:10D860009B78002BE7D1FEF7D3F9E4E7012A04D136 +:10D870004D2814BF002302233AE0022A04D13C2899 +:10D8800014BF0023032333E0032A0FD140284FF0B5 +:10D89000000201D92270CEE71A49042308701A4900 +:10D8A0000A701A490A701A4A107021E0042A08D135 +:10D8B000184A1070164A117880EA01031370052384 +:10D8C00016E0052AB7D110480E4A017812788A422C +:10D8D0000F4A07D914785C4014704A1C02700E4A33 +:10D8E0005354A8E712789A4201D1FFF773F9002345 +:10D8F0002370A0E710BD00BF78160020731600202B +:10D9000013220020741600209316002071160020A8 +:10D91000701600207C1600209416002010B5074CCD +:10D92000074A2368D25C074B1A70FFF753F9236844 +:10D930000133092B88BF0023236010BD6C16002023 +:10D940009D4401087C1600202DE9F04106460F4653 +:10D9500090460025EBB2434518D20024E3B2B3420F +:10D960000FD20B4B0120DA68013482F00802DA6032 +:10D97000F9F78EF93846F9F7DEF90020F9F788F95A +:10D98000ECE73C20F9F7D7F90135E3E7BDE8F08192 +:10D99000000C01400F4B1A6842F001021A605968EE +:10D9A0000D4A0A405A601A6822F0847222F48032CA +:10D9B0001A601A6822F480221A605A6822F4FE0261 +:10D9C0005A604FF41F029A60044B4FF000629A6055 +:10D9D000704700BF001002400000FFF800ED00E0BB +:10D9E000144A154B516801F00C01042903D0082991 +:10D9F00004D0124914E01249096811E051685068D6 +:10DA0000C1F38341C00301F1020101D40D4806E0D6 +:10DA1000506810F4003F0A48006818BF40084143AE +:10DA2000196052680849C2F30312895C1A68CA4037 +:10DA30001A607047001002409801002000127A001E +:10DA40009401002000093D00840100201FB500233F +:10DA50000093019302934FF4E0130393504B1A6821 +:10DA600042F480321A609A6942F010029A611A6890 +:10DA700002F400320192009A01320092019A1AB91E +:10DA8000009AB2F5A06FF2D11968454A11F400313D +:10DA900001D0022215E0146844F0010414600091E2 +:10DAA0001A6802F002020192009A01320092019A71 +:10DAB0001AB9009AB2F5A06FF2D11A68920739D557 +:10DAC00001220292374A384C116841F0100111606E +:10DAD000116821F003011160116841F00201116029 +:10DAE0005A685A605A685A605A6842F480625A60AA +:10DAF0002E4A1168043A21F0704151602C490C60A3 +:10DB00005C6824F47C145C60546844F00044546005 +:10DB1000D46824F40044D4609268140449BF254AB0 +:10DB20004FF4E0120A604FF480120392029A012A25 +:10DB300001D117E0FEE7022A18D168B1039AB2F5C5 +:10DB4000801F02D14FF4A01205E0039AB2F5E01F46 +:10DB500002D14FF4001203925968039A0A4342F427 +:10DB6000803202E05A6842F460125A601A6842F049 +:10DB700080721A6019680A4A8901FBD5516821F040 +:10DB800003015160516841F0020151605A6802F08E +:10DB90000C02082AFAD1FFF723FF04B010BD00BF22 +:10DBA000001002400020024000127A0004100140E0 +:10DBB00094010020001BB700837930B50168027919 +:10DBC00043B3194BCC431D6802F1804225401D60D0 +:10DBD0005D6802F582322C405C601468214311605C +:10DBE00002689C68D1430C409C60DC682140D9608D +:10DBF0004179102906D1996811439960D9680A437F +:10DC0000DA6030BD01F1804303F5823319680A43BD +:10DC10001A6030BD02F1804303F582331A6822EAAC +:10DC20000101196030BD00BF00040140054B1A68B6 +:10DC30005B69034004D010420CBF002001207047F4 +:10DC40001846704700040140014B5861704700BFFF +:10DC50000004014008B5154B98420BD14FF4805099 +:10DC6000012100F0B7FDBDE808404FF480500021CD +:10DC700000F0B0BD0E4B984207D14FF48040012117 +:10DC800000F0B4FD4FF4804009E00A4B98420BD1FC +:10DC90004FF40040012100F0A9FD4FF400400021A5 +:10DCA000BDE8084000F0A2BD08BD00BF0030014043 +:10DCB00000380040003C00400B8810B54C880288BA +:10DCC00023438C8802F441522343CC8823430C899C +:10DCD00023434C8923438C892343CC892343134317 +:10DCE0009BB20380838B23F400631B041B0C838390 +:10DCF0000B8A038210BD038819B19BB243F0400325 +:10DD000003E023F040031B041B0C03807047818158 +:10DD10007047808980B27047038919420CBF002088 +:10DD20000120704743680A6823F4702323F480734A +:10DD300013430A7910B543EA022343608A68CB682B +:10DD400084681A43084B234013434A7943EA420349 +:10DD500083600B7CC26A013B22F47002DBB242EAB0 +:10DD60000353C36210BD00BFFDF7F1FF836811B11B +:10DD700043F0010301E023F00103836070478368EF +:10DD800011B143F4807301E023F480738360704722 +:10DD9000836843F00803836070478068C0F3C00065 +:10DDA0007047836843F00403836070478068C0F362 +:10DDB00080007047836811B143F4A00301E023F4AD +:10DDC000A00383607047092970B50DD9A1F10A0439 +:10DDD00004EB44040725A540A340C66826EA0505D0 +:10DDE00045EA0304C4600BE001EB41040725A540AC +:10DDF00003FA04F4066926EA050545EA040303610B +:10DE0000062A0CD8013A02EB82021F23934001FA42 +:10DE100002F2446B24EA03031A43426370BD0C2AE6 +:10DE20000CD8073A02EB82021F23934001FA02F258 +:10DE3000046B24EA03031A43026370BD0D3A02EB3C +:10DE400082021F23934001FA02F2C46A24EA030308 +:10DE50001A43C26270BD000040F0BF60024B40F444 +:10DE60000030D860704700BF00ED00E0C27810B508 +:10DE70000378FAB1154A4478D26803F16043D2437B +:10DE8000C2F30222C2F1040104FA01F10F2424FAC0 +:10DE900002F2847803F5614322400A431201D2B2B0 +:10DEA00083F8002303780122590903F01F0302FAC3 +:10DEB00003F306E05909012203F01F0302FA03F3FA +:10DEC0002031034A42F8213010BD00BF00ED00E0D0 +:10DED00000E100E030B5048C24F001042404240C9B +:10DEE0000484058B048CADB225F0F3052A4342EA85 +:10DEF00003139DB2104BA4B2984215D003F50063F2 +:10DF0000984211D0B0F1804F0ED0A3F598339842CB +:10DF10000AD003F58063984206D003F580639842E7 +:10DF200018BF24F00A0401D124F0020444F00104D3 +:10DF300021430583018430BD002C014030B5048CA1 +:10DF400024F010042404240C0484048B058C24F491 +:10DF500040742405240D44EA022242EA0333144AA1 +:10DF6000ADB290429BB212D002F5006290420ED048 +:10DF7000B0F1804F0BD0A2F59832904207D002F555 +:10DF80008062904203D002F58062904207D125F072 +:10DF9000200545F0100545EA011189B204E025F09D +:10DFA000A00545F0100529430383018430BD00BF5F +:10DFB000002C0140224A038890429BB212D002F505 +:10DFC000006290420ED0B0F1804F0BD0A2F5983293 +:10DFD000904207D002F58062904203D002F5806241 +:10DFE000904203D14A8823F070031343154A9042AC +:10DFF00008D002F58062904204D023F44073CA88AE +:10E000009BB2134303808B8883850B8803850C4B5D +:10E0100098420FD003F5006398420BD003F540639C +:10E02000984207D003F58063984203D003F58063DC +:10E03000984201D10B7A038601238382704700BF87 +:10E04000002C014000100040038C70B523F0010348 +:10E050001B041B0C0384038C8488028B0D8822F024 +:10E0600073021204120C2A434E880D8923F0020316 +:10E070001B043543ADB21B0C2B43144DA4B2A84274 +:10E080000FD005F50065A8420BD005F54065A84204 +:10E0900007D005F58065A84203D005F58065A84244 +:10E0A0000ED14D8923F008032B438D8823F0040300 +:10E0B0002B43CE898D8924F440743543ADB22C4373 +:10E0C00084800283CA888286038470BD002C01404C +:10E0D000038C30B523F010031B041B0C0384038C4A +:10E0E0008288048B0D8824F4E6442404240C23F055 +:10E0F000200344EA05241B040D891B0C43EA051385 +:10E100004D8892B243EA0513124DA4B2A8429BB2C5 +:10E1100003D005F50065A84215D14D8923F0800391 +:10E120009BB243EA05134FF6BF751D408B8822F45E +:10E13000406245EA03138D899BB242EA8502CD898C +:10E1400042EA850292B28280CA88048302870384ED +:10E1500030BD00BF002C0140038C30B523F4807328 +:10E160001B041B0C0384038C8288848B0D8824F091 +:10E1700073042404240C23F400732C431B040D8922 +:10E180001B0C43EA05234D8892B243EA0523124D46 +:10E190009BB2A84203D005F50065A84215D14D8970 +:10E1A00023F400639BB243EA05234FF6FF351D407D +:10E1B0008B8822F4405245EA03238D899BB242EAC0 +:10E1C0000512CD8942EA051292B28280CA88848300 +:10E1D0008287038430BD00BF002C0140038C30B522 +:10E1E00023F480531B041B0C0384038C8488828BD0 +:10E1F0000D8822F4E6421204120C23F4005342EA82 +:10E2000005221B040D891B0C43EA05334D88A4B27B +:10E2100043EA05330A4D92B2A8429BB203D005F5FA +:10E220000065A84205D18D8924F4804444EA851410 +:10E23000A4B284808283CA88A0F84020038430BDC1 +:10E24000002C01404FF6FF73838000230380C380BE +:10E250004380037270470023038043808380C38020 +:10E26000038143818381C38170470023012203809E +:10E2700043808280C38003817047038819B19BB2B9 +:10E2800043F0010303E023F001031B041B0C038094 +:10E290007047B0F8443029B16FEA43436FEA534303 +:10E2A0009BB201E0C3F30E03A0F8443070478389AA +:10E2B0009BB20AB1194301E023EA01018181704751 +:10E2C000038B23F008031B041B0C194301837047C5 +:10E2D000038B23F400631B041B0C43EA01218BB264 +:10E2E00003837047838B23F008031B041B0C194323 +:10E2F00081837047838B23F400631B041B0C43EA68 +:10E3000001218BB28383704781847047038B23F094 +:10E310000C031B041B0C0383038B9BB21943018367 +:10E320007047038B23F440631B041B0C0383038B94 +:10E330009BB243EA01218BB203837047838B23F0A6 +:10E340000C031B041B0C8383838B9BB219438183B7 +:10E350007047838B23F440631B041B0C8383838BE4 +:10E360009BB243EA01218BB28383704770B50E885C +:10E370000D4604464988AA882B893EB9FFF7AAFDB5 +:10E380002046E988BDE87040FFF7C0BF042E07D1E2 +:10E39000FFF7D4FD2046E988BDE87040FFF7C1BF14 +:10E3A000082EEE88058C39D125F480752D042D0CAE +:10E3B0000584808B258C80B220F0F30040EA0313A3 +:10E3C0009BB21A43344BADB29C4212D003F50063AA +:10E3D0009C420ED0B4F1804F0BD0A3F598339C42F1 +:10E3E00007D003F580639C4203D003F580639C4211 +:10E3F00007D125F4007545EA012189B241F4807105 +:10E4000004E025F4206541F480712943A28320466D +:10E4100021843146BDE87040FFF790BF25F4805558 +:10E420002D042D0C0584808B258C20F44070000574 +:10E43000000D40EA0220184A40EA03339442ADB28C +:10E440009BB212D002F5006294420ED0B4F1804F1C +:10E450000BD0A2F59832944207D002F58062944224 +:10E4600003D002F58062944207D125F4005242EABB +:10E47000013292B242F4805205E047F6FF522A4040 +:10E4800041F480510A43A383204622843146BDE8EB +:10E490007040FFF75EBF00BF002C0140808E80B24D +:10E4A0007047008F80B27047808F80B27047B0F89D +:10E4B000400080B27047038A828911EA030092B259 +:10E4C00003D011420CBF002001207047C94389B21C +:10E4D00001827047038ACA889BB223F440531343D6 +:10E4E00030B503820D4682890989AB8892B20B430D +:10E4F000698922F4B0520B4322F00C0213439BB201 +:10E500008381838AAA899BB223F4407387B0134323 +:10E510000446838201A800F0EDF81749049A039B92 +:10E520008C4208BF1346A289192112B25943002A0E +:10E530002A684FF06403B4BF52009200B1FBF2F1BD +:10E54000B1FBF3F21201100903FB1011A08900B214 +:10E55000002806DAC9003231B1FBF3F303F00703F8 +:10E5600005E009013231B1FBF3F303F00F031A4365 +:10E5700092B2228107B030BD00380140838919B1C1 +:10E580009BB243F4005303E023F400531B041B0C21 +:10E5900083817047C1F3421310B5012401F01F01BC +:10E5A000A34204FA01F101D10C3003E0022B0CBFAD +:10E5B0001030143003680AB1194301E023EA010165 +:10E5C000016010BD838A9BB20AB1194301E023EABE +:10E5D000010181827047090A01238B40DB439BB212 +:10E5E00003807047034B044A5A6002F188325A6034 +:10E5F000704700BF0020024023016745024B1A69A3 +:10E6000042F080021A61704700200240014BD8603E +:10E61000704700BF00200240084BDA68D10709D4D8 +:10E62000DA68520708D4DB6813F0100F0CBF04201F +:10E6300003207047012070470220704700200240ED +:10E6400010B50446FFF7E8FF012806D11CB1FFF71B +:10E65000E3FF013CF8E7052010BD002C08BF0520B2 +:10E6600010BD000038B505464FF43020FFF7E8FF35 +:10E67000042812D1094C4FF43020236943F00203DF +:10E6800023616561236943F040032361FFF7D8FFED +:10E69000226941F6FD731340236138BD002002401A +:10E6A00073B5002306464FF400500D460193FFF763 +:10E6B000C7FF04281AD10E4C4FF40050236943F0D1 +:10E6C00001032361ABB23380FFF7BAFF042808D1FE +:10E6D00002360196019B2D0C1D804FF40050FFF770 +:10E6E000AFFF226941F6FE731340236102B070BD93 +:10E6F000002002401F4B10B55A6802F00C02042A99 +:10E7000003D0082A04D01C4A14E01C4A126811E005 +:10E710005A685968C2F38342C90302F1020201D464 +:10E72000174906E0596811F4003F1449096818BFF9 +:10E7300049084A4302605A681249C2F303128C5CCA +:10E740000268E24042605C68C4F302240C5D22FA75 +:10E7500004F484605C68C4F3C224095DCA40C260EA +:10E760005B680949C3F38133CB5CB2FBF3F202610E +:10E7700010BD00BF0010024000127A00940100207A +:10E7800000093D00A00100209C010020044B5A69B3 +:10E7900009B1104301E022EA00005861704700BF50 +:10E7A00000100240044B9A6909B1104301E022EACB +:10E7B00000009861704700BF00100240044BDA6906 +:10E7C00009B1104301E022EA0000D861704700BFA0 +:10E7D00000100240044BDA6809B1104301E022EA5C +:10E7E0000000D860704700BF00100240044B1A6957 +:10E7F00009B1104301E022EA00001861704700BF30 +:10E8000000100240024B5A6A42F080725A6270470E +:10E810000010024008B50B4B984207D14FF400108E +:10E820000121FFF7E3FF4FF4001006E04FF48000F2 +:10E830000121FFF7DBFF4FF480000021BDE8084015 +:10E84000FFF7D4BF00540040F0B587B00446868877 +:10E8500001A80D46314FFFF74DFF039826F03F0604 +:10E860003604B0FBF7F7360C1FFA87FC4CEA0606B5 +:10E87000A68021882A6821F00101294B0904090C8E +:10E880009A4221800DD85300B0FBF3F39BB20CF1F8 +:10E89000010C032B1FFA8CFC98BF0423A4F820C0A2 +:10E8A00022E0E9884BF6FF73994205D102EB420260 +:10E8B000B0FBF2F39BB206E019235343B0FBF3F332 +:10E8C0009BB243F48043C3F30B020AB943F0010344 +:10E8D0004FF4967257434FF47A7297FBF2F7013771 +:10E8E000BFB243F400432784A383238869899BB282 +:10E8F00043F0010323802388AA8823F4816323F053 +:10E9000002031B040A431B0C13439BB223802A8976 +:10E91000AB8913439BB2238107B0F0BD40420F0087 +:10E92000A086010041F288330360002383804BF608 +:10E93000FF72038143814FF48043C280838170471B +:10E94000038819B19BB243F0010303E023F00103F4 +:10E950001B041B0C03807047038819B19BB243F45E +:10E96000807303E023F480731B041B0C0380704747 +:10E97000038819B19BB243F4007303E023F40073DE +:10E980001B041B0C03807047038819B19BB243F42E +:10E99000806303E023F480631B041B0C0380704737 +:10E9A00083889BB20AB1194301E023EA0101818007 +:10E9B000704701827047008AC0B2704712B141F0BF +:10E9C000010101E001F0FE010182704702684FF68B +:10E9D000FE73134003600023036043608360C360E1 +:10E9E0002A4B984222D02A4B984229D0294B984250 +:10E9F00030D0294B984237D0284B98423ED0284BF4 +:10EA0000984206D153F8682C42F4700243F8682CFF +:10EA10007047244B984206D153F87C2C42F0706228 +:10EA200043F87C2C7047204B984206D153F8042CB5 +:10EA300042F00F0243F8042C70471C4B984206D159 +:10EA400053F8182C42F0F00243F8182C7047184B7A +:10EA5000984206D153F82C2C42F4706243F82C2CC7 +:10EA60007047144B984206D153F8402C42F4704240 +:10EA700043F8402C7047104B984205D153F8542C62 +:10EA800042F4702243F8542C704700BF0800024043 +:10EA90001C00024030000240440002405800024086 +:10EAA0006C00024080000240080402401C04024046 +:10EAB0003004024044040240580402408A6810B501 +:10EAC0000C6A036814430A6923F4FF4314434A6938 +:10EAD00023F0700314438A691443CA6914434A6AD1 +:10EAE00014438A6A224313430360CB6843600B6874 +:10EAF00083604B68C36010BD002303604360836084 +:10EB0000C360036143618361C361036243628362E3 +:10EB1000704719B1036843F0010303E002684FF640 +:10EB2000FE7313400360704703680AB1194301E0A4 +:10EB300023EA01010160704741607047406880B27C +:10EB400070470000C3004CBF014B024B5860704738 +:10EB5000000402400000024000B5194A20F00043C2 +:10EB6000934283B0014617DDB3F1FF4F04DBF1F7A9 +:10EB70009FFF03B05DF804FB694601F03BF800F02D +:10EB80000302012A0098019911D0022A0AD09AB1F1 +:10EB9000012201F0F3FDECE7002101F0F3F903B0ED +:10EBA0005DF804FB01F0EEF900F10040E1E701F04F +:10EBB000E5FD00F10040DCE701F0E4F9D9E700BF32 +:10EBC000D80F493F30B5C0F3C754A4F17F031E2BC3 +:10EBD00083B0014620DC581C1BDB162B4FEAD17595 +:10EBE00009DDC1F3160040F40000963CA04005B1D9 +:10EBF000404203B030BD114B53F825402046F1F799 +:10EC000059FF019001982146F1F752FF20F000438F +:10EC100033B9002003B030BDF2F71AFA03B030BDAB +:10EC2000C0F31604C0F3C75044F40004C0F19600CA +:10EC300024FA00F0002DDCD0DAE700BFA844010878 +:10EC400000B51D4A20F00043934283B0014618DD11 +:10EC5000B3F1FF4F04DBF1F72BFF03B05DF804FBCA +:10EC6000694600F0C7FF00F00300012818D0022811 +:10EC70000ED0D0B10098019901F084F900F1004064 +:10EC8000EBE70021002201F079FD03B05DF804FB01 +:10EC900000980199012201F071FD00F10040DCE7CC +:10ECA0000098019901F06EF9D7E7009801990122C7 +:10ECB00001F064FDD1E700BFD80F493F70B58AB0BD +:10ECC000054600F023FA224C064694F90030013341 +:10ECD00003D0284601F0C4FF10B930460AB070BD19 +:10ECE000284601F06BFF4FF07E51F2F7A7F900289C +:10ECF000F3D018490122002328460092089301917D +:10ED0000F1F794FB02460B461348CDE90423CDE905 +:10ED1000022301F0ABFD94F90030CDE90601022B8E +:10ED20000BD0684601F0A0FD38B1089B53B9DDE96E +:10ED30000601F1F769FE0AB070BD02F035F8212333 +:10ED40000360F2E702F030F8089B0360EFE700BFD2 +:10ED5000B0010020B0440108BC44010800F03EBBF3 +:10ED60002DE9F0418AB007460C4600F0C7FB9B4EE8 +:10ED7000054696F90030013303D0204601F070FFBC +:10ED800018B928460AB0BDE8F081384601F068FF9E +:10ED90008046002832D120460021F2F727F90028CA +:10EDA000EFD08F4A0123384601920093CDF820809E +:10EDB000F1F73CFBCDE902012046F1F737FB894B27 +:10EDC00096F900400022CDE90623631CCDE9040139 +:10EDD0000DD0022C0BD0684601F046FD002800F053 +:10EDE0009A80089B1BB101F0DFFF089B0360DDE9FF +:10EDF0000601F1F709FE0AB0BDE8F08138460021AE +:10EE0000F2F7F4F818B320460021F2F7EFF8804645 +:10EE1000002855D0724901220023384600920893F9 +:10EE20000191F1F703FBCDE902012046F1F7FEFA6B +:10EE300096F9004000220023CDE90401CDE9062324 +:10EE4000002CC8D0674B0022CDE90623CFE7284627 +:10EE500001F0B8FE8046002862D028460021F2F773 +:10EE6000C5F800288DD0384601F0ACFE002888D0C7 +:10EE7000204601F0A7FE002883D059490422002330 +:10EE80003846009208930191F1F7D0FACDE90201DA +:10EE90002046F1F7CBFA96F9004000220023022C1D +:10EEA000CDE90401CDE9062300F08880684601F031 +:10EEB000DBFC002800F08280089B002B97D092E7B3 +:10EEC000204601F07FFE00283FF45BAF2046002182 +:10EED000F2F796F800283FF454AF414A0123384630 +:10EEE00001920093CDF82080F1F7A0FACDE902015C +:10EEF0002046F1F79BFA3478CDE904010022002C7A +:10EF000030D0394B022CCDE906232ED101F04CFF35 +:10EF100021230360D0E701F047FF2123036060E76E +:10EF2000384601F04FFE002897D0204601F04AFEF7 +:10EF3000002892D0284601F093FE0346D8B928490C +:10EF400001223846089300920191F1F76FFACDE95A +:10EF500002012046F1F76AFA3478CDE90401002C69 +:10EF600031D100220023CDE90623684601F07CFC64 +:10EF70000028A1D1CAE71A4A032338460093019218 +:10EF8000CDF82080F1F752FACDE902012046F1F7E1 +:10EF90004DFA96F90030CDE90401384643BB134BD6 +:10EFA0004FF060420021CDE90623F2F729F800284E +:10EFB0003FD196F90030022B7FF478AF01F0F4FED8 +:10EFC0002223036078E70020002102460B46F1F778 +:10EFD000ABFB022CCDE9060198D0C6E7B0010020BA +:10EFE000B84401080000F03F0000F0FFFFFFEF47CA +:10EFF0001C4B00220021CDE90623F2F701F800287E +:10F00000D7D020464FF07C51F1F75CFEF1F70EFAB5 +:10F0100004460D4601F030FC02460B4620462946C8 +:10F02000F1F7C0FC0028C4D10F4B0022CDE9062324 +:10F03000BFE720464FF07C51F1F744FEF1F7F6F9B7 +:10F0400004460D4601F018FC02460B4620462946B0 +:10F05000F1F7A8FC0028ACD1044B4FF06042CDE999 +:10F060000623A6E70000F07F0000F0FFFFFFEFC7D8 +:10F0700070B58AB0054600F031FF224C064694F97F +:10F080000030013308D0284601F0EAFD20B12846BF +:10F090000021F1F7B5FF10B930460AB070BD1A492A +:10F0A000012200232846019100920893F1F7BEF94E +:10F0B0002478CDE90401CDE902017CB900220023C6 +:10F0C000CDE90623684601F0CFFB88B1089BA3B9C0 +:10F0D000DDE90601F1F798FC0AB070BD00200021BF +:10F0E00002460B46F1F720FB022CCDE90601E9D1DF +:10F0F00001F05AFE21230360E8E701F055FE089B6A +:10F100000360E5E7B0010020C0440108F8B520F035 +:10F110000043B3F17E5F044610D008DCB3F17C5F9E +:10F1200011DAB3F10C5F00F384809D48F8BD01460D +:10F13000F1F7BEFC0146F1F779FEF8BD002840F377 +:10F14000CD800020F8BD0028C0F2CA8001464FF0F3 +:10F150007E50F1F7ADFC4FF07C51F1F7B3FD044662 +:10F1600000F0BCFE8F4906462046F1F7ABFD8E4904 +:10F17000F1F7A0FC2146F1F7A5FD8C49F1F798FCC9 +:10F180002146F1F79FFD8A49F1F794FC2146F1F7FA +:10F1900099FD8849F1F78CFC2146F1F793FD8649EA +:10F1A000F1F788FC2146F1F78DFD8449054620469C +:10F1B000F1F788FD8249F1F77BFC2146F1F782FDEA +:10F1C0008049F1F777FC2146F1F77CFD7E49F1F7A4 +:10F1D0006FFC2146F1F776FD4FF07E51F1F76AFCA6 +:10F1E00001462846F1F722FE3146F1F76BFD26F481 +:10F1F0007F6525F00F05074629462846F1F762FD91 +:10F2000001462046F1F754FC294604463046F1F702 +:10F2100051FC01462046F1F709FE01463846F1F758 +:10F2200049FC01462846F1F745FC0146F1F742FC4E +:10F23000F8BD0146F1F746FD5A490546F1F742FD92 +:10F240005949F1F737FC2946F1F73CFD5749F1F7E9 +:10F250002FFC2946F1F736FD5549F1F72BFC2946DD +:10F26000F1F730FD5349F1F723FC2946F1F72AFD68 +:10F270005149F1F71FFC2946F1F724FD4F49064695 +:10F280002846F1F71FFD4E49F1F712FC2946F1F728 +:10F2900019FD4C49F1F70EFC2946F1F713FD4A49D7 +:10F2A000F1F706FC2946F1F70DFD4FF07E51F1F71D +:10F2B00001FC01463046F1F7B9FD01462046F1F761 +:10F2C00001FD01464148F1F7F3FB01462046F1F705 +:10F2D000EFFB01463E48F1F7EBFBF8BD3D48F8BDBA +:10F2E0004FF07E51F1F7E6FB4FF07C51F1F7EAFC6D +:10F2F0002C490446F1F7E6FC2B49F1F7DBFB2146EC +:10F30000F1F7E0FC2949F1F7D3FB2146F1F7DAFCEC +:10F310002749F1F7CFFB2146F1F7D4FC2549F1F756 +:10F32000C7FB2146F1F7CEFC2349F1F7C3FB214689 +:10F33000F1F7C8FC0646204600F0D0FD1F490546FF +:10F340002046F1F7BFFC1E49F1F7B2FB2146F1F769 +:10F35000B9FC1C49F1F7AEFB2146F1F7B3FC1A49A1 +:10F36000F1F7A6FB2146F1F7ADFC4FF07E51F1F726 +:10F37000A1FB01463046F1F759FD2946F1F7A2FC01 +:10F380001249F1F795FB01462846F1F793FB014638 +:10F39000F1F790FB01461048F1F78AFBF8BD00BF7A +:10F3A000DB0FC93F08EF1138047F4F3A4611243D67 +:10F3B000A80A4E3E90B0A63EABAA2A3E2EC69D3D60 +:10F3C0006133303F2D57014039D119406821A233B4 +:10F3D000DA0FC93FDB0F4940DA0F494021F0004204 +:10F3E000B2F1FF4FF8B5044614DC20F00045B5F14A +:10F3F000FF4F06460EDCB1F17E5F3AD08F1707F063 +:10F40000020747EAD07755B9022F2FD0032F2FD10B +:10F410003148F8BD08462146F1F74CFBF8BDFAB17A +:10F42000B2F1FF4F29D0B5F1FF4F19D0AA1AD2156A +:10F430003C2A19DC002938DB2046F1F7F7FC01F003 +:10F44000BDFB01F0A5FA012F2CD0022F22D0002FF6 +:10F450002FD02249F1F72EFB2149F1F729FBF8BD06 +:10F46000002E15DB1F48F8BD1E48ECE71C48F8BD10 +:10F47000F8BDBDE8F84001F08BBAB5F1FF4F19D0E7 +:10F48000022FF3D0032FC3D0012F1BD00020F8BDD3 +:10F490001548F8BD1149F1F70DFB01461048F1F789 +:10F4A00007FBF8BD00F10040F8BD3C32C4DA002093 +:10F4B000C9E7F8BD022F0CD0032F08D0012F04D0CC +:10F4C0000A48F8BD4FF00040F8BD0948F8BD0948AA +:10F4D000F8BD0948F8BD00BFDB0F49C02EBDBB33E6 +:10F4E000DB0F4940DB0FC93FDB0FC9BFDB0F493FD3 +:10F4F000DB0F49BFE4CB16C0E4CB16402DE9F04F3B +:10F5000031F0004987B00D460C46074611D020F077 +:10F51000004ABAF1FF4F804605DD514807B0BDE80B +:10F52000F04F01F0B7BBB9F1FF4F07DDBAF17E5FD5 +:10F53000F3D14FF07E5007B0BDE8F08F002840DBDC +:10F540000026B9F1FF4F34D0B9F17E5F4CD0B4F151 +:10F55000804F384655D0B4F17C5F1BD001F02EFBB4 +:10F560000146BAF1000F1DD028F04043B3F17E5F91 +:10F5700018D04FEAD87808F1FF3856EA080166D06B +:10F58000B9F19A4F74DD374B9A4533DC002C37DBE9 +:10F590000020D0E7B8F1000FE0DB07B0BDE8F04F86 +:10F5A00000F09CBC002C41DBB8F1000F32DB0846B8 +:10F5B000C1E7BAF17E5FBCD027DD002CE8DB28462E +:10F5C000B9E7B9F1974F13DAB9F17E5F0ADB4FEA79 +:10F5D000E953C3F1960349FA03F202FA03F34B45E8 +:10F5E00000F044820026AFE7002C25DB3846A2E776 +:10F5F0000226A6E71C4B9A4540F39D82002CC7DDEE +:10F600001A480146F1F75EFB95E7002CC0DA05F1D8 +:10F61000004090E7AAF17E5A56EA0A0A12D108463B +:10F62000F1F746FA0146F1F701FC84E74FF07E500E +:10F63000F1F7FCFB0146B7E739464FF07E50F1F792 +:10F64000F5FB78E7012EB2D101F1004073E73946AE +:10F650003846F1F72DFA0146F1F7E8FB6BE700BFFA +:10F66000BC440108F7FF7F3F0700803FCAF24971A1 +:10F67000BAF5000F80F202824FF09741F1F722FBBA +:10F680006FF017028246B34B4FEAEA51CAF3160AEB +:10F690007F399A4501EB020C4AF07E5740F3EB812B +:10F6A000AD4B9A4540F3428200220CF1010CA7F5C4 +:10F6B000000705920599A94B384653F82130CDF83B +:10F6C00004C0194603920493F1F7F2F904998146B4 +:10F6D0003846F1F7EFF901464FF07E50F1F7A6FBFF +:10F6E0000346194648460293F1F7ECFA7910039A5B +:10F6F00041F00051BB4601F5802120F47F6727F0DF +:10F700000F070A448246114638460392F1F7DAFAA7 +:10F7100001464846F1F7CCF9039A81460499104610 +:10F72000F1F7C6F901465846F1F7C2F901463846E5 +:10F73000F1F7C8FA01464846F1F7BAF9029B1946B3 +:10F74000F1F7C0FA514683465046F1F7BBFA01463D +:10F750008146F1F7B7FA8249034648460293F1F72A +:10F76000B1FA8049F1F7A6F94946F1F7ABFA7E49BB +:10F77000F1F7A0F94946F1F7A5FA7C49F1F79AF9B2 +:10F780004946F1F79FFA7A49F1F794F94946F1F7BA +:10F7900099FA7849F1F78EF9029B01461846F1F77C +:10F7A00091FA394681465046F1F784F95946F1F706 +:10F7B00089FA4946F1F77EF9394604903846F1F75F +:10F7C00081FA6D490390F1F775F90499F1F772F92F +:10F7D00020F47F6929F00F0949463846F1F772FA9B +:10F7E000494607465846F1F76DFA6349834648464D +:10F7F000F1F75EF9039A1146F1F75AF901460498B8 +:10F80000F1F756F95146F1F75DFA01465846F1F71E +:10F8100051F9834659463846F1F74CF920F47F6A8E +:10F820002AF00F0A50465549F1F74CFA54498146DF +:10F830005046F1F747FA3946034650460293F1F72E +:10F8400037F901465846F1F733F94E49F1F73AFADC +:10F85000029B01461846F1F72DF94B4B059A53F8D8 +:10F860002210F1F727F9DDF804C007466046F1F7EA +:10F87000D5F9464B059A049053F822B039464846CC +:10F88000F1F718F95946F1F715F90499F1F712F95A +:10F8900020F47F6A2AF00F0A04995046F1F708F91C +:10F8A0005946F1F705F94946F1F702F9014638469C +:10F8B000F1F7FEF824F47F6424F00F04013E56EAC9 +:10F8C00008068146214628460CBF314F4FF07E572F +:10F8D000F1F7EEF85146F1F7F5F9494606462846A4 +:10F8E000F1F7F0F901463046F1F7E4F82146064613 +:10F8F0005046F1F7E7F9054601463046F1F7DAF8E8 +:10F9000000288146044620F00048AA4640F3F880CB +:10F91000B8F1864F00F3C28000F0B280B8F17C5F8E +:10F9200000F3C4804FF00009C84624F47F6424F03B +:10F930000F0420461749F1F7C5F951460546204600 +:10F94000F1F7B6F801463046F1F7B2F81249F1F78F +:10F95000B9F923E071C41C00D6B35D00D844010896 +:10F9600042F1533E55326C3E05A38B3EABAAAA3EF4 +:10F97000B76DDB3E9A99193F000040400038763F52 +:10F98000A0C39D364F38763FD0440108C8440108D3 +:10F99000000080BF0072313F1872313F8649064631 +:10F9A0002046F1F78FF901463046F1F783F8064615 +:10F9B00031462846F1F77EF829460446F1F778F8F3 +:10F9C00001463046F1F774F8214606462046F1F725 +:10F9D00079F97A490546F1F775F97949F1F768F847 +:10F9E0002946F1F76FF97749F1F764F82946F1F7FD +:10F9F00069F97549F1F75CF82946F1F763F973493C +:10FA0000F1F758F82946F1F75DF901462046F1F77C +:10FA10004FF8054629462046F1F754F94FF080414A +:10FA200082462846F1F744F801465046F1F7FEF9C0 +:10FA3000314605462046F1F745F93146F1F73AF8E7 +:10FA400001462846F1F734F82146F1F731F801462E +:10FA50004FF07E50F1F72CF88144B9F5000FC0F259 +:10FA6000A58049463846F1F72DF964E502F0010218 +:10FA7000C2F1020668E5002205921BE6002202E6BA +:10FA800053493046F1F716F8294682464846F1F7C1 +:10FA90000FF801465046F1F7D1FA38B138464D49D2 +:10FAA000F1F710F94B49F1F70DF944E54FEAE85841 +:10FAB000A8F17E084FF4000343FA08F32344C3F38C +:10FAC000C7524548C3F31608A2F17F0140FA01F17D +:10FAD000C2F1960248F4000848FA02F8002C23EA22 +:10FAE00001012846B8BFC8F10008F0F7E1FF8246DF +:10FAF00051463046F0F7DEFF4FEAC859044614E796 +:10FB0000364B98450ADC7FF409AF2946F0F7D0FF61 +:10FB100001463046F1F77EFA0028C7D03846304912 +:10FB2000F1F7D0F82E49F1F7CDF804E501234FF4B1 +:10FB300000120593BEE54FF07E51F0F7B9FF294959 +:10FB40000746F1F7BFF8284981463846F1F7BAF879 +:10FB5000394682463846F1F7B5F84FF07A51834678 +:10FB60003846F1F7AFF801462048F0F7A1FF3946D3 +:10FB7000F1F7A8F801464FF07C50F0F799FF0146E5 +:10FB80005846F1F79FF81A49F1F79CF8014650469C +:10FB9000F0F78EFF074639464846F0F78BFF20F412 +:10FBA0007F6A2AF00F0A494650467DE6414601F039 +:10FBB00075F8014656E700BF8CBEBF354CBB3133EC +:10FBC0000EEADD3555B38A38610B363BABAA2A3EC7 +:10FBD0003CAA3833CAF24971FFFF7F000000164388 +:10FBE0006042A20D00AAB83F70A5EC36ABAAAA3EAF +:10FBF0003BAAB83F2DE9F04FAB4A20F000449442B5 +:10FC000089B006460D4664DDA84A94421CDC0028F3 +:10FC1000A74940F3EC80F0F74BFFA64B24F00F040C +:10FC20009C42064664D0A449F0F742FF0146286092 +:10FC30003046F0F73DFFA049F0F73AFF0123686036 +:10FC4000184609B0BDE8F08F9C4A944262DDB4F1D9 +:10FC5000FF4F46DAE715863FA4EBC7542046F1F77D +:10FC6000F7F9F0F7DBFF0346014620460593F0F76E +:10FC70001FFF4FF08741F1F725F88046F1F7E8F9CB +:10FC8000F0F7CCFF0146044640460694F0F710FF1B +:10FC90004FF08741F1F716F800210790F1F7A6F928 +:10FCA000002800F0C58020460021F1F79FF90028C8 +:10FCB00014BF0123022382480221019000913A4699 +:10FCC00005A8294600F022FA002EC0F2A7800346BC +:10FCD00003E00022286000234A60184609B0BDE80E +:10FCE000F08F0146F0F7E4FE002368602860F4E737 +:10FCF0007449F0F7DDFE74490446F0F7D9FE014679 +:10FD000028602046F0F7D4FE6F49F0F7D1FE0123BA +:10FD10006860E2E700F052FF6C490746F0F7D2FF57 +:10FD20004FF07C51F0F7C6FEF1F792F98246F0F7FA +:10FD300075FF5F498346F0F7C5FF01463846F0F787 +:10FD4000B7FE5D4980465846F0F7BCFFBAF11F0F79 +:10FD500081464946404618DC5D4B0AF1FF3253F8B4 +:10FD6000223024F0FF029A420FD0F0F7A1FE07469E +:10FD70002F6039464046F0F79BFE4946F0F798FE63 +:10FD8000002E686056DB5346A7E7F0F791FEE315B7 +:10FD9000C0F3C7529A1A082A0746E9DD494958466E +:10FDA0000393F0F78FFF074639464046F0F780FE91 +:10FDB000044621464046F0F77BFE3946F0F778FED0 +:10FDC000414907465846F0F77DFF3946F0F770FE87 +:10FDD000814649462046F0F76BFE039BC0F3C752AD +:10FDE0009B1A192B074641DC2860A046C1E7F0F7B3 +:10FDF00061FE304B24F00F049C42064623D02E496E +:10FE0000F0F758FE014628603046F0F751FE2A49C7 +:10FE1000F0F750FE4FF0FF3368605EE795E80C00A6 +:10FE200003F1004102F1004243422A60696054E755 +:10FE3000032340E707F1004700F100402F606860AE +:10FE4000CAF1000349E71F49F0F734FE1E49044692 +:10FE5000F0F730FE014628602046F0F729FE1A49E7 +:10FE6000F0F728FE4FF0FF33686036E7194958462F +:10FE7000F0F728FF074639462046F0F719FE80467E +:10FE800041462046F0F714FE3946F0F711FE1249BC +:10FE900004465846F0F716FF2146F0F709FE814662 +:10FEA0004946404661E700BFD80F493FE3CB1640C3 +:10FEB000800FC93FD00FC93F43443537800F4943B6 +:10FEC000604501080044353708A3852E84F9223F98 +:10FED000E044010800A3852E32318D2420F0004239 +:10FEE000B2F1FF4FF8B5044603462DD25AB30028AD +:10FEF0003DDBB2F5000F4FEAE0502CD37F38C3F35F +:10FF00001603C20743F4000348BF5B0000274010FC +:10FF10005B003E4619244FF08072B5189D4202DC0A +:10FF20005B1BAE181744013C4FEA43034FEA5202F1 +:10FF3000F3D113B107F001031F447F1007F17C5781 +:10FF400007EBC050F8BDF8BD0146F0F7BBFE2146F7 +:10FF5000F0F7B0FDF8BD14F400020FD15B001902F8 +:10FF600002F10102FAD5C2F101021044C6E70146CE +:10FF7000F0F79EFD0146F0F759FFF8BD012210444D +:10FF8000BCE700BF2DE9F84320F00046B6F1485F1A +:10FF900005460F4649DAF1F75BF8002800F09D802E +:10FFA00029462846F0F78EFE4E490446F0F78AFEB1 +:10FFB0004D49F0F77FFD2146F0F784FE4B49F0F7FD +:10FFC00077FD2146F0F77EFE4949F0F773FD2146A3 +:10FFD000F0F778FE4749F0F76BFD2146F0F772FE27 +:10FFE0004549F0F767FD2146F0F76CFE8046204654 +:10FFF0004FF07C51F0F766FE414606462046F0F78A :020000040801F1 -:1000000004909442A060009BE7D13D46012D5F46DD -:100010009B4640F3AD805EAB9B445BF8A04C00E098 -:1000200044465AF8049921464846F0F743FD804675 -:1000300041464846F0F73CFD2146F0F73BFD56456A -:10004000CAF80480CAF80800EAD16C1C06EB8404E4 -:100050000020083654F8041DF0F72CFDB442F9D105 -:10006000002F7ED0369A379B099C00F1004002F1A8 -:10007000004203F10043A06022606360029A02F034 -:1000800007005FB0BDE8F08F002DB8BF00200ADB8D -:1000900036AE6C1C002006EB840454F8041DF0F707 -:1000A00009FDB442F9D1002F35D000F10043099C7D -:1000B000014623603698F0F7FBFC002D08DD36ACD6 -:1000C00004EB850554F8041FF0F7F4FCAC42F9D1B9 -:1000D0000FB100F10040099A5060029A02F0070047 -:1000E0005FB0BDE8F08F002D39DB6C1C36AE002010 -:1000F00006EB840454F8041DF0F7DCFCB442F9D19B -:100100000FB100F10040099A1060029A02F0070056 -:100110005FB0BDE8F08F0346C9E7069A0EAC54F80D -:100120002530083ACDF808A00692002B7FF4B2AE35 -:1001300004EB850353F8041D013D083A0029F9D06A -:100140000692A7E6012314E60B9B9C0046E5204699 -:10015000F0F77EFF0EAA4D4642F829009AE60020ED -:10016000CEE7099C369A379BA0602260636085E7E2 -:10017000002075E76C4201082DE9F84320F00043A8 -:10018000B3F1485F04460F46904603DAF0F760FF8C -:10019000002857D021462046F0F794FD2146054619 -:1001A000F0F790FD294906462846F0F78BFD2849CF -:1001B000F0F77EFC2946F0F785FD2649F0F77AFC3A -:1001C0002946F0F77FFD2449F0F772FC2946F0F745 -:1001D00079FD2249F0F76EFC8146B8F1000F22D07C -:1001E00038464FF07C51F0F76DFD49468046304669 -:1001F000F0F768FD01464046F0F75AFC2946F0F753 -:1002000061FD3946F0F754FC154905463046F0F7D4 -:1002100059FD01462846F0F74DFC01462046F0F70F -:1002200047FCBDE8F88349462846F0F74BFD0C49EA -:10023000F0F73EFC3146F0F745FD2146F0F73AFC79 -:10024000BDE8F8832046BDE8F88300BFD3C92E2F50 -:10025000342FD7321BEF3836010D50398988083CCE -:10026000ABAA2A3E0020704700200149704700BF1A -:100270000000F87F2DE9F043C1F30A5CACF2FF37D0 -:10028000132F83B002460B460D46894680464FEA3F -:10029000D17630DC002F4CDB3A49394101EA0300CA -:1002A00010432DD0490801EA030858EA02080CD08F -:1002B0004FF480233B41132F25EA010141EA030952 -:1002C00014BF4FF000084FF000482F494B4601EB98 -:1002D000C606D6E90045424620462946EFF748FFC4 -:1002E000CDE90001DDE9000122462B46EFF73EFF94 -:1002F00003B0BDE8F083332F07DDB7F5806F3ED044 -:100300001046194603B0BDE8F083ACF2134C4FF031 -:10031000FF3121FA0CF10142F2D049080142D4D058 -:100320004FF0804848FA0CFC20EA010141EA0C0831 -:10033000CBE721F000410143E2D0C3F313010143B5 -:100340004C420C431048590C240B490404F400247B -:1003500044EA010300EBC601D1E9004520462946E5 -:10036000EFF706FFCDE90001DDE900012B4622464B -:10037000EFF7FCFE21F0004343EAC671C2E7EFF756 -:10038000F7FEBFE7FFFF0F00984201082DE9F0419B -:1003900020F00045B5F1A14F0446064608DBB5F153 -:1003A000FF4F6FDC002840F3A0806F48BDE8F0816C -:1003B0006E4B9D4277DCB5F1445F68DB4FF0FF3751 -:1003C00021462046F0F77EFC01468046F0F77AFC95 -:1003D00067490546F0F776FC6649F0F76BFB29465E -:1003E000F0F770FC6449F0F765FB2946F0F76AFC0A -:1003F0006249F0F75FFB2946F0F764FC6049F0F7CB -:1004000059FB2946F0F75EFC5E49F0F753FB414685 -:10041000F0F758FC5C4980462846F0F753FC5B49EE -:10042000F0F746FB2946F0F74DFC5949F0F740FB41 -:100430002946F0F747FC5749F0F73AFB2946F0F711 -:1004400041FC5549F0F734FB2946F0F73BFC7B1C97 -:10045000014640464CD0F0F72DFB2146F0F732FC28 -:100460004E4B4F4D53F82710F0F722FB2146F0F783 -:100470001FFB014655F82700F0F71AFB002E30DB72 -:10048000BDE8F0810146F0F715FBBDE8F081454974 -:10049000F0F710FB4FF07E51F0F7D0FD00288DD023 -:1004A0002046BDE8F08100F087F83F4B04469D42AE -:1004B00029DCA3F5D0039D4244DC0146F0F7FAFAAB -:1004C0004FF07E51F0F7F4FA4FF080410546204698 -:1004D000F0F7F0FA01462846F0F7A8FC002704469A -:1004E0006EE700F10040BDE8F0813048BDE8F081E2 -:1004F000F0F7E0FA2146F0F7E5FB01462046F0F779 -:10050000D7FABDE8F0812A4B9D4214DC4FF07F51B1 -:10051000F0F7CEFA4FF07F5105462046F0F7D2FBB8 -:100520004FF07E51F0F7C6FA01462846F0F77EFC00 -:100530000227044644E701461E48F0F777FC0327EC -:1005400004463DE74FF07E51F0F7B2FA4FF07E518E -:1005500005462046F0F7AEFA01462846F0F766FC5D -:10056000012704462CE700BFDB0FC93FFFFFDF3E3A -:10057000D769853C59DA4B3D356B883D6E2EBA3DC7 -:100580002549123EABAAAA3E21A215BD6BF16E3DD4 -:1005900095879D3D388EE33DCDCC4C3EA842010869 -:1005A000B8420108CAF24971FFFF973FDB0FC9BF8C -:1005B000FFFF1B40000080BF20F00040704700BFDD -:1005C00020F00040B0F1FF4FACBF00200120704789 -:1005D0002DE9F04120F00047FD0D7F3D162D064628 -:1005E00013DC002D80461BDB194F2F41074214D02E -:1005F0001849F0F75FFA0021F0F720FD68B1002EEE -:100600001BDB28EA0700BDE8F081B7F1FF4F04D3F8 -:100610000146F0F74FFABDE8F0813046BDE8F081C1 -:100620000C49F0F747FA0021F0F708FD0028F4D054 -:10063000002E08DB0020BDE8F0814FF4000343FAF0 -:1006400005F5A844DDE7002FE7D00348BDE8F081B9 -:10065000FFFF7F00CAF24971000080BF30F0004008 -:1006600001D102207047A0F50003B3F1FE4F01D283 -:1006700004207047054B421E9A4201D80320704760 -:10068000B0F1FF4358425841704700BFFEFF7F0062 -:10069000004870470000C07F38B530F00044024683 -:1006A00003460D4614D0B4F1FF4F0DD2B4F5000F40 -:1006B0000FD3E40D2C44FE2C2EDC002C1DDD23F08A -:1006C000FF4343EAC45038BD0146F0F7F3F938BDA3 -:1006D00038BD4FF09841F0F7F5FA194B02469D42AC -:1006E00007DBC0F3C7540346193CE3E7154800F0A5 -:1006F0002DF81449F0F7E6FA38BD14F1160F13DAA5 -:100700004CF250339D421146F0DD0F4800F01EF8C8 -:100710000D49F0F7D7FA38BD11460B4800F016F82E -:100720000949F0F7CFFA38BD04F1190023F0FF436F -:1007300043EAC0504FF04C51F0F7C4FA38BD00BF47 -:10074000B03CFFFF6042A20DCAF2497101F00041C6 -:1007500020F000400843704700210A2200F0E8BF63 -:100760002DE9F84FDDF828B0164681468A469846AE -:1007700092B18BB1002503E011D0651CAE420BD9BC -:100780007419640808FB04A748463946D84700286E -:10079000F2DA2646AE42F3D80020BDE8F88F38469C -:1007A000BDE8F88F014B1868704700BFD8050020DE -:1007B00070B50F4E0F4D761BB61007D0043D0024C8 -:1007C000013455F8043F9847A642F9D10A4E0B4D23 -:1007D00003F000FE761BB61008D0043D002401345F -:1007E00055F8043F9847A642F9D170BD70BD00BFCF -:1007F000EC430108EC430108F4430108EC43010811 -:10080000F0B4840743D0541E002A3ED0CDB2034634 -:1008100003E0621E002C38D0144603F8015B9A07EF -:10082000F7D1032C2AD9CDB245EA05250F2C45EA8C -:10083000054515D9A4F110073F0903F1100606EB91 -:1008400007161A46156055609560D5601032B242A1 -:10085000F8D104F00F040137032C03EB07130DD973 -:100860001E462246043A032A46F8045BFAD8221FA1 -:1008700022F003020432134404F003042CB1C9B281 -:100880001C4403F8011BA342FBD1F0BC7047144683 -:100890000346C6E72DE9F04F87B00092044602EB0D -:1008A00042020098520005928008A20701911D465D -:1008B000029040F0838000998B077FD1019AB1F1BB -:1008C000040918BF4FF00109062A7CD9019A009843 -:1008D0005308072A00FB034B40F00281059E264483 -:1008E000B9F1000F40F01B812168DBF80020226085 -:1008F000CBF80010009B009823444FF0000AD34629 -:1009000004931F460393C0F10008B246B74240F279 -:1009100096805346DA469B46BAF1000F00F0D38129 -:10092000039A9DE8090000FB0343B91AC4EB020CCB -:100930008C45A8BF8C46BCF1000F019311DDB9F1C5 -:10094000020FCCEB070040F0448104EB0C0A224676 -:1009500090F800C0137802F801CB524500F8013B33 -:10096000F6D1019B0098CBEB0302C6EB0B06121AE3 -:10097000B24228BF3246002A10DD0198B9F1020FB9 -:10098000C2EB000340F0428107EB020C18783A7882 -:1009900007F8010B674503F8012BF7D1009A8A424B -:1009A000C0F0CE80009CB44246D201980099841BCE -:1009B000A207B6FBF1F601963FF47DAF019A4FF026 -:1009C0000209062A82D8009B03FB024B9846A044EA -:1009D000D84531D25F42DDF800A02346CDF804B0FF -:1009E0004C469946C14523D2464608E03268DBF8BA -:1009F00000303360CBF80020CB4519D95E4606EBBA -:100A0000070B58463146A847002811DD002CEDD0D1 -:100A1000012C00F0A18152465B4631781878013AEA -:100A2000002A06F8010B03F8011BF6DCCB45E5D8DC -:100A3000019AD0449045D5D307B0BDE8F08F384631 -:100A40002146A84700280DDC36E03268DAF800308D -:100A50003360CAF80020C2444FF0010B4644B7424D -:100A60003FF657AF30462146A8470028C0F2908194 -:100A7000F4D1B9F1000FE8D0B9F1010F0DD0009910 -:100A800052463346187892F800C00139002903F81D -:100A900001CB02F8010BF5DCDDE7029B5046314645 -:100AA000A4460C680268013B002B41F8042B40F877 -:100AB000044BF6DC6446CEE70FD1B9F1000F40F0ED -:100AC000B280039B03981A683B6803603A60039AFC -:100AD000009B4FF0010B1A4403920098074415E75E -:100AE000019A009B561E282A03FB064631D8B046C1 -:100AF000274659463846A84700284146584679DBDC -:100B0000A84700283FF7ECAE38464146A84738EAE8 -:100B1000200B28BFBB46B9F1000F3FF4E5AEB9F199 -:100B2000010F00F09180009A5946234618780F78FB -:100B3000013A002A03F8017B01F8010BF6DCD9E643 -:100B40002046009C2B46B1FBF4F12246FFF7A2FEA3 -:100B500028E74FEAD20803FB08F804EB08074FEA3E -:100B600048023946204692460392A847A2440028EC -:100B700051463846C0F29B80A847002840F30081C8 -:100B8000C8F100039A46DA44594650460493A847F0 -:100B9000D8440028414658467EDBA847002840F349 -:100BA000E780039ADDF81080C2EB060AB0444146A4 -:100BB0005046A84700283146404652DBA847002847 -:100BC00097DC50463146A84736EA200828BFD04671 -:100BD0008FE74FEA9C0C22468846116803680CF1A7 -:100BE000FF3CBCF1000F42F8043B40F8041BF4DC6E -:100BF0004146B6E6A8470028FFF672AE38464146A1 -:100C0000A84737EA200B28BFC34669E692088C46FE -:100C100039681868013A002A47F8040B43F8041BA6 -:100C2000F6DC6146BAE6B9F1010F26D00099039BC4 -:100C30003A46187892F800C00139002903F801CB30 -:100C400002F8010BF5DC42E7029A5B4621460F6889 -:100C50001868013A002A41F8040B43F8047BF6DCDB -:100C600048E6A8470028FFF644AF50463146A8475B -:100C70003AEA200828BFB0463BE70399029B384672 -:100C8000A4460C680268013B002B41F8042B40F895 -:100C9000044BF6DC64461AE7A847002881DB50467F -:100CA0004146A8473AEA200B28BFC34679E7A84740 -:100CB0000028FFF665AF20465146A84734EA2007D2 -:100CC00028BF57465CE7019A009B03FB0248049A41 -:100CD0004245BFF4B1AE5F42DDF800B02346924614 -:100CE0004C46CDF804809946D14522D2564608E0BC -:100CF0003268D8F800303360C8F80020C84518D9E9 -:100D0000464606EB070840463146A847002810DD56 -:100D1000002CEDD0012C13D05A4643463178187878 -:100D2000013A002A06F8010B03F8011BF6DCC8455E -:100D3000E6D8019BDA449A45D6D307B0BDE8F08FD8 -:100D4000029B414630680A68013B002B46F8042BA1 -:100D500041F8040BF6DCD1E7029B594630680A687B -:100D6000013B002B46F8042B41F8040BF6DC43E66C -:100D700050464146A84738EA200B28BFD34610E723 -:100D800020465146A8473AEA200728BF2746F7E6FB -:100D9000B7423FF6BEADB9F1000F09D13A683368EA -:100DA0003B60326000994FF0010B0F44761AADE5BD -:100DB000B9F1010F0DD0009932463B46187892F8F0 -:100DC00000C00139002903F801CB02F8010BF5DC62 -:100DD000E8E7029B30463946A4460C680268013BAE -:100DE000002B41F8042B40F8044BF6DC6446D9E7AD -:100DF000830770B506461FD10368A3F1013222EACA -:100E0000030313F0803F08BF031D15D1184653F8A4 -:100E1000044BA4F1013525EA040414F0803FF5D019 -:100E200003782BB1431C1C7818460133002CFAD1EF -:100E300000F07EF8304670BD3046F1E7C9B2F0B43C -:100E4000002947D085070FD00278002A3FD0914271 -:100E50003ED0431C05E013F8012B002A37D0914205 -:100E600036D09A071846F6D1036841EA012747EAC7 -:100E7000074783EA0702A2F10135A3F1013425EA0D -:100E8000020224EA0303134313F0803F11D1021D31 -:100E9000104652F8043B83EA0704A4F10136A3F19B -:100EA000013526EA040425EA0303234313F0803FB7 -:100EB000EED00378002B39D0994209D0431C01E0D1 -:100EC000914205D0184613F8012B002AF8D110469C -:100ED000F0BC704784070BD00378002BF8D0431C7C -:100EE00003E002780133002AF2D099071846F8D1BE -:100EF0000368A3F1013222EA030313F0803F0AD111 -:100F0000031D184653F8042BA2F1013121EA020215 -:100F100012F0803FF5D00378002BD9D0431C1A780B -:100F200018460133002AFAD1F0BC70471846CFE7C3 -:100F300080EA0102844612F0030F4FD111F0030F33 -:100F400032D14DF8044D11F0040F51F8043B0BD091 -:100F5000A3F101329A4312F0803F04BF4CF8043BE6 -:100F600051F8043B16D100BF51F8044BA3F10132F4 -:100F70009A4312F0803FA4F101320BD14CF8043BAC -:100F8000A24312F0803F04BF51F8043B4CF8044BDD -:100F9000EAD023460CF8013B13F0FF0F4FEA33234E -:100FA000F8D15DF8044B704711F0010F06D011F82D -:100FB000012B0CF8012B002A08BF704711F0020F1B -:100FC000BFD031F8022B12F0FF0F16BF2CF8022B06 -:100FD0008CF8002012F47F4FB3D1704711F8012B29 -:100FE0000CF8012B002AF9D1704700BF20F0030153 -:100FF00010F00300C0F1000051F8043B00F1040CB4 -:101000004FEACC0C6FF000021CBF22FA0CF2134323 -:101010004FF0010C4CEA0C2C4CEA0C4CA3EB0C02EC -:1010200022EA030212EACC1204BF51F8043B043056 -:10103000F4D013F0FF0F1FBF013013F47F4F0130C6 -:1010400013F47F0F18BF0130704700BFF0B406469D -:10105000FAB1114B1F6804E0E81A18D1BBB1013A8C -:1010600017D016F8014B3B195B78254603F00303B4 -:10107000012B11F8013B08BF04F12005F818407856 -:1010800000F003000128E7D12033E81AE7D0F0BCD4 -:1010900070471046F0BC7047AC01002040EA0103E5 -:1010A0009B0770B42AD1032A28D90C46034621464F -:1010B00054F8045BA5F1013626EA050616F0803FD8 -:1010C00005D1043A032A43F8045B2146EFD89AB1CC -:1010D0000C78013A1C7001333CB16AB111F8014F30 -:1010E000013A03F8014B002CF7D12AB11A44002130 -:1010F00003F8011B9342FBD170BC70470346E6E73F -:101100004FF0010C2DE9F003644600254FF0FF3647 -:1011100063198B4200EB06070DD23F5D10F8038088 -:10112000B8452ED21D460124C6EB030C63198B4231 -:1011300000EB0607F1D34FF00109C2F800C04C469E -:1011400000254FF0FF376319994200EB070C0ED9C9 -:101150001CF804C010F80380E04519D91D4601248D -:10116000C7EB03096319994200EB070CF0D8701C18 -:101170000137874224BF3846C2F80090BDE8F0032B -:1011800070470CD04FF0010C2E4664466544BFE713 -:1011900009D04FF001092F464C464D44D3E7644532 -:1011A00005D00134B4E74C4504D00134CBE71D46EB -:1011B0000124ADE71D460124C5E700BF2DE9F04F2E -:1011C000ADF21C4D164607460D461046194605AAB7 -:1011D0001C46FFF795FF05AB80460DF2144243F81D -:1011E000044F9342FBD15CB104F1FF3E002306A8FB -:1011F000F25CC3EB0E010133A34240F82210F7D199 -:10120000059930463144424600F010FB002879D160 -:1012100008F1FF3C0346CDF808C0B4448246CDF83F -:1012200004802846CDF80CC01D46A04608E025B134 -:10123000059A934238BFC2EB08039A440025204622 -:101240000AEB0804221A0021384400F0A5FA00280D -:1012500053D1002C51D03B1913F8012C06AB53F895 -:101260002230002BE3D1019A08F1FF39954228BFC3 -:101270002A464A4511D207EB0A03985C16F802C0C9 -:10128000B118844506D031E011F8010F13F802C0FF -:1012900084452BD101324A45F6D3019B02989D42E9 -:1012A00028BF18461AD2DDF808C007EB0A0313F866 -:1012B0000C20DDF80CC09CF8001091426ED1624603 -:1012C00006EB050B06E012F8019D13F801C0E1459D -:1012D00004D108465A4500F1FF31F4D10135854269 -:1012E0005ED8059DAA44C5EB0805A8E7019900252D -:1012F000C1F101039A449244A1E700200DF21C4D74 -:10130000BDE8F08FC8EB0403434538BF43460133C3 -:10131000284605934FF0000A06EB08094546A34608 -:101320000AEB0B04221A0021384400F035FA002899 -:10133000E3D1002CE1D03B1913F8012C06AB53F894 -:1013400022301BBB0BF1FF38454507EB0A0012D2D8 -:10135000435D99F800209A4218BF2B4619D14A469E -:101360002B4605E012F8011F10F803C08C4510D180 -:1013700001334345F6D36B1E1DB9BFE713F1FF33AD -:10138000BCD3F15CC25C9142F8D0059B9A442046E4 -:10139000C6E7C5F1010292449A44F8E701989DE737 -:1013A00007EB0A00AAE700BF2DE9F04F037887B0EA -:1013B00082460E46002B00F0EE800A789AB107466E -:1013C0000131012502E011F8012B5AB1934214BFFB -:1013D000002505F0010517F8013F0C46002BF2D15E -:1013E000237823B93DB1504607B0BDE8F08F002007 -:1013F00007B0BDE8F08F0AF101003178FFF71EFD5C -:10140000A41B80460028F2D0012CEDD0A244504508 -:1014100094BFC0EB0A0501251F2C07D92946324687 -:101420002346FFF7CBFE07B0BDE8F08F214605AAA3 -:101430003046FFF765FE0599814602463144304645 -:1014400000F0F4F900285BD1034609F1FF30029067 -:1014500030440390CDF804909A46284699460AEB0A -:1014600004073A1A0021404400F096F90028BED142 -:10147000002FBCD0019B994528BF4B469C4212D9F6 -:1014800008EB030212F80A10F05CF21888422FD120 -:1014900008EB0A0504E012F8011FE85C884227D136 -:1014A00001339C42F7D8019B02994B4576D90398AA -:1014B00008EB0A0C1CF8013002789A426ED1034600 -:1014C00006EB090B06E013F8015D1CF802008542EB -:1014D00004D111465B4501F1FF32F4D109F1010954 -:1014E00089455DD8059B9A44C3EB04093846B6E7A5 -:1014F00001994FF00009C1F1010292449A44F5E7C5 -:10150000C9EB04034B4538BF4B46013328460593CE -:101510004FF0000B06EB09074D460BEB0409C0EB3F -:1015200009020021404400F037F900287FF45FAF42 -:10153000B9F1000F3FF45BAFAC4298BF08EB0B0072 -:1015400014D908EB050313F80B303A789A421CD1F2 -:101550003A462B4608EB0B0005E012F8011F10F885 -:1015600003C08C4512D101339C42F6D86B1E25B9BD -:101570003AE713F1FF33FFF437AFF15CC25C9142FD -:10158000F7D0059B9B444846C7E72B46C5F10102AF -:1015900093449B44F7E70C46012521E701999DE719 -:1015A00008EB0A0020E700BF024A012312685C3200 -:1015B00000F002B8D8050020F0B420B3074617F8B1 -:1015C000016B0D4601E0A64216D015F8014B002C28 -:1015D000F9D1EEB13E4616F8015B0C4600E073B15E -:1015E00014F8013BAB42FAD15DB100233B701660A9 -:1015F00006463046F0BC704763B13846DEE73746F2 -:10160000E8E72E46F3E710680028D7D10646F0E752 -:101610001660EEE7176006460370EAE72DE9F00F63 -:10162000424C82B0D4F800C001900E4600E026463D -:10163000344614F8015B0CEB0500407800F008001C -:1016400000F0FF0A0028F2D12D2D5BD02B2D04BF16 -:101650007578B41C33F010003CD09946BAF1000FF5 -:101660000CBF6FF0004B4FF0004BBBFBF9F80027AD -:1016700009FB18BB38460CE0303DAB4219DD7E1C3F -:1016800005D0404523D820D009FB0050012714F88D -:10169000015B0CEB0506767816F0040FECD116F022 -:1016A000030606D0012E14BF57263726AD1BAB42CA -:1016B000E5DC7B1C15D0BAF1000F21D10AB1EFB9DE -:1016C000116002B0BDE8F00F70475D45DCDD4FF002 -:1016D000FF37DCE7302D1AD0002BBED10A23994604 -:1016E000BCE70199BAF1000F4FF022030CBF6FF075 -:1016F00000404FF000400B60002AE2D0611EDFE79F -:101700004042DBE7B41C75784FF0010AA2E720786D -:1017100000F0DF00582803D0002B9ED108239CE75F -:10172000102365789946023498E700BFAC01002089 -:1017300030B4044C0D46134601462A46206830BC9E -:10174000FFF76CBFD8050020024B13B1024800F030 -:1017500005B8704700000000691701080146002025 -:101760000246034600F096B838B5094D094C641B93 -:10177000A41018BF05EB840505D0013C55F8043DC5 -:101780009847002CF9D1BDE8384002F029BE00BFCF -:10179000F4430108F8430108830770B4C9B240D08C -:1017A000541E2AB303788B4223D0431C04E0FCB1BF -:1017B000057814468D421CD013F0030F184604F12F -:1017C000FF3203F10103F2D1032C14D8651E54B388 -:1017D00003788B420DD0421C002302E004788C4237 -:1017E00007D0AB42104603F1010302F10102F5D12B -:1017F000002070BC704741EA0126034646EA0646CF -:101800001A6818467240A2F1013525EA020212F068 -:10181000803F03F10403D9D1043C032C1846EFD8D0 -:10182000D4E71446D0E72046E3E700BF032A70B4AC -:1018300028D940EA01039B0713D005780C78A5420C -:1018400024D1013A002305E010F8015F11F8014F9F -:10185000A5421BD1934203F10103F5D1002070BCD6 -:1018600070470C46034625681E682146AE4218465E -:1018700004F1040403F1040304D1043A032A1846D2 -:101880002146F0D8002AD8D11046E8E7281B70BCC2 -:10189000704700BFF0B5274C85B026680746D6F8DC -:1018A0004841002C40D065681F2D1EDD224818B924 -:1018B0004FF0FF3005B0F0BD4FF4C87003910292B5 -:1018C0000193AFF3008003990446029A019B00281C -:1018D000EED0D6F848510020256060600546C6F875 -:1018E0004841C4F88801C4F88C013FB96B1C002042 -:1018F0000235636044F8251005B0F0BD0126AE4006 -:1019000004EB8500C0F88820D4F88821022F42EA31 -:101910000602C4F88821C0F80831E7D1D4F88C3128 -:101920001E43C4F88C61E1E706F5A674C6F8484189 -:10193000B9E700BFD0430108000000001E1E646428 -:1019400064646464000C014008001002000C014053 -:1019500010001002000801400010140200010103F1 -:10196000080409040A040B040C040D04040405040F -:1019700006040704FFFF00010103080409040A0527 -:101980000B050C050D050405050506050705FFFFFC -:10199000A01901085C190108BE190108761901088F -:1019A000000201020202030204020502060207020B -:1019B000080409040A040B040C040D04FFFF0002D0 -:1019C00001020202030204020502060207020804E1 -:1019D00009040A050B050C050D05FFFF1B35000862 -:1019E000D3340008EF3400089D3600089534000811 -:1019F00091340008113B0008513900086D39000886 -:101A000045390008D13800084B3900080000004073 -:101A10000008014001000000001C002800000040F8 -:101A20000008014002000000041C002800000040E3 -:101A30000008014004000000081C002800000040CD -:101A400000080140080000000C1C002800040040B1 -:101A50000008014040000000001D00280004004074 -:101A60000008014080000000041D00280004004020 -:101A7000000C014001000000081D00280004004087 -:101A8000000C0140020000000C1D0028002C014049 -:101A90000008014000010000001B0128002C01404B -:101AA00000080140000800000C1B0128000800404D -:101AB000000C014040000000001E0028000800400B -:101AC000000C014080000000041E002800080040B7 -:101AD000000C014000010000081E00280008004022 -:101AE000000C0140000200000C1E0028002C0140E8 -:101AF0000000004000040040000800400000040016 -:101B000008000C00D00732003200320032003200F0 -:101B100032003200C80064000000414554523132A6 -:101B2000333400303132333435363738394142437B -:101B30004445464748494A4B4C4D4E4F50515253ED -:101B40005455565758595A0099520008F5520008F2 -:101B5000D15200080D5300083553000845530008C2 -:101B6000A5520008FD530008B9520008C5520008EC -:101B70000000803FF704353FF70435BF0000803F89 -:101B80000000803FF70435BFF70435BF0000803FF9 -:101B90000000803FF70435BFF704353F0000803F69 -:101BA0000000803FF704353FF704353F0000803FD9 -:101BB0000000803F00000000000080BF000080BFE8 -:101BC0000000803F000080BF00000000000080BFD8 -:101BD0000000803F000000000000803F000080BF48 -:101BE0000000803F0000803F00000000000080BF38 -:101BF0000000803F0000803F000000BF0000803FE9 -:101C00000000803F000000BF000080BF0000803F58 -:101C10000000803F000080BF0000003F0000803FC8 -:101C20000000803F0000003F0000803F0000803F38 -:101C30000000803F0000003F000080BF000080BF28 -:101C40000000803F000080BF000000BF000080BF98 -:101C50000000803F000000BF0000803F000080BF08 -:101C60000000803F0000803F0000003F000080BF78 -:101C70000000803F000000BFD0B35D3F0000803F08 -:101C80000000803F000000BFD0B35DBF0000803F78 -:101C90000000803F0000003FD0B35D3F000080BFE8 -:101CA0000000803F0000003FD0B35DBF000080BF58 -:101CB0000000803F000080BF00000000000080BFE7 -:101CC0000000803F0000803F000000000000803FD7 -:101CD0000000803F000000000000803F0000803FC7 -:101CE0000000803F000080BF000080BF00000000B7 -:101CF0000000803F000000000000803F000080BF27 -:101D00000000803F0000803F000080BF0000008096 -:101D10000000803F0000803F000000000000000045 -:101D20000000803F000080BF0000000000000000B5 -:101D30000000803F0000000000000000000080BFA5 -:101D40000000803F00000000000000000000803F15 -:101D500000000000000000000301000068200108EE -:101D600004000000881F010804000000E81E0108AC -:101D700002010000101D0108000100000000000029 -:101D8000060000000820010806000000281F0108C6 -:101D9000010100000000000004000000C81F01084D -:101DA00006000000701C010808000000681E010801 -:101DB00008000000701B010808000000F01B01086B -:101DC0000101000000000000000100000000000010 -:101DD000000100000000000004000000D01C010809 -:101DE00006000000081E01080001000000000000BD -:101DF00002010000301D0108010100000000000088 -:101E000000000000000000000000803F000080BFD4 -:101E10000000803F000080BF0000803F000080BFC6 -:101E2000000080BF0000803F0000803F0000803F36 -:101E30000000803F0000803F0000803F0000803FA6 -:101E4000000080BF000080BF0000803F0000000055 -:101E500000000000000000000000803F00000000C3 -:101E600000000000000000000000803F000080BF74 -:101E70000000803F000080BF0000803F000080BF66 -:101E8000000080BF0000803F0000803F0000803FD6 -:101E90000000803F0000803F0000803F0000803F46 -:101EA000000080BF000080BF0000803F000080BFB6 -:101EB0000000803F0000803F0000803F000080BFA6 -:101EC000000080BF000080BF0000803F0000803F16 -:101ED0000000803F000080BF0000803F0000803F86 -:101EE000000080BF0000803F0000803F000080BFF6 -:101EF0000000803F000080BF0000803F000080BFE6 -:101F0000000080BF0000803F0000803F0000803F55 -:101F10000000803F0000803F0000803F0000803FC5 -:101F2000000080BF000080BF0000803FD0B35DBFD5 -:101F30000000003F0000803F0000803FD0B35DBF45 -:101F4000000000BF000080BF0000803FD0B35D3FB5 -:101F50000000003F0000803F0000803FD0B35D3FA5 -:101F6000000000BF000080BF0000803F00000000B4 -:101F7000000080BF0000803F0000803F00000000A4 -:101F80000000803F000080BF0000803F0000000094 -:101F90000000803F000080BF0000803F000080BF45 -:101FA000000000000000803F0000803F0000803FF4 -:101FB000000000000000803F0000803F00000000A3 -:101FC000000080BF000080BF0000803F00000000D4 -:101FD0000000803F000080BF0000803F000080BF05 -:101FE000000080BF000000000000803F00000000F3 -:101FF0000000803F0000803F0000803F0000803FE5 -:10200000000080BF000000000000803F00000000D2 -:10201000A8AAAA3F0000803F0000803F000080BFC8 -:10202000B0AA2ABF000080BF0000803F0000803FB0 -:10203000B0AA2ABF000080BF0000803F000000005F -:10204000A8AAAA3F000080BF0000803F000080BF18 -:10205000B0AA2ABF0000803F0000803F0000803F00 -:10206000B0AA2ABF0000803F0000803F00000000AF -:10207000A8AAAA3F000000000000803F000080BF27 -:10208000B0AA2ABF000000000000803F0000803F8F -:10209000B0AA2ABF0000000024505542582C343109 -:1020A0002C312C303030332C303030312C31313534 -:1020B0003230302C302A31450D0A0024504D544B1B -:1020C0003235312C3131353230302A31460D0A006B -:1020D00024505542582C34312C312C303030332C94 -:1020E000303030312C35373630302C302A32440DF8 -:1020F0000A0024504D544B3235312C3537363030B0 -:102100002A32430D0A0024505542582C34312C31C8 -:102110002C303030332C303030312C3338343030B8 -:102120002C302A32360D0A0024504D544B323531B2 -:102130002C33383430302A32370D0A0024505542BF -:10214000582C34312C312C303030332C303030316D -:102150002C31393230302C302A32330D0A002450E1 -:102160004D544B3235312C31393230302A32320D28 -:102170000A00B56206010300F00500FF19B562060A -:10218000010300F00300FD15B56206010300F00134 -:1021900000FB11B56206010300F00000FA0FB56202 -:1021A00006010300F00200FC13B56206010300F013 -:1021B0000400FE17B562060103000102010E47B5D7 -:1021C00062060103000103010F49B5620601030025 -:1021D000010601124FB562060103000112011E67DC -:1021E000B56206160800030703000000000031E591 -:1021F000B56206080600C80001000100DE6A0000A2 -:102200000000000000C2010098200108BB20010866 -:102210000100000000E10000D0200108F2200108C8 -:102220000200000000960000062101082821010894 -:1022300003000000004B00003C2101085E21010862 -:102240000400000080250000FB290108FB2901088B -:102250004145525431323334000027100804230220 -:1022600020010000000000008025000000C20100E5 -:1022700002000000010000008025000000C20100F3 -:10228000030000000200000080250000004B000059 -:10229000050000000300000080250000004B000046 -:1022A00005000000020000008025000000C20100BF -:1022B00000000000100000008025000000C20100A6 -:1022C00001000000200000008025000000C2010085 -:1022D00000000000010000008025000000C2010095 -:1022E00000000000080000008025000000C201007E -:1022F000000300000400000080250000004B0000E7 -:102300000000000051320108583201085D32010816 -:102310006E32010878320108833201088E320108DA -:102320009932010845320108A23201083F32010802 -:10233000AB320108B5320108C0320108C6320108CB -:10234000C9320108D9320108E0320108000000005A -:10235000E9320108ED320108F3320108F9320108CF -:10236000FC32010803330108063301080B3301086E -:10237000173301081A3301082033010827330108F5 -:10238000313301083B33010844330108523301085B -:102390005E330108653301086B33010878330108A7 -:1023A0008333010890330108000000005B3001080E -:1023B0005F300108ADBF0008863001088B3001088E -:1023C0006DBA00089F300108A830010855BA00080E -:1023D000C5300108CA30010811C00008F9300108F1 -:1023E000FB2901081DBA0008FE300108063101086A -:1023F00035B900081A3101082931010815B900085A -:1024000043310108FB29010861B600084831010881 -:102410004C3101086DB80008993001086831010895 -:10242000BDBC00087B3101088131010805BF0008EF -:102430009C310108A4310108B9BE0008B33101087C -:10244000B831010845B80008DB260108C831010889 -:102450005DBD0008F6310108EA3101088DB60008BB -:10246000EF2B0108FB29010855B60008FB290108DC -:10247000FD310108053201080D320108153201084D -:102480001C320108273201082C320108000000002C -:102490004166726F333220434C492076657273690E -:1024A0006F6E20322E32204D61792032362032304C -:1024B0003134202F2031333A33313A3538202D2032 -:1024C00028636C65616E666C696768742900417683 -:1024D00061696C61626C6520636F6D6D616E6473C0 -:1024E0003A0D0A0025730925730D0A005379737498 -:1024F000656D20557074696D653A2025642073659B -:10250000636F6E64732C20566F6C746167653A203C -:102510002564202A20302E3156202825645320623D -:10252000617474657279290D0A0043505520256441 -:102530004D487A2C20646574656374656420736506 -:102540006E736F72733A2000257320004143434835 -:10255000573A202573002E2563004379636C65206C -:1025600054696D653A2025642C2049324320457218 -:10257000726F72733A2025642C20636F6E666967F0 -:102580002073697A653A2025640D0A0020256420AD -:102590002564000D0A5265626F6F74696E672E2E96 -:1025A0002E00536176696E672E2E2E004D75737462 -:1025B00020626520616E79206F72646572206F669B -:1025C0002041455452313233340D0A004375727242 -:1025D000656E742061737369676E6D656E743A2001 -:1025E000004572726F723A20456E61626C652061BF -:1025F0006E6420706C756720696E204750532066AA -:10260000697273740D0A00456E61626C65642066C0 -:10261000656174757265733A2000417661696C6119 -:10262000626C652066656174757265733A20004955 -:102630006E76616C69642066656174757265206E82 -:10264000616D652E2E2E0D0A0044697361626C6502 -:10265000642000456E61626C656420000D0A4C6563 -:102660006176696E6720434C49206D6F64652E2E3C -:102670002E0D0A00526573657474696E6720746F5D -:102680002064656661756C74732E2E2E004E4709AA -:10269000004F4B0900437573746F6D206D69786549 -:1026A000723A200D0A4D6F746F72095468720952A4 -:1026B0006F6C6C095069746368095961770D0A0081 -:1026C0002325643A09002573090053616E69747902 -:1026D00020636865636B3A09007265736574006C0A -:1026E0006F616400496E76616C6964206D6978651C -:1026F0007220747970652E2E2E0D0A004C6F616465 -:102700006564202573206D69782E2E2E0D0A0057E2 -:10271000726F6E67206E756D626572206F662061E4 -:102720007267756D656E74732C206E6565647320B9 -:102730006964782074687220726F6C6C20706974A0 -:102740006368207961770D0A004D6F746F72206E97 -:10275000756D626572206D757374206265206265A7 -:10276000747765656E203120616E642025640D0AE2 -:102770000043757272656E74206D697865723A20D7 -:1027800025730D0A00417661696C61626C65206D8C -:1027900069786572733A20004D69786572207365B7 -:1027A0007420746F2025730D0A0043757272656E74 -:1027B000742073657474696E67733A200D0A00257E -:1027C000732073657420746F20004552523A20566E -:1027D000616C75652061737369676E6D656E7420D9 -:1027E0006F7574206F662072616E67650D0A004513 -:1027F00052523A20556E6B6E6F776E207661726919 -:1028000061626C65206E616D650D0A0043757272C0 -:10281000656E742070726F66696C653A2025640D70 -:102820000A0055736167653A0D0A6D6F746F722007 -:10283000696E646578205B76616C75655D202D201E -:1028400073686F77205B6F72207365745D206D6FA6 -:10285000746F722076616C75650D0A004E6F20737F -:10286000756368206D6F746F722C207573652061BD -:10287000206E756D626572205B302C2025645D0DC5 -:102880000A004D6F746F7220256420697320736590 -:10289000742061742025640D0A00496E76616C69AC -:1028A00064206D6F746F722076616C75652C2031B9 -:1028B0003030302E2E323030300D0A0053657474B3 -:1028C000696E67206D6F746F7220256420746F20AD -:1028D00025640D0A006175782025752025750D0A7F -:1028E00000496E76616C6964204665617475726535 -:1028F00020696E6465783A206D7573742062652076 -:102900003C2025750D0A0043757272656E74204374 -:102910006F6E6669673A20436F70792065766572DD -:10292000797468696E672062656C6F77206865727C -:10293000652E2E2E0D0A006D697865722025730DA7 -:102940000A00636D697820256400636D697820252D -:102950006420302030203020300D0A00666561741C -:10296000757265202D25730D0A0066656174757298 -:10297000652025730D0A006D61702025730D0A0016 -:10298000736574202573203D20000D0A456E746523 -:1029900072696E6720434C49204D6F64652C20742A -:1029A0007970652027657869742720746F207265B7 -:1029B0007475726E2C206F72202768656C70270DFD -:1029C0000A000D0A2320000D1B5B4B001B5B324AE3 -:1029D0001B5B313B3148004552523A20556E6B6EBD -:1029E0006F776E20636F6D6D616E642C20747279E9 -:1029F000202768656C702700082008006C6F6F70D6 -:102A000074696D6500656D665F61766F6964616E9E -:102A10006365006D69647263006D696E6368656308 -:102A20006B006D6178636865636B00727373695FD7 -:102A30006368616E6E656C00727373695F70776D49 -:102A40005F70726F7669646572006D696E7468722A -:102A50006F74746C65006D61787468726F74746CF7 -:102A600065006D696E636F6D6D616E6400646561B4 -:102A70006462616E6433645F6C6F77006465616487 -:102A800062616E6433645F68696768006E6575745F -:102A900072616C3364006465616462616E643364A6 -:102AA0005F7468726F74746C65006D6F746F725FC1 -:102AB00070776D5F7261746500736572766F5F70B9 -:102AC000776D5F72617465007265746172646564CC -:102AD0005F61726D00666C6170735F7370656564D1 -:102AE00000666978656477696E675F616C74686FAA -:102AF0006C645F6469720073657269616C5F706FAA -:102B000072745F315F7363656E6172696F007365C4 -:102B10007269616C5F706F72745F325F7363656E50 -:102B20006172696F0073657269616C5F706F727456 -:102B30005F335F7363656E6172696F00736572699D -:102B4000616C5F706F72745F345F7363656E617226 -:102B5000696F007265626F6F745F63686172616351 -:102B6000746572006D73705F626175647261746523 -:102B700000636C695F62617564726174650067709F -:102B8000735F6261756472617465006770735F7012 -:102B90006173737468726F7567685F626175647280 -:102BA000617465006770735F70726F7669646572D7 -:102BB0000073657269616C72785F70726F766964B8 -:102BC00065720074656C656D657472795F70726FA3 -:102BD00076696465720074656C656D657472795FA1 -:102BE000737769746368006672736B795F696E7678 -:102BF000657273696F6E00766261747363616C6590 -:102C000000766261746D617863656C6C766F6C746C -:102C100061676500766261746D696E63656C6C7680 -:102C20006F6C7461676500706F7765725F61646374 -:102C30005F6368616E6E656C00616C69676E5F678B -:102C400079726F00616C69676E5F61636300616CCC -:102C500069676E5F6D616700616C69676E5F626F67 -:102C60006172645F726F6C6C00616C69676E5F6249 -:102C70006F6172645F706974636800616C69676E2C -:102C80005F626F6172645F796177006D61785F6127 -:102C90006E676C655F696E636C696E6174696F6E97 -:102CA000006779726F5F6C7066006D6F726F6E5F38 -:102CB0007468726573686F6C64006779726F5F63C4 -:102CC0006D70665F666163746F72006779726F5FC3 -:102CD000636D70666D5F666163746F7200616C74C2 -:102CE0005F686F6C645F7468726F74746C655F6E3C -:102CF00065757472616C00616C745F686F6C645FA1 -:102D0000666173745F6368616E6765007468726F93 -:102D100074746C655F636F7272656374696F6E5F04 -:102D200076616C7565007468726F74746C655F634E -:102D30006F7272656374696F6E5F616E676C650058 -:102D40007961776465616462616E64007961775F5F -:102D5000636F6E74726F6C5F646972656374696FC0 -:102D60006E007961775F646972656374696F6E0084 -:102D70007472695F756E61726D65645F736572769A -:102D80006F0072635F726174650072635F65787073 -:102D90006F007468725F6D6964007468725F657853 -:102DA000706F00726F6C6C5F70697463685F7261E2 -:102DB0007465007961775F72617465007470615F3A -:102DC00072617465007470615F627265616B706FCF -:102DD000696E74006661696C736166655F64656CD9 -:102DE0006179006661696C736166655F6F66665FD5 -:102DF00064656C6179006661696C736166655F74B6 -:102E000068726F74746C65006661696C7361666585 -:102E10005F6D696E5F75736563006661696C736190 -:102E200066655F6D61785F757365630067696D6284 -:102E3000616C5F666C616773006163635F68617298 -:102E40006477617265006163635F6C70665F666181 -:102E500063746F720061636378795F646561646253 -:102E6000616E64006163637A5F6465616462616E70 -:102E700064006163635F756E61726D656463616C4C -:102E8000006163635F7472696D5F70697463680089 -:102E90006163635F7472696D5F726F6C6C00626115 -:102EA000726F5F7461625F73697A65006261726FED -:102EB0005F6E6F6973655F6C7066006261726F5FF1 -:102EC00063665F76656C006261726F5F63665F6107 -:102ED0006C74006D61675F6465636C696E617469D1 -:102EE0006F6E006770735F706F735F7000677073F1 -:102EF0005F706F735F69006770735F706F735F649B -:102F0000006770735F706F73725F70006770735FDC -:102F1000706F73725F69006770735F706F73725F59 -:102F200064006770735F6E61765F70006770735FD7 -:102F30006E61765F69006770735F6E61765F6400D3 -:102F40006770735F77705F726164697573006E613B -:102F5000765F636F6E74726F6C735F6865616469CE -:102F60006E67006E61765F73706565645F6D696E34 -:102F7000006E61765F73706565645F6D6178006E89 -:102F800061765F736C65775F726174650070696408 -:102F90005F636F6E74726F6C6C657200705F7069E6 -:102FA00074636800695F706974636800705F726F52 -:102FB0006C6C00695F726F6C6C00705F7961770098 -:102FC000695F796177005070697463686600497061 -:102FD000697463686600447069746368660050725F -:102FE0006F6C6C660049726F6C6C660044726F6C3B -:102FF0006C660050796177660049796177660044B4 -:1030000079617766006C6576656C5F686F72697A66 -:103010006F6E006C6576656C5F616E676C650070E5 -:103020005F616C7400695F616C7400645F616C74F3 -:1030300000705F6C6576656C00695F6C6576656CC9 -:1030400000645F6C6576656C00705F76656C006926 -:103050005F76656C00645F76656C0061757800660C -:103060006561747572655F6E616D65206175786606 -:103070006C6167206F7220626C616E6B20666F728C -:10308000206C69737400636D6978006465736967A7 -:103090006E20637573746F6D206D6978657200645E -:1030A000656661756C747300726573657420746F06 -:1030B0002064656661756C747320616E642072654E -:1030C000626F6F740064756D70007072696E742049 -:1030D000636F6E666967757261626C652073657493 -:1030E00074696E677320696E20612070617374610A -:1030F000626C6520666F726D006578697400666544 -:103100006174757265006C697374206F72202D761E -:10311000616C206F722076616C00677073706173F0 -:10312000737468726F756768007061737374687226 -:103130006F7567682067707320746F20736572699C -:10314000616C0068656C70006D6170006D6170701D -:10315000696E67206F66207263206368616E6E65BA -:103160006C206F72646572006D69786572206E61A3 -:103170006D65206F72206C697374006D6F746F726F -:10318000006765742F736574206D6F746F72206FA4 -:1031900075747075742076616C75650070726F66F9 -:1031A000696C6500696E64657820283020746F2032 -:1031B00032290073617665007361766520616E6403 -:1031C000207265626F6F74006E616D653D76616C33 -:1031D0007565206F7220626C616E6B206F72202AA1 -:1031E00020666F72206C6973740073686F77207348 -:1031F000797374656D2073746174757300414458FC -:103200004C333435004D505536303530004D4D413E -:103210003834357800424D41323830004C534D330C -:103220003033444C48430046414B45004E6F6E6579 -:10323000004759524F00414343004241524F00530F -:103240004F4E415200475053004750532B4D41477A -:103250000052585F50504D005642415400494E466E -:103260004C494748545F4143435F43414C005258E7 -:103270005F53455249414C004D4F544F525F535498 -:103280004F5000534552564F5F54494C5400534FD2 -:10329000465453455249414C004C45445F52494EB7 -:1032A00047004641494C534146450054454C454D25 -:1032B0004554525900504F5745524D4554455200C0 -:1032C000564152494F0033440052585F50415241D9 -:1032D0004C4C454C5F50574D0052585F4D53500079 -:1032E000525353495F50574D005452490051554174 -:1032F00044500051554144580042490047494D420D -:10330000414C005936004845583600464C59494E04 -:10331000475F57494E4700593400484558365800D2 -:103320004F43544F5838004F43544F464C4154502C -:10333000004F43544F464C41545800414952504C61 -:10334000414E450048454C495F3132305F43435060 -:103350004D0048454C495F39305F4445470056545D -:1033600041494C340048455836480050504D5F5450 -:103370004F5F534552564F004455414C434F5054B4 -:1033800045520053494E474C45434F505445520017 -:10339000435553544F4D0000313201083632010875 -:1033A0003A3201084D3201083F3201084532010826 -:1033B0004932010800000000FC2901080200000059 -:1033C000F41A00200000000028230000052A01084C -:1033D00000000000F61A00200000000001000000BC -:1033E000132A010802000000FA1B0020B0040000AC -:1033F000A4060000192A010802000000FC1B00209E -:1034000000000000D0070000222A0108020000008E -:10341000FE1B002000000000D00700002B2A01083E -:1034200001000000001C002000000000120000004D -:10343000382A010801000000011C002000000000E3 -:10344000010000004A2A010802000000B81B002009 -:1034500000000000D0070000562A0108020000000A -:10346000BA1B002000000000D0070000622A0108FB -:1034700002000000BC1B002000000000D00700007C -:103480006D2A010802000000BE1B002000000000A1 -:10349000D00700007C2A010802000000C01B0020A9 -:1034A00000000000D00700008C2A01080200000084 -:1034B000C21B002000000000D0070000962A01086F -:1034C00002000000C41B002000000000D007000024 -:1034D000AA2A010802000000C61B002032000000DA -:1034E000007D0000B92A010802000000C81B00206E -:1034F00032000000F2010000C82A010800000000AC -:10350000021C00200000000001000000D52A010874 -:1035100000000000031C0020000000006400000008 -:10352000E12A010801000000041C0020FFFFFFFF4A -:1035300001000000F72A010800000000081C00201C -:1035400000000000080000000E2B01080000000031 -:10355000091C00200000000008000000252B0108C5 -:10356000000000000A1C002000000000080000000D -:103570003C2B0108000000000B1C00200000000094 -:1035800008000000532B0108000000001C1C002054 -:10359000300000007E000000642B010804000000E1 -:1035A0000C1C0020B004000000C20100712B0108B7 -:1035B00004000000101C0020B004000000C2010044 -:1035C0007E2B010804000000141C002000000000F5 -:1035D00000C201008B2B010804000000181C002011 -:1035E000B004000000C20100A42B0108000000008C -:1035F000061C00200000000002000000B12B0108A2 -:1036000000000000F81B0020000000000300000084 -:10361000C32B010800000000201C00200000000057 -:1036200002000000D62B010800000000211C002031 -:103630000000000001000000E72B0108000000006E -:10364000221C00200000000001000000F72B0108F0 -:1036500000000000EC1B00200A000000C800000071 -:10366000012C010800000000ED1B00200A000000F2 -:1036700032000000142C010800000000EE1B0020A6 -:103680000A00000032000000272C010800000000A2 -:10369000EF1B00200000000009000000392C010889 -:1036A00000000000CA1B002000000000080000000D -:1036B000442C010800000000CB1B0020000000008B -:1036C000080000004E2C010800000000CC1B002068 -:1036D0000000000008000000582C01080300000052 -:1036E000CE1B00204CFFFFFF68010000692C010881 -:1036F00003000000D01B00204CFFFFFF680100000A -:103700007B2C010803000000D21B00204CFFFFFFB0 -:10371000680100008B2C010802000000DE1B002065 -:103720006400000084030000A12C010802000000D6 -:10373000D61B00200000000000010000AA2C010898 -:1037400000000000DC1B00200000000080000000E2 -:10375000BA2C010802000000D81B00206400000001 -:10376000E8030000CB2C010802000000DA1B002057 -:1037700064000000E8030000DD2C010800000000E8 -:10378000CA1F002001000000FA000000F72C010809 -:1037900000000000CB1F002000000000010000001E -:1037A0000C2D010800000000CE1F002000000000CA -:1037B00096000000262D010802000000CC1F00200A -:1037C00001000000840300005B2E010800000000DF -:1037D000C81F00200000000020000000402D01084C -:1037E00000000000C91F002000000000640000006D -:1037F0004C2D010801000000D41B0020FFFFFFFF3B -:1038000001000000622D01080100000018200020C6 -:10381000FFFFFFFF01000000702D01080100000004 -:10382000192000200000000001000000822D010886 -:1038300000000000781F002000000000FA000000D7 -:103840008A2D010800000000791F00200000000000 -:1038500064000000922D0108000000007A1F002083 -:1038600000000000640000009A2D01080000000024 -:103870007B1F00200000000064000000A32D010851 -:10388000000000007C1F0020000000006400000019 -:10389000B32D0108000000007D1F00200000000083 -:1038A00064000000BC2D0108000000007E1F002005 -:1038B0000000000064000000C52D010802000000A7 -:1038C000801F0020E8030000D0070000D42D01086D -:1038D000000000001020002000000000C8000000D0 -:1038E000E32D01080000000011200020000000006E -:1038F000C8000000F62D0108020000001220002080 -:10390000E8030000D0070000082E010802000000B4 -:103910001420002064000000D00700001A2E0108C7 -:10392000020000001620002064000000B80B000018 -:103930002C2E0108000000001A20002000000000CA -:10394000FF000000392E010800000000D51B0020F8 -:103950000000000005000000462E010800000000E5 -:10396000881F002000000000FA000000552E01080A -:10397000000000008A1F002000000000640000001A -:10398000642E010800000000891F002000000000D4 -:1039900064000000722E0108000000009C1F00203F -:1039A0000000000001000000812E0108030000005B -:1039B000861F0020D4FEFFFF2C010000902E01087E -:1039C00003000000841F0020D4FEFFFF2C01000034 -:1039D0009E2E0108000000008C1F00200000000047 -:1039E00030000000AC2E010805000000901F0020F0 -:1039F0000000000001000000BB2E010805000000CF -:103A0000941F00200000000001000000C72E0108E4 -:103A100005000000981F00200000000001000000C9 -:103A2000D32E010803000000821F0020B0B9FFFF61 -:103A300050460000E32E010800000000301F002067 -:103A400000000000C8000000ED2E0108000000008A -:103A50003A1F002000000000C8000000F72E0108F7 -:103A600000000000441F002000000000C80000000B -:103A7000012F010800000000311F0020000000009D -:103A8000C80000000C2F0108000000003B1F0020B0 -:103A900000000000C8000000172F0108000000000F -:103AA000451F002000000000C8000000222F010870 -:103AB00000000000321F002000000000C8000000CD -:103AC0002C2F0108000000003C1F00200000000017 -:103AD000C8000000362F010800000000461F00202B -:103AE00000000000C8000000402F01080200000094 -:103AF0001C20002000000000D00700004E2F01080D -:103B00000000000020200020000000000100000054 -:103B1000632F010802000000222000200A0000009C -:103B2000D0070000712F01080200000024200020AF -:103B30000A000000D00700007F2F010800000000ED -:103B40001F20002000000000640000008D2F0108ED -:103B500000000000281F00200000000002000000FC -:103B60009C2F0108000000002D1F00200000000015 -:103B7000C8000000A42F010800000000371F00202B -:103B800000000000C8000000732C010800000000C5 -:103B9000411F002000000000C8000000AC2F0108F9 -:103BA000000000002C1F002000000000C8000000E2 -:103BB000B32F010800000000361F002000000000A5 -:103BC000C8000000622C010800000000401F002017 -:103BD00000000000C8000000BA2F0108000000002B -:103BE0002E1F002000000000C8000000C02F0108A8 -:103BF00000000000381F002000000000C800000086 -:103C0000852C010800000000421F00200000000079 -:103C1000C8000000C62F010805000000501F00204A -:103C20000000000064000000CE2F01080500000025 -:103C30005C1F00200000000064000000D62F010877 -:103C400005000000681F0020000000006400000064 -:103C5000DE2F0108050000004C1F002000000000BE -:103C600064000000E52F010805000000581F002037 -:103C70000000000064000000EC2F010805000000B7 -:103C8000641F00200000000064000000F32F010802 -:103C900005000000541F0020000000006400000028 -:103CA000F92F010805000000601F0020000000003F -:103CB00064000000FF2F0108050000006C1F0020B9 -:103CC000000000006400000005300108050000004D -:103CD000741F0020000000000A00000013300108DB -:103CE00005000000701F0020000000000A00000016 -:103CF0001F300108000000002F1F002000000000FE -:103D0000C80000002530010800000000391F002015 -:103D100000000000C80000002B3001080000000077 -:103D2000431F002000000000C800000031300108DF -:103D300000000000331F002000000000C800000049 -:103D400039300108000000003D1F00200000000085 -:103D5000C80000004130010800000000471F00209B -:103D600000000000C8000000493001080000000009 -:103D7000351F002000000000C80000004F3001087F -:103D8000000000003F1F002000000000C8000000ED -:103D90005530010800000000491F0020000000000D -:103DA000C8000000524F4C4C3B50495443483B59CB -:103DB00041573B414C543B506F733B506F73523BE8 -:103DC0004E6176523B4C4556454C3B4D41473B5628 -:103DD000454C3B0041524D3B00414E474C453B005A -:103DE000484F52495A4F4E3B004241524F3B0056BA -:103DF0004152494F3B004D41473B004845414446F5 -:103E00005245453B004845414441444A3B004341FB -:103E10004D535441423B0043414D545249473B00AE -:103E200047505320484F4D453B0047505320484F83 -:103E30004C443B0050415353544852553B0042457B -:103E4000455045523B004C45444D41583B004C4584 -:103E5000444C4F573B004C4C49474854533B00435C -:103E6000414C49423B00474F5645524E4F523B0052 -:103E70004F53442053573B0054454C454D455452F5 -:103E8000593B00746564666D6A69736C6700000075 -:103E90000000004B000000CB61636F736600000000 -:103EA000706F776600000000737172746600000026 -:103EB0000000000000C0153F00000000DCCFD1353D -:103EC0000000803F0000C03F000FC93F000F494085 -:103ED00000CB9640000FC9400053FB4000CB164179 -:103EE00000ED2F41000F49410031624100537B41F9 -:103EF000003A8A4100CB9641005CA34100EDAF41FE -:103F0000007EBC41000FC94100A0D5410031E24113 -:103F100000C2EE410053FB4100F20342003A0A4264 -:103F20000083104200CB164200141D42005C234265 -:103F300000A5294200ED2F4200363642007E3C4269 -:103F400000C74242000F4942A2000000F9000000F1 -:103F5000830000006E0000004E00000044000000DE -:103F60001500000029000000FC00000027000000F0 -:103F700057000000D1000000F500000034000000F0 -:103F8000DD000000C0000000DB0000006200000057 -:103F900095000000990000003C0000004300000074 -:103FA0009000000041000000FE00000051000000F1 -:103FB00063000000AB000000DE000000BB0000005A -:103FC000C500000061000000B700000024000000F0 -:103FD0006E0000003A000000420000004D000000AA -:103FE000D2000000E00000000600000049000000D0 -:103FF0002E000000EA00000009000000D1000000CF -:10400000920000001C000000FE0000001D000000E7 -:10401000EB0000001C000000B100000029000000BF -:10402000A70000003E000000E80000008200000041 -:1040300035000000F50000002E000000BB0000006D -:104040004400000084000000E90000009C00000023 -:104050007000000026000000B40000005F000000B7 -:104060007E000000410000003900000091000000C7 -:10407000D60000003900000083000000530000005B -:1040800039000000F40000009C00000084000000E3 -:104090005F0000008B000000BD000000F900000080 -:1040A000280000003B0000001F000000F800000096 -:1040B00097000000FF000000DE0000000500000087 -:1040C000980000000F000000EF0000002F0000002B -:1040D000110000008B0000005A0000000A000000E0 -:1040E0006D0000001F0000006D00000036000000A1 -:1040F0007E000000CF00000027000000CB00000081 -:1041000009000000B70000004F000000460000005A -:104110003F000000660000009E0000005F000000FD -:10412000EA0000002D0000007500000027000000DC -:10413000BA000000C7000000EB000000E50000002E -:10414000F10000007B0000003D00000007000000BF -:1041500039000000F70000008A0000005200000053 -:1041600092000000EA0000006B000000FB0000006D -:104170005F000000B10000001F0000008D00000083 -:104180005D00000008000000560000000300000071 -:104190003000000046000000FC0000007B00000032 -:1041A0006B000000AB000000F0000000CF0000003A -:1041B000BC000000200000009A000000F400000095 -:1041C000360000001D000000A9000000E300000010 -:1041D00091000000610000005E000000E6000000A9 -:1041E0001B000000080000006500000099000000AE -:1041F000850000005F00000014000000A000000027 -:1042000068000000400000008D000000FF0000007A -:10421000D8000000800000004D0000007300000086 -:10422000270000003100000006000000060000002A -:104230001500000056000000CA00000073000000D6 -:10424000A8000000C900000060000000E2000000BB -:104250007B000000C00000008C0000006B0000002C -:104260000400000007000000090000000000C93F32 -:104270000000F0390000DA370000A2330000842E7D -:104280000000502B0000C2270000D0220000C41FF5 -:104290000000C61B0000441700000000000030436F -:1042A00000000000000030C36937AC3168212233C0 -:1042B000B40F14336821A2333863ED3EDA0F493F5F -:1042C0005E987B3FDA0FC93F00202020202020206D -:1042D00020202828282828202020202020202020B6 -:1042E00020202020202020202088101010101010C6 -:1042F0001010101010101010100404040404040412 -:1043000004040410101010101010414141414141AB -:10431000010101010101010101010101010101018D -:10432000010101011010101010104242424242429D -:10433000020202020202020202020202020202025D -:104340000202020210101010200000000000000005 -:10435000000000000000000000000000000000005D -:10436000000000000000000000000000000000004D -:10437000000000000000000000000000000000003D -:10438000000000000000000000000000000000002D -:10439000000000000000000000000000000000001D -:1043A000000000000000000000000000000000000D -:1043B00000000000000000000000000000000000FD -:1043C00000000000000000000000000043000000AA -:1043D000B0010020F8B500BFF8BC08BC9E4670478D -:0C43E000F8B500BFF8BC08BC9E46704752 -:0843EC00491701083501000822 -:0443F40011010008AB -:1043F800030300000000803F0000803F0000803F72 -:1044080003010001396E00080000803F0000000031 -:1044180000000000DC05DC05DC05DC05DC05DC054E -:10442800DC05DC050000803F010100000000000001 -:104438000000000000000000010000000000000073 -:104448000000000002000000000000000000000062 -:10445800030000000000000000000000040000004D -:104468003C00002000000000D43D010800000000CE -:1044780001000000D93D0108010000000200000011 -:10448800E03D01080200000003000000E93D0108CA -:104498000300000004000000EF3D010804000000D4 -:1044A80005000000F63D01080500000006000000B8 -:1044B800FB3D01080600000007000000053E01085A -:1044C80007000000080000000E3E01080800000078 -:1044D80009000000173E0108090000000A0000005A -:1044E800203E01080A0000000B0000002A3E0108D7 -:1044F8000B0000000C000000343E01080C00000016 -:104508000D0000003E3E01080D0000000E000000F6 -:10451800463E01080E0000000F0000004E3E010854 -:104528000F00000010000000563E010810000000B7 -:10453800110000005F3E0108110000001200000099 -:10454800663E01081200000013000000703E0108DA -:104558001300000014000000783E01081400000059 -:104568001500000000000000FF000000000000002F -:1045780000000000010203040607080900127A007F -:1045880000A24A0402040608000000000102030415 -:10459800010203040607080901000000C8420108D7 -:1045A800000000009C040020040500206C05002089 -:1045B80000000000000000000000000000000000F3 -:1045C80000000000000000000000000000000000E3 -:1045D80000000000CC4301080000000000000000BB -:1045E80000000000000000000000000000000000C3 -:1045F80000000000000000000000000000000000B3 -:1046080000000000000000000000000000000000A2 -:104618000000000000000000000000000000000092 -:104628000000000000000000000000000000000082 -:104638000000000000000000000000000000000072 -:104648000000000000000000010000000000000061 -:104658000E33CDAB34126DE6ECDE05000B00000026 -:104668000000000000000000000000000000000042 -:104678000000000000000000000000000000000032 -:104688000000000000000000000000000000000022 -:104698000000000000000000000000000000000012 -:1046A8000000000000000000000000000000000002 -:1046B80000000000000000000000000000000000F2 -:1046C80000000000000000000000000000000000E2 -:1046D80000000000000000000000000000000000D2 -:1046E80000000000000000000000000000000000C2 -:1046F80000000000000000000000000000000000B2 -:1047080000000000000000000000000000000000A1 -:104718000000000000000000000000000000000091 -:104728000000000000000000000000000000000081 -:104738000000000000000000000000000000000071 -:104748000000000000000000000000000000000061 -:104758000000000000000000000000000000000051 -:104768000000000000000000000000000000000041 -:104778000000000000000000000000000000000031 -:104788000000000000000000000000000000000021 -:104798000000000000000000000000000000000011 -:1047A8000000000000000000000000000000000001 -:1047B80000000000000000000000000000000000F1 -:1047C80000000000000000000000000000000000E1 -:1047D80000000000000000000000000000000000D1 -:1047E80000000000000000000000000000000000C1 -:1047F80000000000000000000000000000000000B1 -:1048080000000000000000000000000000000000A0 -:104818000000000000000000000000000000000090 -:104828000000000000000000000000000000000080 -:104838000000000000000000000000000000000070 -:104848000000000000000000000000000000000060 -:104858000000000000000000000000000000000050 -:104868000000000000000000000000000000000040 -:104878000000000000000000000000000000000030 -:104888000000000000000000000000000000000020 -:104898000000000000000000000000000000000010 -:1048A8000000000000000000000000000000000000 -:1048B80000000000000000000000000000000000F0 -:1048C80000000000000000000000000000000000E0 -:1048D80000000000000000000000000000000000D0 -:1048E80000000000000000000000000000000000C0 -:1048F80000000000000000000000000000000000B0 -:10490800000000000000000000000000000000009F -:10491800000000000000000000000000000000008F -:10492800000000000000000000000000000000007F -:10493800000000000000000000000000000000006F -:10494800000000000000000000000000000000005F -:10495800000000000000000000000000000000004F -:10496800000000000000000000000000000000003F -:10497800000000000000000000000000000000002F -:10498800000000000000000000000000000000001F -:10499800000000000000000000000000000000000F -:1049A80000000000000000000000000000000000FF -:1049B80000000000000000000000000000000000EF -:0C49C8000000000000000000B001002012 +:1000000061FE394604462846F0F75CFE014620466C +:10001000F0F74EFD01463046F0F74AFD01464FF03D +:100020007E50F0F745FDBDE8F8830146F0F74AFE43 +:100030002C490446F0F746FE2B49F0F73BFD2146DC +:10004000F0F740FE2949F0F733FD2146F0F73AFE7C +:100050002749F0F72FFD2146F0F734FE2549F0F748 +:1000600027FD2146F0F72EFE2349F0F723FD214618 +:10007000F0F728FE214B80469E42B8DD204B9E4281 +:1000800027DC06F17F4631464FF07E50F0F710FD39 +:10009000814620464FF07C51F0F714FE3146F0F7D0 +:1000A00007FD414606462046F0F70CFE3946044659 +:1000B0002846F0F707FE01462046F0F7F9FC014616 +:1000C0003046F0F7F5FC01464846F0F7F1FCBDE894 +:1000D000F883DFF834900B4EDBE74FF07E50BDE83D +:1000E000F88300BF4ED747ADF6740F317CF29334DE +:1000F000010DD037610BB63AABAA2A3D9999993ECA +:100100000000483F0000903E0000383F2DE9F04FCE +:10011000DFB00B93013B0293D31E48BF131DB84CB5 +:1001200006466898DB1054F8204023EAE3730C93EA +:10013000DB4302EBC30308940693089C029B0C9AD2 +:100140001D190991C3EB02071DD4699C3D4404EBC2 +:10015000870901354FF0000822AC0AE059F8080081 +:10016000F0F75CFD0137AF4244F8080008F10408DD +:1001700009D0002FF2DA01370020AF4244F808001E +:1001800008F10408F5D1089A002AC0F2DF82089A23 +:100190000B9B02F101089C0022AF4FEA880827441C +:1001A0000025029A002AC0F2F28105EB070B4FF0FE +:1001B00000094FF0000A56F809005BF8041DF0F73B +:1001C00081FD01465046F0F775FC09F10409A1458F +:1001D0008246F0D14AA840F805A004354545E0D153 +:1001E000089A0EAB03EB82030D9391464FEA890305 +:1001F0000793079A5EAB1344B9F1000F53F850AC64 +:1002000023DD0DF134084AAF174490440DAD4FF093 +:100210006E515046F0F756FDF0F71AFFF0F7FEFC6E +:100220004FF087418346F0F74DFD01465046F0F709 +:100230003FFCF0F70DFF594645F8040F57F8040D41 +:10024000F0F738FC45458246E1D15046069900F06A +:1002500025FD4FF078510546F0F734FD00F0BAFC6B +:100260004FF08241F0F72EFD01462846F0F720FCC2 +:100270000546F0F7EDFE8246F0F7D0FC0146284631 +:10028000F0F716FC069A8046002A40F3678109F1D0 +:10029000FF310EA850F82130C2F1080043FA00F2F5 +:1002A00002FA00F01B1A06989244C0F1070743FABD +:1002B00007F70EA840F82130002F32DDB9F1000F0A +:1002C0000AF1010A40F375810EAB079A19461144F1 +:1002D000002507E0C2F5807012B143F8040C012537 +:1002E0008B420BD053F8042B002DF3D0C2F1FF0248 +:1002F0008B4243F8042C4FF00105F3D1069B002BF1 +:100300000DDD012B00F03281022B08D109F1FF3302 +:100310000EA951F8232002F03F0241F82320022FBA +:1003200070D040460021F0F761FE002800F0838085 +:10033000089A09F1FF35AA420DDC079A0EAB0D9819 +:100340001344002253F8041D834242EA0102F9D10A +:10035000002A40F0E481089B0EA85A1E50F8223073 +:10036000002B40F0F18100EB8202012352F8041DC2 +:1003700001330029FAD04B4499450A933DDADDF860 +:100380002CA022AACA44DDF8308002EB8A02C844BD +:10039000C9EB0309131D03920593699A079B4FEA62 +:1003A00089094AAF02EB8808CDF810901F44002558 +:1003B00058F8040FF0F732FC029B039A002B5051BF +:1003C0004FF0000B13DBDDF814A04FF00009AA4436 +:1003D00056F809005AF8041DF0F774FC0146584617 +:1003E000F0F768FB09F10409A1458346F0D1049AAE +:1003F0000435954247F804BFDAD1DDF82890F5E6D8 +:100400007848010841464FF07E50F0F751FB804696 +:10041000002D86D006994FF07E5000F03FFC01463B +:100420004046F0F745FB804640460021F0F7DEFDF0 +:1004300000287FF47DAF069B40465942CDF808A0C6 +:1004400000F02CFC4FF087410446F0F7EDFD00284A +:1004500000F07F814FF06E512046F0F733FCF0F74B +:10046000F7FDF0F7DBFB4FF087410546F0F72AFC7C +:1004700001462046F0F71CFBF0F7EAFD0EAB43F80F +:1004800029002846F0F7E4FD069C09F1010508342F +:100490000EA9069441F8250006994FF07E5000F011 +:1004A000FDFB002D04464FDB6E1C4FEA8508C6EBB2 +:1004B000867A0DF138094AABC1444FEA8A0A98445A +:1004C0004FF0000B59F80B00F0F7A8FB2146F0F7AE +:1004D000F9FB4FF06E5148F80B002046F0F7F2FBA5 +:1004E000ABF1040BD3450446ECD1DFF88C92DDF878 +:1004F00020A00024B34603950497BAF1000FB8BFBB +:10050000002515DB00263746002501E0A7420FDC59 +:1005100058F8061059F80600F0F7D4FB01462846B3 +:10052000F0F7C8FA0137BA45054606F10406EDDAD8 +:100530005EA800EB84030134A345A8F1040843F846 +:10054000A05CDAD1039D049F689C032C00F2988084 +:10055000DFE814F0CB009C009C00310010D109F1C1 +:10056000FF330EA951F823703F12A5E609F1FF33BE +:100570000EA850F8232002F07F0240F82320CEE698 +:100580004FF07C51F0F750FD58B90746C9E64FF0DF +:10059000000A4AA840F805A0043545457FF401AE9D +:1005A0001EE6B9F1000F4FF002070AF1010A3FF70A +:1005B0008BAE0025A2E6002D40F3DC804FEA850BD0 +:1005C0005EAB36AE05F1FF3A5B4406EB8A0A53F8A0 +:1005D000A08C54465B4635AABB462F4600E0C84671 +:1005E00054F804594146284601920093F0F762FA04 +:1005F000814649462846F0F75BFA4146F0F75AFA39 +:10060000019AC4F804909442A060009BE7D13D4653 +:10061000012D5F469B4640F3AD805EAB9B445BF88B +:10062000A04C00E044465AF8049921464846F0F7A9 +:1006300041FA804641464846F0F73AFA2146F0F73B +:1006400039FA5645CAF80480CAF80800EAD16C1C89 +:1006500006EB84040020083654F8041DF0F72AFA4B +:10066000B442F9D1002F7ED0369A379B099C00F115 +:10067000004002F1004203F10043A0602260636089 +:10068000029A02F007005FB0BDE8F08F002DB8BFFE +:1006900000200ADB36AE6C1C002006EB840454F804 +:1006A000041DF0F707FAB442F9D1002F35D000F15C +:1006B0000043099C014623603698F0F7F9F9002DB4 +:1006C00008DD36AC04EB850554F8041FF0F7F2F9A9 +:1006D000AC42F9D10FB100F10040099A5060029A82 +:1006E00002F007005FB0BDE8F08F002D39DB6C1C15 +:1006F00036AE002006EB840454F8041DF0F7DAF956 +:10070000B442F9D10FB100F10040099A1060029A89 +:1007100002F007005FB0BDE8F08F0346C9E7069A14 +:100720000EAC54F82530083ACDF808A00692002BFC +:100730007FF4B2AE04EB850353F8041D013D083A83 +:100740000029F9D00692A7E6012314E60B9B9C0032 +:1007500046E52046F0F77CFC0EAA4D4642F82900FB +:100760009AE60020CEE7099C369A379BA06022606B +:10077000636085E7002075E7844801082DE9F843A8 +:1007800020F00043B3F1485F04460F46904603DA79 +:10079000F0F75EFC002857D021462046F0F792FA89 +:1007A00021460546F0F78EFA294906462846F0F715 +:1007B00089FA2849F0F77CF92946F0F783FA2649A7 +:1007C000F0F778F92946F0F77DFA2449F0F770F947 +:1007D0002946F0F777FA2249F0F76CF98146B8F12B +:1007E000000F22D038464FF07C51F0F76BFA4946A3 +:1007F00080463046F0F766FA01464046F0F758F971 +:100800002946F0F75FFA3946F0F752F915490546DF +:100810003046F0F757FA01462846F0F74BF9014603 +:100820002046F0F745F9BDE8F88349462846F0F739 +:1008300049FA0C49F0F73CF93146F0F743FA214602 +:10084000F0F738F9BDE8F8832046BDE8F88300BF2B +:10085000D3C92E2F342FD7321BEF3836010D503924 +:100860008988083CABAA2A3E002070470020014935 +:10087000704700BF0000F87F2DE9F043C1F30A5C28 +:10088000ACF2FF37132F83B002460B460D46894664 +:1008900080464FEAD17630DC002F4CDB3A493941B3 +:1008A00001EA030010432DD0490801EA030858EA81 +:1008B00002080CD04FF480233B41132F25EA01019D +:1008C00041EA030914BF4FF000084FF000482F49D8 +:1008D0004B4601EBC606D6E900454246204629466E +:1008E000EFF746FCCDE90001DDE9000122462B4689 +:1008F000EFF73CFC03B0BDE8F083332F07DDB7F51D +:10090000806F3ED01046194603B0BDE8F083ACF2CC +:10091000134C4FF0FF3121FA0CF10142F2D049089B +:100920000142D4D04FF0804848FA0CFC20EA010183 +:1009300041EA0C08CBE721F000410143E2D0C3F3C8 +:10094000130101434C420C431048590C240B490439 +:1009500004F4002444EA010300EBC601D1E9004598 +:1009600020462946EFF704FCCDE90001DDE900014E +:100970002B462246EFF7FAFB21F0004343EAC6710B +:10098000C2E7EFF7F5FBBFE7FFFF0F00B048010834 +:100990002DE9F04120F00045B5F1A14F044606468F +:1009A00008DBB5F1FF4F6FDC002840F3A0806F48F3 +:1009B000BDE8F0816E4B9D4277DCB5F1445F68DBAA +:1009C0004FF0FF3721462046F0F77CF9014680467C +:1009D000F0F778F967490546F0F774F96649F0F7DA +:1009E00069F82946F0F76EF96449F0F763F829468B +:1009F000F0F768F96249F0F75DF82946F0F762F917 +:100A00006049F0F757F82946F0F75CF95E49F0F7CE +:100A100051F84146F0F756F95C4980462846F0F710 +:100A200051F95B49F0F744F82946F0F74BF9594979 +:100A3000F0F73EF82946F0F745F95749F0F738F84E +:100A40002946F0F73FF95549F0F732F82946F0F713 +:100A500039F97B1C014640464CD0F0F72BF8214673 +:100A6000F0F730F94E4B4F4D53F82710F0F720F8C0 +:100A70002146F0F71DF8014655F82700F0F718F861 +:100A8000002E30DBBDE8F0810146F0F713F8BDE839 +:100A9000F0814549F0F70EF84FF07E51F0F7CEFAAD +:100AA00000288DD02046BDE8F08100F087F83F4B4C +:100AB00004469D4229DCA3F5D0039D4244DC014657 +:100AC000EFF7F8FF4FF07E51EFF7F2FF4FF0804164 +:100AD00005462046EFF7EEFF01462846F0F7A6F957 +:100AE000002704466EE700F10040BDE8F081304881 +:100AF000BDE8F081EFF7DEFF2146F0F7E3F80146AD +:100B00002046EFF7D5FFBDE8F0812A4B9D4214DC6B +:100B10004FF07F51EFF7CCFF4FF07F510546204655 +:100B2000F0F7D0F84FF07E51EFF7C4FF01462846AA +:100B3000F0F77CF90227044644E701461E48F0F727 +:100B400075F9032704463DE74FF07E51EFF7B0FFFC +:100B50004FF07E5105462046EFF7ACFF0146284690 +:100B6000F0F764F9012704462CE700BFDB0FC93F0B +:100B7000FFFFDF3ED769853C59DA4B3D356B883D39 +:100B80006E2EBA3D2549123EABAAAA3E21A215BD42 +:100B90006BF16E3D95879D3D388EE33DCDCC4C3E4F +:100BA000C0480108D0480108CAF24971FFFF973FC9 +:100BB000DB0FC9BFFFFF1B40000080BF20F00040DB +:100BC000704700BF20F00040B0F1FF4FACBF0020E5 +:100BD000012070472DE9F04120F00047FD0D7F3DD9 +:100BE000162D064613DC002D80461BDB194F2F41C6 +:100BF000074214D01849EFF75DFF0021F0F71EFA05 +:100C000068B1002E1BDB28EA0700BDE8F081B7F1D0 +:100C1000FF4F04D30146EFF74DFFBDE8F0813046AA +:100C2000BDE8F0810C49EFF745FF0021F0F706FA27 +:100C30000028F4D0002E08DB0020BDE8F0814FF43E +:100C4000000343FA05F5A844DDE7002FE7D0034889 +:100C5000BDE8F081FFFF7F00CAF24971000080BF4C +:100C600030F0004001D102207047A0F50003B3F13D +:100C7000FE4F01D204207047054B421E9A4201D814 +:100C800003207047B0F1FF4358425841704700BFFE +:100C9000FEFF7F00004870470000C07F38B530F08D +:100CA0000044024603460D4614D0B4F1FF4F0DD266 +:100CB000B4F5000F0FD3E40D2C44FE2C2EDC002CD9 +:100CC0001DDD23F0FF4343EAC45038BD0146EFF772 +:100CD000F1FE38BD38BD4FF09841EFF7F3FF194BE7 +:100CE00002469D4207DBC0F3C7540346193CE3E7C5 +:100CF000154800F02DF81449EFF7E4FF38BD14F162 +:100D0000160F13DA4CF250339D421146F0DD0F48B6 +:100D100000F01EF80D49EFF7D5FF38BD11460B481E +:100D200000F016F80949EFF7CDFF38BD04F11900BE +:100D300023F0FF4343EAC0504FF04C51EFF7C2FF9E +:100D400038BD00BFB03CFFFF6042A20DCAF249713E +:100D500001F0004120F000400843704700210A22C2 +:100D600000F0E8BF2DE9F84FDDF828B016468146BF +:100D70008A46984692B18BB1002503E011D0651CDC +:100D8000AE420BD97419640808FB04A748463946DB +:100D9000D8470028F2DA2646AE42F3D80020BDE854 +:100DA000F88F3846BDE8F88F014B1868704700BFD0 +:100DB000E005002070B50F4E0F4D761BB61007D022 +:100DC000043D0024013455F8043F9847A642F9D168 +:100DD0000A4E0B4D03F00AFE761BB61008D0043DF8 +:100DE0000024013455F8043F9847A642F9D170BD5C +:100DF00070BD00BF044A0108044A01080C4A0108FA +:100E0000044A0108F0B4840743D0541E002A3ED09F +:100E1000CDB2034603E0621E002C38D0144603F81E +:100E2000015B9A07F7D1032C2AD9CDB245EA0525F3 +:100E30000F2C45EA054515D9A4F110073F0903F128 +:100E4000100606EB07161A46156055609560D560CA +:100E50001032B242F8D104F00F040137032C03EB37 +:100E600007130DD91E462246043A032A46F8045BAE +:100E7000FAD8221F22F003020432134404F00304C0 +:100E80002CB1C9B21C4403F8011BA342FBD1F0BC36 +:100E9000704714460346C6E72DE9F04F87B000922D +:100EA000044602EB42020098520005928008A20715 +:100EB00001911D46029040F0838000998B077FD1FD +:100EC000019AB1F1040918BF4FF00109062A7CD933 +:100ED000019A00985308072A00FB034B40F0028157 +:100EE000059E2644B9F1000F40F01B812168DBF814 +:100EF00000202260CBF80010009B009823444FF0A4 +:100F0000000AD34604931F460393C0F10008B2467B +:100F1000B74240F296805346DA469B46BAF1000F3C +:100F200000F0D381039A9DE8090000FB0343B91A3E +:100F3000C4EB020C8C45A8BF8C46BCF1000F01939A +:100F400011DDB9F1020FCCEB070040F0448104EB56 +:100F50000C0A224690F800C0137802F801CB5245E3 +:100F600000F8013BF6D1019B0098CBEB0302C6EBE6 +:100F70000B06121AB24228BF3246002A10DD019831 +:100F8000B9F1020FC2EB000340F0428107EB020C03 +:100F900018783A7807F8010B674503F8012BF7D169 +:100FA000009A8A42C0F0CE80009CB44246D201989A +:100FB0000099841BA207B6FBF1F601963FF47DAFC2 +:100FC000019A4FF00209062A82D8009B03FB024BCC +:100FD0009846A044D84531D25F42DDF800A02346B0 +:100FE000CDF804B04C469946C14523D2464608E0A8 +:100FF0003268DBF800303360CBF80020CB4519D9DC +:101000005E4606EB070B58463146A847002811DD1F +:10101000002CEDD0012C00F0A18152465B463178C6 +:101020001878013A002A06F8010B03F8011BF6DCD8 +:10103000CB45E5D8019AD0449045D5D307B0BDE85B +:10104000F08F38462146A84700280DDC36E032688C +:10105000DAF800303360CAF80020C2444FF0010BC8 +:101060004644B7423FF657AF30462146A8470028CE +:10107000C0F29081F4D1B9F1000FE8D0B9F1010FBD +:101080000DD0009952463346187892F800C00139C5 +:10109000002903F801CB02F8010BF5DCDDE7029B28 +:1010A00050463146A4460C680268013B002B41F8CB +:1010B000042B40F8044BF6DC6446CEE70FD1B9F1BF +:1010C000000F40F0B280039B03981A683B680360EE +:1010D0003A60039A009B4FF0010B1A440392009868 +:1010E000074415E7019A009B561E282A03FB064673 +:1010F00031D8B046274659463846A84700284146C9 +:10110000584679DBA84700283FF7ECAE3846414601 +:10111000A84738EA200B28BFBB46B9F1000F3FF4BF +:10112000E5AEB9F1010F00F09180009A59462346CF +:1011300018780F78013A002A03F8017B01F8010BB7 +:10114000F6DCD9E62046009C2B46B1FBF4F12246A2 +:10115000FFF7A2FE28E74FEAD20803FB08F804EBEA +:1011600008074FEA48023946204692460392A847AC +:10117000A244002851463846C0F29B80A847002868 +:1011800040F30081C8F100039A46DA4459465046BC +:101190000493A847D8440028414658467EDBA84718 +:1011A000002840F3E780039ADDF81080C2EB060ABE +:1011B000B04441465046A84700283146404652DBDD +:1011C000A847002897DC50463146A84736EA200851 +:1011D00028BFD0468FE74FEA9C0C2246884611680C +:1011E00003680CF1FF3CBCF1000F42F8043B40F8EF +:1011F000041BF4DC4146B6E6A8470028FFF672AEB1 +:1012000038464146A84737EA200B28BFC34669E65F +:1012100092088C4639681868013A002A47F8040B8E +:1012200043F8041BF6DC6146BAE6B9F1010F26D09B +:101230000099039B3A46187892F800C001390029BA +:1012400003F801CB02F8010BF5DC42E7029A5B469A +:1012500021460F681868013A002A41F8040B43F848 +:10126000047BF6DC48E6A8470028FFF644AF50466A +:101270003146A8473AEA200828BFB0463BE7039921 +:10128000029B3846A4460C680268013B002B41F8DB +:10129000042B40F8044BF6DC64461AE7A847002804 +:1012A00081DB50464146A8473AEA200B28BFC34697 +:1012B00079E7A8470028FFF665AF20465146A847C2 +:1012C00034EA200728BF57465CE7019A009B03FBDE +:1012D0000248049A4245BFF4B1AE5F42DDF800B067 +:1012E000234692464C46CDF804809946D14522D2F9 +:1012F000564608E03268D8F800303360C8F800205D +:10130000C84518D9464606EB070840463146A84767 +:10131000002810DD002CEDD0012C13D05A46434696 +:1013200031781878013A002A06F8010B03F8011BFE +:10133000F6DCC845E6D8019BDA449A45D6D307B017 +:10134000BDE8F08F029B414630680A68013B002BE4 +:1013500046F8042B41F8040BF6DCD1E7029B594612 +:1013600030680A68013B002B46F8042B41F8040B57 +:10137000F6DC43E650464146A84738EA200B28BF32 +:10138000D34610E720465146A8473AEA200728BF2F +:101390002746F7E6B7423FF6BEADB9F1000F09D1D7 +:1013A0003A6833683B60326000994FF0010B0F449C +:1013B000761AADE5B9F1010F0DD0009932463B46E2 +:1013C000187892F800C00139002903F801CB02F81F +:1013D000010BF5DCE8E7029B30463946A4460C6871 +:1013E0000268013B002B41F8042B40F8044BF6DC6B +:1013F0006446D9E7830770B506461FD10368A3F199 +:10140000013222EA030313F0803F08BF031D15D108 +:10141000184653F8044BA4F1013525EA040414F0EE +:10142000803FF5D003782BB1431C1C78184601335C +:10143000002CFAD100F07EF8304670BD3046F1E75E +:10144000C9B2F0B4002947D085070FD00278002A2E +:101450003FD091423ED0431C05E013F8012B002AF7 +:1014600037D0914236D09A071846F6D1036841EA40 +:10147000012747EA074783EA0702A2F10135A3F1F2 +:10148000013425EA020224EA0303134313F0803FE8 +:1014900011D1021D104652F8043B83EA0704A4F15F +:1014A0000136A3F1013526EA040425EA03032343A8 +:1014B00013F0803FEED00378002B39D0994209D049 +:1014C000431C01E0914205D0184613F8012B002A75 +:1014D000F8D11046F0BC704784070BD00378002B7E +:1014E000F8D0431C03E002780133002AF2D09907B8 +:1014F0001846F8D10368A3F1013222EA030313F07E +:10150000803F0AD1031D184653F8042BA2F1013184 +:1015100021EA020212F0803FF5D00378002BD9D0E7 +:10152000431C1A7818460133002AFAD1F0BC7047E0 +:101530001846CFE780EA0102844612F0030F4FD12C +:1015400011F0030F32D14DF8044D11F0040F51F892 +:10155000043B0BD0A3F101329A4312F0803F04BF49 +:101560004CF8043B51F8043B16D100BF51F8044B32 +:10157000A3F101329A4312F0803FA4F101320BD162 +:101580004CF8043BA24312F0803F04BF51F8043BE7 +:101590004CF8044BEAD023460CF8013B13F0FF0F44 +:1015A0004FEA3323F8D15DF8044B704711F0010F77 +:1015B00006D011F8012B0CF8012B002A08BF704748 +:1015C00011F0020FBFD031F8022B12F0FF0F16BF3F +:1015D0002CF8022B8CF8002012F47F4FB3D1704707 +:1015E00011F8012B0CF8012B002AF9D1704700BF2C +:1015F00020F0030110F00300C0F1000051F8043B9B +:1016000000F1040C4FEACC0C6FF000021CBF22FA70 +:101610000CF213434FF0010C4CEA0C2C4CEA0C4C2E +:10162000A3EB0C0222EA030212EACC1204BF51F827 +:10163000043B0430F4D013F0FF0F1FBF013013F44C +:101640007F4F013013F47F0F18BF0130704700BF88 +:10165000F0B40646FAB1114B1F6804E0E81A18D13D +:10166000BBB1013A17D016F8014B3B195B78254600 +:1016700003F00303012B11F8013B08BF04F120051F +:10168000F818407800F003000128E7D12033E81A69 +:10169000E7D0F0BC70471046F0BC7047B4010020A2 +:1016A00040EA01039B0770B42AD1032A28D90C46CB +:1016B0000346214654F8045BA5F1013626EA0506E7 +:1016C00016F0803F05D1043A032A43F8045B214613 +:1016D000EFD89AB10C78013A1C7001333CB16AB171 +:1016E00011F8014F013A03F8014B002CF7D12AB150 +:1016F0001A44002103F8011B9342FBD170BC7047D0 +:101700000346E6E74FF0010C2DE9F003644600259F +:101710004FF0FF3663198B4200EB06070DD23F5D99 +:1017200010F80380B8452ED21D460124C6EB030CE9 +:1017300063198B4200EB0607F1D34FF00109C2F8A1 +:1017400000C04C4600254FF0FF376319994200EB6B +:10175000070C0ED91CF804C010F80380E04519D915 +:101760001D460124C7EB03096319994200EB070CDE +:10177000F0D8701C0137874224BF3846C2F8009069 +:10178000BDE8F00370470CD04FF0010C2E466446C4 +:101790006544BFE709D04FF001092F464C464D4440 +:1017A000D3E7644505D00134B4E74C4504D0013497 +:1017B000CBE71D460124ADE71D460124C5E700BF68 +:1017C0002DE9F04FADF21C4D164607460D4610466A +:1017D000194605AA1C46FFF795FF05AB80460DF29A +:1017E000144243F8044F9342FBD15CB104F1FF3E35 +:1017F000002306A8F25CC3EB0E010133A34240F8BC +:101800002210F7D1059930463144424600F010FBD2 +:10181000002879D108F1FF3C0346CDF808C0B44454 +:101820008246CDF804802846CDF80CC01D46A0465F +:1018300008E025B1059A934238BFC2EB08039A44E9 +:10184000002520460AEB0804221A0021384400F043 +:10185000A5FA002853D1002C51D03B1913F8012CC4 +:1018600006AB53F82230002BE3D1019A08F1FF397F +:10187000954228BF2A464A4511D207EB0A03985CD5 +:1018800016F802C0B118844506D031E011F8010FF6 +:1018900013F802C084452BD101324A45F6D3019B8F +:1018A00002989D4228BF18461AD2DDF808C007EBFF +:1018B0000A0313F80C20DDF80CC09CF800109142CC +:1018C0006ED1624606EB050B06E012F8019D13F897 +:1018D00001C0E14504D108465A4500F1FF31F4D179 +:1018E000013585425ED8059DAA44C5EB0805A8E7E9 +:1018F00001990025C1F101039A449244A1E7002017 +:101900000DF21C4DBDE8F08FC8EB0403434538BF12 +:1019100043460133284605934FF0000A06EB0809B9 +:101920004546A3460AEB0B04221A0021384400F076 +:1019300035FA0028E3D1002CE1D03B1913F8012C33 +:1019400006AB53F822301BBB0BF1FF38454507EBC4 +:101950000A0012D2435D99F800209A4218BF2B4624 +:1019600019D14A462B4605E012F8011F10F803C0B2 +:101970008C4510D101334345F6D36B1E1DB9BFE72B +:1019800013F1FF33BCD3F15CC25C9142F8D0059BEC +:101990009A442046C6E7C5F1010292449A44F8E70A +:1019A00001989DE707EB0A00AAE700BF2DE9F04F79 +:1019B000037887B082460E46002B00F0EE800A784E +:1019C0009AB107460131012502E011F8012B5AB105 +:1019D000934214BF002505F0010517F8013F0C469E +:1019E000002BF2D1237823B93DB1504607B0BDE8B2 +:1019F000F08F002007B0BDE8F08F0AF101003178C8 +:101A0000FFF71EFDA41B80460028F2D0012CEDD06C +:101A1000A244504594BFC0EB0A0501251F2C07D9ED +:101A2000294632462346FFF7CBFE07B0BDE8F08FCC +:101A3000214605AA3046FFF765FE05998146024614 +:101A40003144304600F0F4F900285BD1034609F137 +:101A5000FF30029030440390CDF804909A46284617 +:101A600099460AEB04073A1A0021404400F096F91F +:101A70000028BED1002FBCD0019B994528BF4B4602 +:101A80009C4212D908EB030212F80A10F05CF2181B +:101A900088422FD108EB0A0504E012F8011FE85C28 +:101AA000884227D101339C42F7D8019B02994B45CC +:101AB00076D9039808EB0A0C1CF8013002789A4298 +:101AC0006ED1034606EB090B06E013F8015D1CF826 +:101AD0000200854204D111465B4501F1FF32F4D189 +:101AE00009F1010989455DD8059B9A44C3EB0409B6 +:101AF0003846B6E701994FF00009C1F1010292445E +:101B00009A44F5E7C9EB04034B4538BF4B46013314 +:101B1000284605934FF0000B06EB09074D460BEBEB +:101B20000409C0EB09020021404400F037F9002805 +:101B30007FF45FAFB9F1000F3FF45BAFAC4298BFE9 +:101B400008EB0B0014D908EB050313F80B303A78B7 +:101B50009A421CD13A462B4608EB0B0005E012F8DE +:101B6000011F10F803C08C4512D101339C42F6D8F6 +:101B70006B1E25B93AE713F1FF33FFF437AFF15C81 +:101B8000C25C9142F7D0059B9B444846C7E72B4671 +:101B9000C5F1010293449B44F7E70C46012521E778 +:101BA00001999DE708EB0A0020E700BF024A0123E4 +:101BB00012685C3200F002B8E0050020F0B420B3F7 +:101BC000074617F8016B0D4601E0A64216D015F83E +:101BD000014B002CF9D1EEB13E4616F8015B0C46E4 +:101BE00000E073B114F8013BAB42FAD15DB10023C0 +:101BF0003B70166006463046F0BC704763B138460D +:101C0000DEE73746E8E72E46F3E710680028D7D12D +:101C10000646F0E71660EEE7176006460370EAE74F +:101C20002DE9F00F424C82B0D4F800C001900E466E +:101C300000E02646344614F8015B0CEB05004078C2 +:101C400000F0080000F0FF0A0028F2D12D2D5BD033 +:101C50002B2D04BF7578B41C33F010003CD099468E +:101C6000BAF1000F0CBF6FF0004B4FF0004BBBFB05 +:101C7000F9F8002709FB18BB38460CE0303DAB42B1 +:101C800019DD7E1C05D0404523D820D009FB00502B +:101C9000012714F8015B0CEB0506767816F0040FAB +:101CA000ECD116F0030606D0012E14BF57263726B6 +:101CB000AD1BAB42E5DC7B1C15D0BAF1000F21D186 +:101CC0000AB1EFB9116002B0BDE8F00F70475D4591 +:101CD000DCDD4FF0FF37DCE7302D1AD0002BBED112 +:101CE0000A239946BCE70199BAF1000F4FF022038D +:101CF0000CBF6FF000404FF000400B60002AE2D0B4 +:101D0000611EDFE74042DBE7B41C75784FF0010A43 +:101D1000A2E7207800F0DF00582803D0002B9ED1E6 +:101D200008239CE7102365789946023498E700BFA2 +:101D3000B401002030B4044C0D46134601462A4637 +:101D4000206830BCFFF76CBFE0050020024B13B1E8 +:101D5000024800F005B87047000000006D1D010842 +:101D6000014600200246034600F096B838B5094DFA +:101D7000094C641BA41018BF05EB840505D0013C79 +:101D800055F8043D9847002CF9D1BDE8384002F0E1 +:101D900033BE00BF0C4A0108104A0108830770B423 +:101DA000C9B240D0541E2AB303788B4223D0431CBF +:101DB00004E0FCB1057814468D421CD013F0030FEB +:101DC000184604F1FF3203F10103F2D1032C14D8B9 +:101DD000651E54B303788B420DD0421C002302E0F1 +:101DE00004788C4207D0AB42104603F1010302F1A4 +:101DF0000102F5D1002070BC704741EA012603467C +:101E000046EA06461A6818467240A2F1013525EAEC +:101E1000020212F0803F03F10403D9D1043C032CE9 +:101E20001846EFD8D4E71446D0E72046E3E700BFD2 +:101E3000032A70B428D940EA01039B0713D0057820 +:101E40000C78A54224D1013A002305E010F8015F87 +:101E500011F8014FA5421BD1934203F10103F5D1C3 +:101E6000002070BC70470C46034625681E6821465A +:101E7000AE42184604F1040403F1040304D1043A09 +:101E8000032A18462146F0D8002AD8D11046E8E7A0 +:101E9000281B70BC704700BFF0B5274C85B0266882 +:101EA0000746D6F84841002C40D065681F2D1EDD3E +:101EB000224818B94FF0FF3005B0F0BD4FF4C8709C +:101EC000039102920193AFF3008003990446029AB2 +:101ED000019B0028EED0D6F84851002025606060B4 +:101EE0000546C6F84841C4F88801C4F88C013FB9DA +:101EF0006B1C00200235636044F8251005B0F0BD6E +:101F00000126AE4004EB8500C0F88820D4F8882173 +:101F1000022F42EA0602C4F88821C0F80831E7D14E +:101F2000D4F88C311E43C4F88C61E1E706F5A67441 +:101F3000C6F84841B9E700BFE849010800000000C1 +:101F40001E1E646464646464000C01400800100296 +:101F5000000C0140100010020008014000101402A3 +:101F600000010103080409040A040B040C040D0415 +:101F70000404050406040704FFFF0001010308042C +:101F800009040A050B050C050D05040505050605E4 +:101F90000705FFFFA41F0108601F0108C21F0108F9 +:101FA0007A1F010800020102020203020402050274 +:101FB00006020702080409040A040B040C040D04B9 +:101FC000FFFF0002010202020302040205020602F0 +:101FD0000702080409040A050B050C050D05FFFF9F +:101FE0001B350008D3340008EF3400089D36000884 +:101FF0009534000891340008113B0008513900085D +:102000006D39000845390008D13800084B390008FF +:10201000000000400008014001000000001C0028F2 +:10202000000000400008014002000000041C0028DD +:10203000000000400008014004000000081C0028C7 +:102040000000004000080140080000000C1C0028AF +:10205000000400400008014040000000001D00286E +:10206000000400400008014080000000041D00281A +:1020700000040040000C014001000000081D002881 +:1020800000040040000C0140020000000C1D00286C +:10209000002C01400008014000010000001B012845 +:1020A000002C014000080140000800000C1B012822 +:1020B00000080040000C014040000000001E002805 +:1020C00000080040000C014080000000041E0028B1 +:1020D00000080040000C014000010000081E00281C +:1020E00000080040000C0140000200000C1E002807 +:1020F000002C0140000000400004004000080040A7 +:102100000000040008000C00D0073200320032004A +:102110003200320032003200C80064000000414545 +:10212000545231323334003031323334353637386B +:10213000394142434445464748494A4B4C4D4E4F2E +:10214000505152535455565758595A00A9520008E5 +:1021500005530008E15200081D53000845530008CC +:1021600055530008B55200080D540008C952000824 +:10217000D5520008000100010000803FF704353F00 +:10218000F70435BF0000803F0000803FF70435BFF3 +:10219000F70435BF0000803F0000803FF70435BFE3 +:1021A000F704353F0000803F0000803FF704353FD3 +:1021B000F704353F0000803F0000803F0000000032 +:1021C000000080BF000080BF0000803F000080BF93 +:1021D00000000000000080BF0000803F0000000001 +:1021E0000000803F000080BF0000803F0000803F73 +:1021F00000000000000080BF0000803F0000803F22 +:10220000000000BF0000803F0000803F000000BFD2 +:10221000000080BF0000803F0000803F000080BFC2 +:102220000000003F0000803F0000803F0000003FB2 +:102230000000803F0000803F0000803F0000003F22 +:10224000000080BF000080BF0000803F000080BF12 +:10225000000000BF000080BF0000803F000000BF02 +:102260000000803F000080BF0000803F0000803FF2 +:102270000000003F000080BF0000803F000000BF62 +:10228000D0B35D3F0000803F0000803F000000BFF2 +:10229000D0B35DBF0000803F0000803F0000003FE2 +:1022A000D0B35D3F000080BF0000803F0000003FD2 +:1022B000D0B35DBF000080BF0000803F000080BF42 +:1022C00000000000000080BF0000803F0000803F51 +:1022D000000000000000803F0000803F0000000080 +:1022E0000000803F0000803F0000803F000080BF72 +:1022F000000080BF000000000000803F00000000E0 +:102300000000803F000080BF0000803F0000803F51 +:10231000000080BF000000800000803F0000803F80 +:1023200000000000000000000000803F000080BFAF +:1023300000000000000000000000803F00000000DE +:1023400000000000000080BF0000803F000000008F +:10235000000000000000803F0000000000000000BE +:102360000301000070260108040000009025010808 +:1023700004000000F02401080201000018230108F5 +:102380000001000000000000060000001026010807 +:1023900006000000302501080101000000000000D7 +:1023A00004000000D0250108060000007822010882 +:1023B00008000000702401080800000078210108CE +:1023C00008000000F82101080101000000000000E1 +:1023D00000010000000000000001000000000000FB +:1023E00004000000D82201080600000010240108A3 +:1023F0000001000000000000020100003823010875 +:1024000001010000000000000000000000000000CA +:102410000000803F000080BF0000803F000080BFC0 +:102420000000803F000080BF000080BF0000803FB0 +:102430000000803F0000803F0000803F0000803FA0 +:102440000000803F0000803F000080BF000080BF90 +:102450000000803F000000000000000000000000BD +:102460000000803F000000000000000000000000AD +:102470000000803F000080BF0000803F000080BF60 +:102480000000803F000080BF000080BF0000803F50 +:102490000000803F0000803F0000803F0000803F40 +:1024A0000000803F0000803F000080BF000080BF30 +:1024B0000000803F000080BF0000803F0000803FA0 +:1024C0000000803F000080BF000080BF000080BF90 +:1024D0000000803F0000803F0000803F000080BF80 +:1024E0000000803F0000803F000080BF0000803F70 +:1024F0000000803F000080BF0000803F000080BFE0 +:102500000000803F000080BF000080BF0000803FCF +:102510000000803F0000803F0000803F0000803FBF +:102520000000803F0000803F000080BF000080BFAF +:102530000000803FD0B35DBF0000003F0000803F3F +:102540000000803FD0B35DBF000000BF000080BF2F +:102550000000803FD0B35D3F0000003F0000803F9F +:102560000000803FD0B35D3F000000BF000080BF8F +:102570000000803F00000000000080BF0000803F9E +:102580000000803F000000000000803F000080BF8E +:102590000000803F000000000000803F000080BF7E +:1025A0000000803F000080BF000000000000803F6E +:1025B0000000803F0000803F000000000000803FDE +:1025C0000000803F00000000000080BF000080BFCE +:1025D0000000803F000000000000803F000080BF3E +:1025E0000000803F000080BF000080BF00000000AE +:1025F0000000803F000000000000803F0000803F9E +:102600000000803F0000803F000080BF000000000D +:102610000000803F00000000A8AAAA3F0000803F01 +:102620000000803F000080BFB0AA2ABF000080BF2A +:102630000000803F0000803FB0AA2ABF000080BF9A +:102640000000803F00000000A8AAAA3F000080BF51 +:102650000000803F000080BFB0AA2ABF0000803F7A +:102660000000803F0000803FB0AA2ABF0000803FEA +:102670000000803F00000000A8AAAA3F0000000060 +:102680000000803F000080BFB0AA2ABF0000000009 +:102690000000803F0000803FB0AA2ABF0000000079 +:1026A00024505542582C34312C312C303030332CBE +:1026B000303030312C3131353230302C302A314508 +:1026C0000D0A0024504D544B3235312C3131353206 +:1026D00030302A31460D0A0024505542582C3431EE +:1026E0002C312C303030332C303030312C353736E3 +:1026F00030302C302A32440D0A0024504D544B32D5 +:1027000035312C35373630302A32430D0A0024500B +:102710005542582C34312C312C303030332C303061 +:1027200030312C33383430302C302A32360D0A0018 +:1027300024504D544B3235312C33383430302A321A +:10274000370D0A0024505542582C34312C312C308E +:102750003030332C303030312C31393230302C3075 +:102760002A32330D0A0024504D544B3235312C316E +:10277000393230302A32320D0A00B56206010300C8 +:10278000F00500FF19B56206010300F00300FD1516 +:10279000B56206010300F00100FB11B562060103FA +:1027A00000F00000FA0FB56206010300F00200FC21 +:1027B00013B56206010300F00400FE17B5620601BE +:1027C00003000102010E47B5620601030001030187 +:1027D0000F49B56206010300010601124FB56206FA +:1027E0000103000112011E67B56206160800030707 +:1027F00003000000000031E5B56206080600C800CD +:1028000001000100DE6A00000000000000C20100BB +:10281000A0260108C32601080100000000E1000015 +:10282000D8260108FA2601080200000000960000E0 +:102830000E2701083027010803000000004B0000AC +:1028400044270108662701080400000080250000D5 +:102850000B3001080B3001084145525431323334FA +:1028600000002710080423022001000000000000DF +:102870008025000000C201000200000001000000ED +:102880008025000000C201000300000002000000DB +:1028900080250000004B0000050000000300000040 +:1028A00080250000004B000005000000040000002F +:1028B00040000020020000008025000000C201004E +:1028C00000000000100000008025000000C2010090 +:1028D00001000000200000008025000000C201006F +:1028E00000000000010000008025000000C201007F +:1028F00000000000080000008025000000C2010068 +:10290000000300000400000080250000004B0000D0 +:102910000000000061380108683801086D380108BE +:102920007E38010888380108933801089E3801086C +:10293000A938010855380108B23801084F38010894 +:10294000BB380108C5380108D0380108D63801085D +:10295000D9380108E9380108F03801080000000002 +:10296000F9380108FD38010803390108093901085F +:102970000C39010813390108163901081B390108FF +:10298000273901082A390108303901083739010887 +:10299000413901084B3901085439010862390108ED +:1029A0006E390108753901087B3901088839010839 +:1029B00093390108A0390108000000006B360108B6 +:1029C0006F360108A5C50008963601089B36010838 +:1029D00065C00008AF360108B83601084DC00008D0 +:1029E000D5360108DA36010809C60008093701089A +:1029F0000B30010815C000080E3701081637010812 +:102A00002DBF00082A370108393701080DBF00081B +:102A1000533701080B30010859BC0008583701082A +:102A20005C37010865BE0008A9360108783701083F +:102A3000B5C200088B37010891370108FDC40008B2 +:102A4000AC370108B4370108B1C40008C337010826 +:102A5000C83701083DBE0008EB2C0108D837010833 +:102A600055C3000806380108FA37010885BC00087C +:102A7000FF3101080B3001084DBC00080B30010884 +:102A80000D380108153801081D38010825380108DE +:102A90002C380108373801083C38010800000000D4 +:102AA0004166726F333220434C49207665727369F8 +:102AB0006F6E20322E32204D617920323820323034 +:102AC0003134202F2030333A34303A3135202D2024 +:102AD00028636C65616E666C69676874290041766D +:102AE00061696C61626C6520636F6D6D616E6473AA +:102AF0003A0D0A0025730925730D0A005379737482 +:102B0000656D20557074696D653A20256420736584 +:102B1000636F6E64732C20566F6C746167653A2026 +:102B20002564202A20302E31562028256453206227 +:102B3000617474657279290D0A004350552025642B +:102B40004D487A2C206465746563746564207365F0 +:102B50006E736F72733A200025732000414343481F +:102B6000573A202573002E2563004379636C652056 +:102B700054696D653A2025642C2049324320457202 +:102B8000726F72733A2025642C20636F6E666967DA +:102B90002073697A653A2025640D0A002025642097 +:102BA0002564000D0A5265626F6F74696E672E2E80 +:102BB0002E00536176696E672E2E2E004D7573744C +:102BC00020626520616E79206F72646572206F6685 +:102BD0002041455452313233340D0A00437572722C +:102BE000656E742061737369676E6D656E743A20EB +:102BF000004572726F723A20456E61626C652061A9 +:102C00006E6420706C756720696E20475053206693 +:102C1000697273740D0A00456E61626C65642066AA +:102C2000656174757265733A2000417661696C6103 +:102C3000626C652066656174757265733A2000493F +:102C40006E76616C69642066656174757265206E6C +:102C5000616D652E2E2E0D0A0044697361626C65EC +:102C6000642000456E61626C656420000D0A4C654D +:102C70006176696E6720434C49206D6F64652E2E26 +:102C80002E0D0A00526573657474696E6720746F47 +:102C90002064656661756C74732E2E2E004E470994 +:102CA000004F4B0900437573746F6D206D69786533 +:102CB000723A200D0A4D6F746F720954687209528E +:102CC0006F6C6C095069746368095961770D0A006B +:102CD0002325643A09002573090053616E697479EC +:102CE00020636865636B3A09007265736574006CF4 +:102CF0006F616400496E76616C6964206D69786506 +:102D00007220747970652E2E2E0D0A004C6F61644E +:102D10006564202573206D69782E2E2E0D0A0057CC +:102D2000726F6E67206E756D626572206F662061CE +:102D30007267756D656E74732C206E6565647320A3 +:102D40006964782074687220726F6C6C207069748A +:102D50006368207961770D0A004D6F746F72206E81 +:102D6000756D626572206D75737420626520626591 +:102D7000747765656E203120616E642025640D0ACC +:102D80000043757272656E74206D697865723A20C1 +:102D900025730D0A00417661696C61626C65206D76 +:102DA00069786572733A20004D69786572207365A1 +:102DB0007420746F2025730D0A0043757272656E5E +:102DC000742073657474696E67733A200D0A002568 +:102DD000732073657420746F20004552523A205658 +:102DE000616C75652061737369676E6D656E7420C3 +:102DF0006F7574206F662072616E67650D0A0045FD +:102E000052523A20556E6B6E6F776E207661726902 +:102E100061626C65206E616D650D0A0043757272AA +:102E2000656E742070726F66696C653A2025640D5A +:102E30000A0055736167653A0D0A6D6F746F7220F1 +:102E4000696E646578205B76616C75655D202D2008 +:102E500073686F77205B6F72207365745D206D6F90 +:102E6000746F722076616C75650D0A004E6F207369 +:102E7000756368206D6F746F722C207573652061A7 +:102E8000206E756D626572205B302C2025645D0DAF +:102E90000A004D6F746F722025642069732073657A +:102EA000742061742025640D0A00496E76616C6996 +:102EB00064206D6F746F722076616C75652C2031A3 +:102EC0003030302E2E323030300D0A00536574749D +:102ED000696E67206D6F746F7220256420746F2097 +:102EE00025640D0A006175782025752025750D0A69 +:102EF00000496E76616C696420466561747572651F +:102F000020696E6465783A206D757374206265205F +:102F10003C2025750D0A0043757272656E7420435E +:102F20006F6E6669673A20436F70792065766572C7 +:102F3000797468696E672062656C6F772068657266 +:102F4000652E2E2E0D0A006D697865722025730D91 +:102F50000A00636D697820256400636D6978202517 +:102F60006420302030203020300D0A006665617406 +:102F7000757265202D25730D0A0066656174757282 +:102F8000652025730D0A006D61702025730D0A0000 +:102F9000736574202573203D20000D0A456E74650D +:102FA00072696E6720434C49204D6F64652C207414 +:102FB0007970652027657869742720746F207265A1 +:102FC0007475726E2C206F72202768656C70270DE7 +:102FD0000A000D0A2320000D1B5B4B001B5B324ACD +:102FE0001B5B313B3148004552523A20556E6B6EA7 +:102FF0006F776E20636F6D6D616E642C20747279D3 +:10300000202768656C702700082008006C6F6F70BF +:1030100074696D6500656D665F61766F6964616E88 +:103020006365006D69647263006D696E63686563F2 +:103030006B006D6178636865636B00727373695FC1 +:103040006368616E6E656C00727373695F70776D33 +:103050005F70726F7669646572006D696E74687214 +:103060006F74746C65006D61787468726F74746CE1 +:1030700065006D696E636F6D6D616E64006465619E +:103080006462616E6433645F6C6F77006465616471 +:1030900062616E6433645F68696768006E65757449 +:1030A00072616C3364006465616462616E64336490 +:1030B0005F7468726F74746C65006D6F746F725FAB +:1030C00070776D5F7261746500736572766F5F70A3 +:1030D000776D5F72617465007265746172646564B6 +:1030E0005F61726D00666C6170735F7370656564BB +:1030F00000666978656477696E675F616C74686F94 +:103100006C645F6469720073657269616C5F706F93 +:1031100072745F315F7363656E6172696F007365AE +:103120007269616C5F706F72745F325F7363656E3A +:103130006172696F0073657269616C5F706F727440 +:103140005F335F7363656E6172696F007365726987 +:10315000616C5F706F72745F345F7363656E617210 +:10316000696F007265626F6F745F6368617261633B +:10317000746572006D73705F62617564726174650D +:1031800000636C695F626175647261746500677089 +:10319000735F6261756472617465006770735F70FC +:1031A0006173737468726F7567685F62617564726A +:1031B000617465006770735F70726F7669646572C1 +:1031C0000073657269616C72785F70726F766964A2 +:1031D00065720074656C656D657472795F70726F8D +:1031E00076696465720074656C656D657472795F8B +:1031F000737769746368006672736B795F696E7662 +:10320000657273696F6E00766261747363616C6579 +:1032100000766261746D617863656C6C766F6C7456 +:1032200061676500766261746D696E63656C6C766A +:103230006F6C7461676500706F7765725F6164635E +:103240005F6368616E6E656C00616C69676E5F6775 +:1032500079726F00616C69676E5F61636300616CB6 +:1032600069676E5F6D616700616C69676E5F626F51 +:103270006172645F726F6C6C00616C69676E5F6233 +:103280006F6172645F706974636800616C69676E16 +:103290005F626F6172645F796177006D61785F6111 +:1032A0006E676C655F696E636C696E6174696F6E81 +:1032B000006779726F5F6C7066006D6F726F6E5F22 +:1032C0007468726573686F6C64006779726F5F63AE +:1032D0006D70665F666163746F72006779726F5FAD +:1032E000636D70666D5F666163746F7200616C74AC +:1032F0005F686F6C645F7468726F74746C655F6E26 +:1033000065757472616C00616C745F686F6C645F8A +:10331000666173745F6368616E6765007468726F7D +:1033200074746C655F636F7272656374696F6E5FEE +:1033300076616C7565007468726F74746C655F6338 +:103340006F7272656374696F6E5F616E676C650042 +:103350007961776465616462616E64007961775F49 +:10336000636F6E74726F6C5F646972656374696FAA +:103370006E007961775F646972656374696F6E006E +:103380007472695F756E61726D65645F7365727684 +:103390006F0072635F726174650072635F6578705D +:1033A0006F007468725F6D6964007468725F65783D +:1033B000706F00726F6C6C5F70697463685F7261CC +:1033C0007465007961775F72617465007470615F24 +:1033D00072617465007470615F627265616B706FB9 +:1033E000696E74006661696C736166655F64656CC3 +:1033F0006179006661696C736166655F6F66665FBF +:1034000064656C6179006661696C736166655F749F +:1034100068726F74746C65006661696C736166656F +:103420005F6D696E5F75736563006661696C73617A +:1034300066655F6D61785F757365630067696D626E +:10344000616C5F666C616773006163635F68617282 +:103450006477617265006163635F6C70665F66616B +:1034600063746F720061636378795F64656164623D +:10347000616E64006163637A5F6465616462616E5A +:1034800064006163635F756E61726D656463616C36 +:10349000006163635F7472696D5F70697463680073 +:1034A0006163635F7472696D5F726F6C6C006261FF +:1034B000726F5F7461625F73697A65006261726FD7 +:1034C0005F6E6F6973655F6C7066006261726F5FDB +:1034D00063665F76656C006261726F5F63665F61F1 +:1034E0006C74006D61675F6465636C696E617469BB +:1034F0006F6E006770735F706F735F7000677073DB +:103500005F706F735F69006770735F706F735F6484 +:10351000006770735F706F73725F70006770735FC6 +:10352000706F73725F69006770735F706F73725F43 +:1035300064006770735F6E61765F70006770735FC1 +:103540006E61765F69006770735F6E61765F6400BD +:103550006770735F77705F726164697573006E6125 +:10356000765F636F6E74726F6C735F6865616469B8 +:103570006E67006E61765F73706565645F6D696E1E +:10358000006E61765F73706565645F6D6178006E73 +:1035900061765F736C65775F7261746500706964F2 +:1035A0005F636F6E74726F6C6C657200705F7069D0 +:1035B00074636800695F706974636800705F726F3C +:1035C0006C6C00695F726F6C6C00705F7961770082 +:1035D000695F79617700507069746368660049704B +:1035E0006974636866004470697463686600507249 +:1035F0006F6C6C660049726F6C6C660044726F6C25 +:103600006C6600507961776600497961776600449D +:1036100079617766006C6576656C5F686F72697A50 +:103620006F6E006C6576656C5F616E676C650070CF +:103630005F616C7400695F616C7400645F616C74DD +:1036400000705F6C6576656C00695F6C6576656CB3 +:1036500000645F6C6576656C00705F76656C006910 +:103660005F76656C00645F76656C006175780066F6 +:103670006561747572655F6E616D652061757866F0 +:103680006C6167206F7220626C616E6B20666F7276 +:10369000206C69737400636D697800646573696791 +:1036A0006E20637573746F6D206D69786572006448 +:1036B000656661756C747300726573657420746FF0 +:1036C0002064656661756C747320616E6420726538 +:1036D000626F6F740064756D70007072696E742033 +:1036E000636F6E666967757261626C65207365747D +:1036F00074696E677320696E2061207061737461F4 +:10370000626C6520666F726D00657869740066652D +:103710006174757265006C697374206F72202D7608 +:10372000616C206F722076616C00677073706173DA +:10373000737468726F756768007061737374687210 +:103740006F7567682067707320746F207365726986 +:10375000616C0068656C70006D6170006D61707007 +:10376000696E67206F66207263206368616E6E65A4 +:103770006C206F72646572006D69786572206E618D +:103780006D65206F72206C697374006D6F746F7259 +:10379000006765742F736574206D6F746F72206F8E +:1037A00075747075742076616C75650070726F66E3 +:1037B000696C6500696E64657820283020746F201C +:1037C00032290073617665007361766520616E64ED +:1037D000207265626F6F74006E616D653D76616C1D +:1037E0007565206F7220626C616E6B206F72202A8B +:1037F00020666F72206C6973740073686F77207332 +:10380000797374656D2073746174757300414458E5 +:103810004C333435004D505536303530004D4D4128 +:103820003834357800424D41323830004C534D33F6 +:103830003033444C48430046414B45004E6F6E6563 +:10384000004759524F00414343004241524F0053F9 +:103850004F4E415200475053004750532B4D414764 +:103860000052585F50504D005642415400494E4658 +:103870004C494748545F4143435F43414C005258D1 +:103880005F53455249414C004D4F544F525F535482 +:103890004F5000534552564F5F54494C5400534FBC +:1038A000465453455249414C004C45445F52494EA1 +:1038B00047004641494C534146450054454C454D0F +:1038C0004554525900504F5745524D4554455200AA +:1038D000564152494F0033440052585F50415241C3 +:1038E0004C4C454C5F50574D0052585F4D53500063 +:1038F000525353495F50574D00545249005155415E +:1039000044500051554144580042490047494D42F6 +:10391000414C005936004845583600464C59494EEE +:10392000475F57494E4700593400484558365800BC +:103930004F43544F5838004F43544F464C41545016 +:10394000004F43544F464C41545800414952504C4B +:10395000414E450048454C495F3132305F4343504A +:103960004D0048454C495F39305F44454700565447 +:1039700041494C340048455836480050504D5F543A +:103980004F5F534552564F004455414C434F50549E +:1039900045520053494E474C45434F505445520001 +:1039A000435553544F4D0000413801084638010833 +:1039B0004A3801085D3801084F38010855380108B8 +:1039C00059380108000000000C3001080200000016 +:1039D000881B00200000000028230000153001088B +:1039E000000000008A1B0020000000000100000011 +:1039F00023300108020000008E1C0020B0040000EB +:103A0000A40600002930010802000000901C0020DC +:103A100000000000D0070000323001080200000062 +:103A2000921C002000000000D00700003B3001087D +:103A300001000000941C00200000000012000000A3 +:103A40004830010801000000951C00200000000023 +:103A5000010000005A300108020000004C1C002048 +:103A600000000000D00700006630010802000000DE +:103A70004E1C002000000000D0070000723001083A +:103A800002000000501C002000000000D0070000D1 +:103A90007D30010802000000521C002000000000E0 +:103AA000D00700008C30010802000000541C0020E8 +:103AB00000000000D00700009C3001080200000058 +:103AC000561C002000000000D0070000A6300108AE +:103AD00002000000581C002000000000D007000079 +:103AE000BA300108020000005A1C00203200000019 +:103AF000007D0000C9300108020000005C1C0020AD +:103B000032000000F2010000D8300108000000007F +:103B1000961C00200000000001000000E5300108B4 +:103B200000000000971C002000000000640000005E +:103B3000F130010801000000981C0020FFFFFFFF8A +:103B40000100000007310108000000009C1C00205B +:103B500000000000080000001E3101080000000005 +:103B60009D1C002000000000080000003531010805 +:103B7000000000009E1C0020000000000800000063 +:103B80004C310108000000009F1C002000000000D4 +:103B9000080000006331010800000000B01C002094 +:103BA000300000007E0000007431010804000000B5 +:103BB000A01C0020B004000000C2010081310108F7 +:103BC00004000000A41C0020B004000000C201009A +:103BD0008E31010804000000A81C00200000000035 +:103BE00000C201009B31010804000000AC1C002051 +:103BF000B004000000C20100B43101080000000060 +:103C00009A1C00200000000002000000C1310108E1 +:103C1000000000008C1C00200000000003000000D9 +:103C2000D331010800000000B41C00200000000097 +:103C300002000000E631010800000000B51C002071 +:103C40000000000001000000F73101080000000042 +:103C5000B61C00200000000001000000073201082F +:103C600000000000801C00200A000000C8000000C6 +:103C70001132010800000000811C00200A00000031 +:103C8000320000002432010800000000821C0020E5 +:103C90000A00000032000000373201080000000076 +:103CA000831C0020000000000900000049320108C8 +:103CB000000000005E1C0020000000000800000062 +:103CC00054320108000000005F1C002000000000CA +:103CD000080000005E32010800000000601C0020A7 +:103CE0000000000008000000683201080300000026 +:103CF000621C00204CFFFFFF6801000079320108C0 +:103D000003000000641C00204CFFFFFF680100005E +:103D10008B32010803000000661C00204CFFFFFFEF +:103D2000680100009B32010802000000721C0020A4 +:103D30006400000084030000B132010802000000AA +:103D40006A1C00200000000000010000BA320108D7 +:103D500000000000701C0020000000008000000037 +:103D6000CA320108020000006C1C00206400000040 +:103D7000E8030000DB320108020000006E1C002096 +:103D800064000000E8030000ED32010800000000BC +:103D90006C20002001000000FA0000000733010839 +:103DA000000000006D200020000000000100000065 +:103DB0001C330108000000007020002000000000FB +:103DC0009600000036330108020000006E2000203B +:103DD00001000000840300006B34010800000000B3 +:103DE0006A2000200000000020000000503301087D +:103DF000000000006B2000200000000064000000B4 +:103E00005C33010801000000681C0020FFFFFFFF79 +:103E1000010000007233010801000000BA200020F8 +:103E2000FFFFFFFF010000008033010801000000D8 +:103E3000BB200020000000000100000092330108B8 +:103E4000000000001820002000000000FA00000020 +:103E50009A33010800000000192000200000000033 +:103E600064000000A2330108000000001A200020B6 +:103E70000000000064000000AA33010800000000F8 +:103E80001B2000200000000064000000B333010884 +:103E9000000000001C200020000000006400000062 +:103EA000C3330108000000001D20002000000000B6 +:103EB00064000000CC330108000000001E20002038 +:103EC0000000000064000000D5330108020000007B +:103ED00020200020E8030000D0070000E4330108A0 +:103EE00000000000B220002000000000C800000018 +:103EF000F333010800000000B320002000000000A0 +:103F0000C80000000634010802000000B4200020B0 +:103F1000E8030000D0070000183401080200000088 +:103F2000B620002064000000D00700002A340108F9 +:103F300002000000B820002064000000B80B000060 +:103F40003C34010800000000BC20002000000000FC +:103F5000FF0000004934010800000000691C002037 +:103F600000000000050000005634010800000000B9 +:103F70002820002000000000FA000000653401083D +:103F8000000000002A200020000000006400000063 +:103F90007434010800000000292000200000000007 +:103FA0006400000082340108000000003C20002072 +:103FB000000000000100000091340108030000002F +:103FC00026200020D4FEFFFF2C010000A0340108B1 +:103FD0000300000024200020D4FEFFFF2C0100007D +:103FE000AE340108000000002C200020000000007A +:103FF00030000000BC340108050000003020002023 +:104000000000000001000000CB34010805000000A2 +:10401000342000200000000001000000D734010817 +:104020000500000038200020000000000100000012 +:10403000E33401080300000022200020B0B9FFFF94 +:1040400050460000F334010800000000D01F00209B +:1040500000000000C8000000FD340108000000005E +:10406000DA1F002000000000C8000000073501082A +:1040700000000000E41F002000000000C800000055 +:104080001135010800000000D11F002000000000D1 +:10409000C80000001C35010800000000DB1F0020E4 +:1040A00000000000C80000002735010800000000E3 +:1040B000E51F002000000000C800000032350108A4 +:1040C00000000000D21F002000000000C800000017 +:1040D0003C35010800000000DC1F0020000000004B +:1040E000C80000004635010800000000E61F00205F +:1040F00000000000C8000000503501080200000068 +:10410000BE20002000000000D00700005E3501083E +:1041100000000000C220002000000000010000009C +:104120007335010802000000C42000200A000000CE +:10413000D00700008135010802000000C6200020E1 +:104140000A000000D00700008F35010800000000C1 +:10415000C120002000000000640000009D3501081F +:1041600000000000C81F0020000000000200000046 +:10417000AC35010800000000CD1F00200000000049 +:10418000C8000000B435010800000000D71F00205F +:1041900000000000C8000000833201080000000099 +:1041A000E11F002000000000C8000000BC3501082D +:1041B00000000000CC1F002000000000C80000002C +:1041C000C335010800000000D61F002000000000D9 +:1041D000C80000007232010800000000E01F00204B +:1041E00000000000C8000000CA35010800000000FF +:1041F000CE1F002000000000C8000000D0350108DC +:1042000000000000D81F002000000000C8000000CF +:104210009532010800000000E21F002000000000AD +:10422000C8000000D635010805000000F01F00207E +:104230000000000064000000DE35010805000000F9 +:10424000FC1F00200000000064000000E6350108AB +:1042500005000000082000200000000064000000AD +:10426000EE35010805000000EC1F002000000000F2 +:1042700064000000F535010805000000F81F00206B +:104280000000000064000000FC350108050000008B +:104290000420002000000000640000000336010834 +:1042A00005000000F41F0020000000006400000072 +:1042B0000936010805000000002000200000000071 +:1042C000640000000F360108050000000C200020EB +:1042D0000000000064000000153601080500000021 +:1042E00014200020000000000A000000233601080E +:1042F0000500000010200020000000000A0000005F +:104300002F36010800000000CF1F00200000000031 +:10431000C80000003536010800000000D91F002049 +:1043200000000000C80000003B360108000000004B +:10433000E31F002000000000C80000004136010813 +:1043400000000000D31F002000000000C800000093 +:104350004936010800000000DD1F002000000000B9 +:10436000C80000005136010800000000E71F0020CF +:1043700000000000C80000005936010800000000DD +:10438000D51F002000000000C80000005F360108B3 +:1043900000000000DF1F002000000000C800000037 +:1043A0006536010800000000E91F00200000000041 +:1043B000C8000000524F4C4C3B50495443483B59B5 +:1043C00041573B414C543B506F733B506F73523BD2 +:1043D0004E6176523B4C4556454C3B4D41473B5612 +:1043E000454C3B0041524D3B00414E474C453B0044 +:1043F000484F52495A4F4E3B004241524F3B0056A4 +:104400004152494F3B004D41473B004845414446DE +:104410005245453B004845414441444A3B004341E5 +:104420004D535441423B0043414D545249473B0098 +:1044300047505320484F4D453B0047505320484F6D +:104440004C443B0050415353544852553B00424565 +:10445000455045523B004C45444D41583B004C456E +:10446000444C4F573B004C4C49474854533B004346 +:10447000414C49423B00474F5645524E4F523B003C +:104480004F53442053573B0054454C454D455452DF +:10449000593B004155544F54554E453B007465649B +:1044A000666D6A69736C67000000004B000000CB0A +:1044B00061636F7366000000706F77660000000034 +:1044C00073717274660000000000000000C0153FA8 +:1044D00000000000DCCFD1350000803F0000C03F6D +:1044E000000FC93F000F494000CB9640000FC94064 +:1044F0000053FB4000CB164100ED2F41000F494116 +:104500000031624100537B41003A8A4100CB964121 +:10451000005CA34100EDAF41007EBC41000FC941EA +:1045200000A0D5410031E24100C2EE410053FB4101 +:1045300000F20342003A0A420083104200CB1642C6 +:1045400000141D42005C234200A5294200ED2F42C9 +:1045500000363642007E3C4200C74242000F4942CC +:10456000A2000000F9000000830000006E000000BF +:104570004E0000004400000015000000290000006B +:10458000FC0000002700000057000000D1000000E0 +:10459000F500000034000000DD000000C000000055 +:1045A000DB000000620000009500000099000000A0 +:1045B0003C000000430000009000000041000000AB +:1045C000FE0000005100000063000000AB0000008E +:1045D000DE000000BB000000C5000000610000001C +:1045E000B7000000240000006E0000003A00000048 +:1045F000420000004D000000D2000000E00000007A +:1046000006000000490000002E000000EA00000043 +:1046100009000000D1000000920000001C00000012 +:10462000FE0000001D000000EB0000001C00000068 +:10463000B100000029000000A70000003E000000BB +:10464000E80000008200000035000000F5000000D6 +:104650002E000000BB0000004400000084000000A9 +:10466000E90000009C00000070000000260000002F +:10467000B40000005F0000007E0000004100000068 +:104680003900000091000000D60000003900000051 +:10469000830000005300000039000000F400000017 +:1046A0009C000000840000005F0000008B00000000 +:1046B000BD000000F9000000280000003B000000E1 +:1046C0001F000000F800000097000000FF0000003D +:1046D000DE00000005000000980000000F00000050 +:1046E000EF0000002F000000110000008B00000010 +:1046F0005A0000000A0000006D0000001F000000CA +:104700006D000000360000007E000000CF000000B9 +:1047100027000000CB00000009000000B7000000E7 +:104720004F000000460000003F000000660000004F +:104730009E0000005F000000EA0000002D00000065 +:104740007500000027000000BA000000C70000004C +:10475000EB000000E5000000F10000007B0000001D +:104760003D0000000700000039000000F7000000D5 +:104770008A0000005200000092000000EA000000E1 +:104780006B000000FB0000005F000000B1000000B3 +:104790001F0000008D0000005D0000000800000008 +:1047A000560000000300000030000000460000003A +:1047B000FC0000007B0000006B000000AB0000006C +:1047C000F0000000CF000000BC000000200000004E +:1047D0009A000000F4000000360000001D000000F8 +:1047E000A9000000E300000091000000610000004B +:1047F0005E000000E60000001B0000000800000052 +:104800006500000099000000850000005F000000C6 +:1048100014000000A000000068000000400000003C +:104820008D000000FF000000D800000080000000A4 +:104830004D00000073000000270000003100000060 +:1048400006000000060000001500000056000000F1 +:10485000CA00000073000000A8000000C9000000AA +:1048600060000000E20000007B000000C0000000CB +:104870008C0000006B000000040000000700000036 +:10488000090000000000C93F0000F0390000DA37DD +:104890000000A2330000842E0000502B0000C2272D +:1048A0000000D0220000C41F0000C61B00004417F7 +:1048B000000000000000304300000000000030C392 +:1048C0006937AC3168212233B40F14336821A23325 +:1048D0003863ED3EDA0F493F5E987B3FDA0FC93F00 +:1048E00000202020202020202020282828282820C0 +:1048F00020202020202020202020202020202020B8 +:10490000208810101010101010101010101010101F +:10491000100404040404040404040410101010100F +:1049200010104141414141410101010101010101D9 +:10493000010101010101010101010101101010102B +:1049400010104242424242420202020202020202AB +:1049500002020202020202020202020210101010FF +:104960002000000000000000000000000000000027 +:104970000000000000000000000000000000000037 +:104980000000000000000000000000000000000027 +:104990000000000000000000000000000000000017 +:1049A0000000000000000000000000000000000007 +:1049B00000000000000000000000000000000000F7 +:1049C00000000000000000000000000000000000E7 +:1049D00000000000000000000000000000000000D7 +:1049E0000000000043000000B8010020F8B500BF3F +:1049F000F8BC08BC9E467047F8B500BFF8BC08BCC0 +:044A00009E46704717 +:084A04004D1D010835010008F9 +:044A0C00110100088C +:104A1000030300000000803F0000803F0000803F53 +:104A20000301000101000000D17300080000803F75 +:104A30000000000000000000DC05DC05DC05DC05F2 +:104A4000DC05DC05DC05DC050000803F0101000021 +:104A50000000000000000000000000000100000055 +:104A60000000000000000000020000000000000044 +:104A70000000000003000000000000000000000033 +:104A800000000000E44301080000000001000000F5 +:104A9000E94301080100000002000000F0430108A2 +:104AA0000200000003000000F943010803000000B9 +:104AB00004000000FF43010804000000050000009E +:104AC0000644010805000000060000000B44010830 +:104AD0000600000007000000154401080700000060 +:104AE000080000001E440108080000000900000042 +:104AF00027440108090000000A00000030440108B2 +:104B00000A0000000B0000003A4401080B000000FE +:104B10000C000000444401080C0000000D000000DF +:104B20004E4401080D0000000E000000564401082C +:104B30000E0000000F0000005E4401080F0000009E +:104B40001000000066440108100000001100000081 +:104B50006F440108110000001200000076440108B3 +:104B60001200000013000000804401081300000040 +:104B70001400000088440108140000001500000023 +:104B8000934401081500000016000000000000001A +:104B9000FF0000000000000000000000010203040C +:104BA0000607080900127A0000A24A040204060857 +:104BB00000000000010203040102030406070809C3 +:104BC00001000000E048010800000000A4040020EB +:104BD0000C0500207405002000000000000000000B +:104BE00000000000000000000000000000000000C5 +:104BF000000000000000000000000000E44901087F +:104C000000000000000000000000000000000000A4 +:104C10000000000000000000000000000000000094 +:104C20000000000000000000000000000000000084 +:104C30000000000000000000000000000000000074 +:104C40000000000000000000000000000000000064 +:104C50000000000000000000000000000000000054 +:104C60000000000000000000000000000000000044 +:104C700001000000000000000E33CDAB34126DE6E1 +:104C8000ECDE05000B00000000000000000000004A +:104C90000000000000000000000000000000000014 +:104CA0000000000000000000000000000000000004 +:104CB00000000000000000000000000000000000F4 +:104CC00000000000000000000000000000000000E4 +:104CD00000000000000000000000000000000000D4 +:104CE00000000000000000000000000000000000C4 +:104CF00000000000000000000000000000000000B4 +:104D000000000000000000000000000000000000A3 +:104D10000000000000000000000000000000000093 +:104D20000000000000000000000000000000000083 +:104D30000000000000000000000000000000000073 +:104D40000000000000000000000000000000000063 +:104D50000000000000000000000000000000000053 +:104D60000000000000000000000000000000000043 +:104D70000000000000000000000000000000000033 +:104D80000000000000000000000000000000000023 +:104D90000000000000000000000000000000000013 +:104DA0000000000000000000000000000000000003 +:104DB00000000000000000000000000000000000F3 +:104DC00000000000000000000000000000000000E3 +:104DD00000000000000000000000000000000000D3 +:104DE00000000000000000000000000000000000C3 +:104DF00000000000000000000000000000000000B3 +:104E000000000000000000000000000000000000A2 +:104E10000000000000000000000000000000000092 +:104E20000000000000000000000000000000000082 +:104E30000000000000000000000000000000000072 +:104E40000000000000000000000000000000000062 +:104E50000000000000000000000000000000000052 +:104E60000000000000000000000000000000000042 +:104E70000000000000000000000000000000000032 +:104E80000000000000000000000000000000000022 +:104E90000000000000000000000000000000000012 +:104EA0000000000000000000000000000000000002 +:104EB00000000000000000000000000000000000F2 +:104EC00000000000000000000000000000000000E2 +:104ED00000000000000000000000000000000000D2 +:104EE00000000000000000000000000000000000C2 +:104EF00000000000000000000000000000000000B2 +:104F000000000000000000000000000000000000A1 +:104F10000000000000000000000000000000000091 +:104F20000000000000000000000000000000000081 +:104F30000000000000000000000000000000000071 +:104F40000000000000000000000000000000000061 +:104F50000000000000000000000000000000000051 +:104F60000000000000000000000000000000000041 +:104F70000000000000000000000000000000000031 +:104F80000000000000000000000000000000000021 +:104F90000000000000000000000000000000000011 +:104FA0000000000000000000000000000000000001 +:104FB00000000000000000000000000000000000F1 +:104FC00000000000000000000000000000000000E1 +:104FD00000000000000000000000000000000000D1 +:104FE00000000000000000000000000000000000C1 +:044FF000B8010020E4 :0400000508000000EF :00000001FF diff --git a/obj/cleanflight_OLIMEXINO.hex b/obj/cleanflight_OLIMEXINO.hex index 3651203d29..d690cbda82 100644 --- a/obj/cleanflight_OLIMEXINO.hex +++ b/obj/cleanflight_OLIMEXINO.hex @@ -1,8 +1,8 @@ :020000040800F2 -:1000000000500020B9100008691100088144000860 +:1000000000500020B9100008691100089144000850 :10001000691100086911000869110008000000005A :10002000000000000000000000000000691100084E -:1000300069110008000000006911000871520008F1 +:10003000691100080000000069110008155300084C :1000400069110008691100086911000869110008A8 :100050006911000869110008691100086911000898 :100060006911000869110008691100086911000888 @@ -18,9 +18,9 @@ :0C01000000000000000000005FF808F1A3 :1001100010B5054C237833B9044B13B10448AFF341 :1001200000800123237010BDD405002000000000D2 -:10013000101A010808B5064B1BB106480649AFF373 +:100130003820010808B5064B1BB106480649AFF345 :1001400000800648036813B1054B03B1984708BD0A -:1001500000000000101A0108D8050020D405002076 +:100150000000000038200108D8050020D405002048 :100160000000000081F0004102E000BF83F0004386 :1001700030B54FEA41044FEA430594EA050F08BF42 :1001800090EA020F1FBF54EA000C55EA020C7FEA06 @@ -270,12 +270,12 @@ :1010C0008A4200F01F80002100F004B81A4B5B58E0 :1010D0004350043119481A4B42189A42FFF4F6AFB4 :1010E000184A00F003B8002342F8043B164B9A421A -:1010F000FFF4F9AF0AF076FA0CF09AFE03F0BAF9B1 +:1010F000FFF4F9AF0AF080FD0DF0A4F903F0C2F996 :10110000FFF7FEBF114E124830601248016821F00F :1011100070610160410201600F4C182020600F498E :101120000F4808600F48D0F800D040680047000022 -:10113000F04F0020EFBEADDE341A010800000020A1 -:10114000D4050020D40500203820002018100240CB +:10113000F04F0020EFBEADDE5C2001080000002073 +:10114000D4050020D4050020E02000201810024023 :101150000900000004000140140C0140000C014093 :101160004434434400F0FF1FFFF7FEBF064B1B78DB :1011700013B1012B03D070474FF4006201E04FF42C @@ -288,18 +288,18 @@ :1011E00000209DF8013043EA022323809DF802206D :1011F0009DF8033043EA022363809DF804209DF8A4 :10120000053043EA0223A38002B010BD07B52320B6 -:1012100004F061F86820752101220DF1070300F048 +:1012100004F0B3F86820752101220DF1070300F0F6 :101220004FFC28B19DF80700B0F1680358425841BF :1012300003B05DF804FB000007B54FF40053ADF8B0 :10124000043002238DF8073004238DF806301C4B40 :101250001C4A1B68934201D11B4803E01B4A93427E :1012600003D11B4801A900F02FFD6B2180226820CB -:1012700000F01CFC052004F02EF819210022682043 +:1012700000F01CFC052004F080F8192100226820F1 :1012800000F014FC6B210322682000F00FFC3721D2 :101290000222682000F00AFC0E4B1A211A786820FE :1012A00000F004FC1B211822682000F0FFFB1C2129 :1012B0001022682000F0FAFB03B05DF804FB00BFC9 -:1012C0008001002000127A00000C0140001BB700D2 +:1012C0008401002000127A00000C0140001BB700CE :1012D0000010014000000020F0B585B00546FFF782 :1012E00095FF074600283ED0062102AB68200A463B :1012F00000F0E6FB9DF80B309DF80D6003F0010354 @@ -307,7 +307,7 @@ :1013100003F001031E4306D0012E01D1002317E084 :10132000022E0CD113E00DF1070368200C210122DD :1013300000F0C6FB9DF8073013F00F0303D1052022 -:1013400004F03CF805E0042B01D1267001E00123F4 +:1013400004F08EF805E0042B01D1267001E00123A2 :101350002370074B2B60074B6B602378002B14BF67 :101360006E236F232B72384605B0F0BDF0050020C8 :101370006D1100089111000838B505460C46FFF7BD @@ -317,72 +317,72 @@ :1013B00002220AE0002208E0012206E0032204E003 :1013C000042202E0052200E006221A7038BD00BFA8 :1013D00039120008CF11000890C1793D00000020AB -:1013E000044B03EB40004278034B33F8120080B209 -:1013F000704700BFB2140020AC140020F0B5404E7E -:10140000404C04234049337023780D683F495A1CEF -:10141000D2B28D4291B07370227004D10521023393 -:10142000B170F2702370037823B133712378737134 -:101430000133237036480BF0A3F8364B0025059393 -:10144000354B33480693237805A9022B089334BF04 -:101450002B4680230A934FF480730B934FF48063E1 -:101460000C9320230D934FF400530E930795099589 -:101470000F950BF0FDF8264801210BF024F9237895 -:101480002648012B94BF002201228DF8042001225E -:101490008DF8052069464FF460220095029203956D -:1014A0008DF810300AF018FA23786F1CEDB2AB42B9 -:1014B0001A4807D916F81510FAB203230AF05DFA94 -:1014C0003D46F1E701210AF034FA144801210AF0FF -:1014D00027FA12480AF036FA10480AF038FA0028BB -:1014E000FAD10E480AF037FA0C480AF039FA002807 -:1014F000FAD10A4801210AF037FA11B0F0BD00BF55 -:10150000B2140020F105002080010020001BB7006C -:10151000080002404C240140AC140020002401408B +:1013E000044B00EB400018444278034B33F81200E2 +:1013F00080B270474815002042150020F0B5414CDE +:10140000092291B00646002120460DF043F804233E +:1014100023703D4B01251A683C4BA5709A4204D1BC +:10142000052325716571E370022533782BB1012303 +:10143000EA18E571A3712372D5B235480BF0AAFB07 +:10144000344B00260593344B012D06930CBF3346D5 +:1014500080230A934FF480730B934FF480630C93B3 +:1014600020230D932A484FF4005305A90E930796A5 +:10147000089509960F960BF005FC254801210BF005 +:101480002CFC012D94BF002301238DF8043001278B +:101490004FF460232148694600968DF80570029349 +:1014A00003968DF810500AF021FD3A46A3199B7857 +:1014B0003BB1551CEDB21948A15D03230AF067FD4D +:1014C0002A460336092EF1D1144801210AF03BFDCA +:1014D000124801210AF02EFD10480AF03DFD0F4888 +:1014E0000AF03FFD0028FAD10C480AF03EFD0B48F7 +:1014F0000AF040FD0028FAD1084801210AF03EFD1B +:1015000011B0F0BD4815002084010020001BB70079 +:10151000080002404C2401404215002000240140F4 :101520002DE9F047974C2068B0F814C01FFA8CFCE6 :101530005FFA8CF3DD0736D50388012123F40063BD -:101540001B041B0C03800AF0F9FF8F4B00221A705A +:101540001B041B0C03800BF003FB8F4B00221A7053 :101550008E4A1D4612788E4BC2B18E4A117819B947 :101560008D490978FF2911D1012111708B4A127818 :10157000022A05D12268118889B241F400611180E4 -:101580001978206801220AF0F3FF21E11978206818 -:1015900000220AF0EDFF804B1B78FF2B00F0188132 +:101580001978206801220BF0FDFA21E11978206812 +:1015900000220BF0F7FA804B1B78FF2B00F018812C :1015A000FF232B7014E103F0020202F0FF01002A76 :1015B0003BD0BFF35F8F794B1A78012A16D1734A5B -:1015C00012789AB1734A127882B100210AF0B6FFFC -:1015D000BFF35F8F20680121038B0AF0A3FF704BDC +:1015C00012789AB1734A127882B100210BF0C0FAF6 +:1015D000BFF35F8F20680121038B0BF0ADFA704BD6 :1015E00001221A7020684FF48061EFE0028BBFF394 :1015F0005F8F1A78022A09D1644A127832B1654A9B -:1016000012781AB100210AF099FFDBE01B78032B56 +:1016000012781AB100210BF0A3FADBE01B78032B50 :1016100007D15E4B1B7823B15E4B1B78002B40F04B :10162000D2804FF480610122D0E003F0040505F080 :10163000FF08002D67D0554BDFF864811A7801262A :1016400088F80060534B002A47D01A78002A44D00B -:10165000524B4D4D1B78534F022B23D90AF06EFF8E +:10165000524B4D4D1B78534F022B23D90BF078FA88 :101660002B7820689A194FFA83FAD7F800902A70DD -:101670000AF07BFF314609F80A0020680AF052FFA1 +:101670000BF085FA314609F80A0020680BF05CFA95 :101680002B7820689A193F682A7088F800605DB24C -:101690000AF06BFF4FF480617855324620680AF0FB -:1016A00059FF2BE031460AF03DFF2B7820685A1C89 -:1016B0003E684FFA83F82A700AF057FF2B7806F835 -:1016C00008005A1C20683E682A705FB20AF04DFF7D +:101690000BF075FA4FF480617855324620680BF0F4 +:1016A00063FA2BE031460BF047FA2B7820685A1C7E +:1016B0003E684FFA83F82A700BF061FA2B7806F82F +:1016C00008005A1C20683E682A705FB20BF057FA77 :1016D0002B78F05501332B7010E01B78012113B9E2 -:1016E000314B1B782BB10AF01DFF274B1A780132C2 -:1016F00003E00AF00BFF274B01221A7022681388BF +:1016E000314B1B782BB10BF027FA274B1A780132BC +:1016F00003E00BF015FA274B01221A7022681388B9 :10170000D805FCD464E003F0400303F0FF071E4D4E :10171000224EFBB1234B1F682B785A1C4FFA83F9DA -:101720002A700AF022FF95F9003007F80900327894 -:1017300003339A4205D120684FF4806142460AF093 -:1017400009FF2B7831785AB2914241D10E4A0133C8 +:101720002A700BF02CFA95F9003007F8090032788E +:1017300003339A4205D120684FF4806142460BF092 +:1017400013FA2B7831785AB2914241D10E4A0133C3 :1017500013703DE01CF0800F3AD02A7853B2591C28 -:1017600026D01249013209682A70C95C0AF0FBFED2 +:1017600026D01249013209682A70C95C0BF005FACB :10177000327895F900309A422AD120684FF480617E :101780003A4623E0080600200C060020050600204B :101790000D060020F4050020F6050020F7050020C6 :1017A000FD050020F8050020F505002000060020BA -:1017B000134B2F7019780AF0D6FE124B1B780BB919 -:1017C00033782BB920684FF4806100220AF0C2FE02 +:1017B000134B2F7019780BF0E0F9124B1B780BB913 +:1017C00033782BB920684FF4806100220BF0CCF9FC :1017D0000D4B0E4A1B7892F9002001339A420DD12D :1017E0000B4B00221A700B4B1B7823B120684FF46F -:1017F00040710AF0AFFE084B00221A70BDE8F08776 +:1017F00040710BF0B9F9084B00221A70BDE8F08770 :10180000F605002005060020F70500200C06002044 :10181000F4050020FD05002004060020FFF780BE2F :10182000FFF77EBE2DE9F041484C86B04FF440658D @@ -390,28 +390,28 @@ :101840008DF806308DF8077000F03EFA142320461C :1018500002A9ADF80850C6F800808DF80B708DF81D :101860000A3000F031FA25610825384CA3685B0581 -:1018700003D40A2003F024FDF7E74FF480670A2021 -:10188000676103F01DFD013D27610A2003F018FD8B +:1018700003D40A2003F076FDF7E74FF480670A20CF +:10188000676103F06FFD013D27610A2003F06AFDE7 :1018900015F0FF05E9D14FF40068C4F814800A2060 -:1018A00003F00EFD67610A2003F00AFD27610A209C -:1018B00003F006FD4FF44063C4F81080ADF8083023 +:1018A00003F060FD67610A2003F05CFD27610A20F8 +:1018B00003F058FD4FF44063C4F81080ADF80830D1 :1018C000022302A98DF80B3020461C238DF80A3024 -:1018D00000F0FAF930680AF077FD02A80AF0FCFD82 -:1018E0002A4630684FF440710AF034FE4BF6FF731D +:1018D00000F0FAF930680BF081F802A80BF006F975 +:1018E0002A4630684FF440710BF03EF94BF6FF7317 :1018F000ADF80E304FF48043ADF81430154B30681E -:1019000001210293ADF80C500AF0F4FD02A93068F1 -:101910000AF074FD4FF4A0600AF078F822238DF8E5 +:1019000001210293ADF80C500BF0FEF802A93068EB +:101910000BF07EF84FF4A0600AF082FB22238DF8D2 :101920000030684601238DF803308DF801508DF8A2 -:1019300002500AF075F8212368468DF800308DF8C2 -:1019400001500AF06DF806B0BDE8F081000C0140CE +:1019300002500AF07FFB212368468DF800308DF8B5 +:1019400001500AF077FB06B0BDE8F081000C0140C1 :1019500008060020801A060037B5224C2068838ACA :101960009BB20193019B13F4706F02D01E4B0122B6 :101970001A70019B13F4E06F28D04FF480610022AD -:10198000038B0AF0E7FD019B98051FD420680388AC +:10198000038B0BF0F1F8019B98051FD420680388A6 :1019900099051BD4058805F48075ADB265B103883F -:1019A000DA05FCD401210AF0BDFD206803889B05FF -:1019B000FCD4FFF737FF09E001210AF0B3FD094B22 -:1019C0004FF4407118682A460AF0C4FD2268938AD1 +:1019A000DA05FCD401210BF0C7F8206803889B05F9 +:1019B000FCD4FFF737FF09E001210BF0BDF8094B1C +:1019C0004FF4407118682A460BF0CEF82268938ACB :1019D00023F470631B041B0C9382044B00221A70C7 :1019E00003B030BD08060020FC05002004060020DE :1019F000FFF7B2BFFFF7B0BF70B54000204CC0B2D8 @@ -419,8 +419,8 @@ :101A100021701F4C23601F4C23601F4B1F4C1A70FA :101A20001F4A204B1070206819708188164611F4E7 :101A3000007F1D460ED10388DA0505D403889B0577 -:101A4000FCD401210AF062FD20684FF440710122AC -:101A50000AF080FD47F23053327812B1013BFBD1DE +:101A4000FCD401210BF06CF820684FF440710122A6 +:101A50000BF08AF847F23053327812B1013BFBD1D8 :101A600000E04BB9104B20681A88013292B21A80FC :101A7000FFF7D8FE002070BD287880F0010070BD0F :101A80000D060020F605002005060020F5050020C3 @@ -431,8 +431,8 @@ :101AD000204800210170012020701F4C23601F4C02 :101AE00023601F4B1F4C1A701F4A204B1070206838 :101AF00019708188164611F4007F1D460ED10388A7 -:101B0000DA0505D403889B05FCD401210AF0FEFC0C -:101B100020684FF4407101220AF01CFD47F2305357 +:101B0000DA0505D403889B05FCD401210BF008F805 +:101B100020684FF4407101220BF026F847F2305351 :101B2000327812B1013BFBD100E04BB9104B206879 :101B30001A88013292B21A80FFF774FE002070BD3D :101B4000287880F0010070BD0D060020F605002009 @@ -440,22 +440,22 @@ :101B6000F70500200806002004060020FC050020E0 :101B7000F2050020014B188880B27047F205002062 :101B8000F8B5134B04469B890D461646EEB115B1C8 -:101B90002F78013500E0FF270D48022109F096FE5D -:101BA0000028F9D00A48394609F08BFE084801217F -:101BB00009F08CFE0028F9D0054809F084FEC0B277 +:101B90002F78013500E0FF270D4802210AF0A0F957 +:101BA0000028F9D00A4839460AF095F90848012179 +:101BB0000AF096F90028F9D005480AF08EF9C0B26B :101BC0000CB120700134013EE0E70120F8BD00BFF8 :101BD000003800402DE9F0474FF4804088B00121E3 -:101BE0000AF0C6FB4FF4804001210AF0D9FB344DC6 +:101BE0000AF0D0FE4FF4804001210AF0E3FE344DAC :101BF00018238DF802304FF42043ADF8003028460A :101C0000032369464FF004082E4F8DF8033000F08F :101C10005BF84FF4804328466946ADF800304FF436 :101C200080564FF0100A8DF8028000F04DF869469A :101C30002846ADF800608DF802A000F045F838465F -:101C400009F0E2FD4FF48273ADF80E304FF40073EB +:101C40000AF0ECF84FF48273ADF80E304FF40073E5 :101C5000ADF8163007230024ADF81C304FF0010911 :101C60000223384603A9ADF81230ADF80C40ADF8A8 -:101C70001040ADF81A40ADF81490ADF818A009F076 -:101C8000F5FD3846494609F010FE9F238DF80430D3 +:101C70001040ADF81A40ADF81490ADF818A00AF075 +:101C8000FFF8384649460AF01AF99F238DF80430C8 :101C90008DF805408DF806408DF8074002A86E616A :101CA0000DEB08014246FFF76BFF2E619DF809001E :101CB000B0F1EF035842584108B0BDE8F08700BFCB @@ -483,7 +483,7 @@ :101E100000F0E2F801E000F0F5F808F101080AE04E :101E2000052B08D1074BF9B203EB0010A289238AD6 :101E300000F0FEF8013702351C2D91D1BDE8F88382 -:101E4000F8EF000874F00008074BA1F57A7153F819 +:101E40000CF6000888F60008074BA1F57A7153F8E4 :101E500020304FF47A701A689B884B4393FBF0F361 :101E60009BB21380704700BF10060020024B53F84E :101E700020301B6819807047100600202DE9F04FB4 @@ -491,17 +491,17 @@ :101E90002A704643724620684946019300F072FF5B :101EA000A2686068ADF808204FF0020A182202A963 :101EB0008DF80A208DF80BA0FFF706FF02A8256811 -:101EC00094F80CB009F0A1FF7022019B354FADF8DA +:101EC00094F80CB00AF0ABFA7022019B354FADF8D4 :101ED00008200122ADF80A20ADF80E3000224FF4A0 :101EE000807307EB0608ADF80C20ADF810A0ADF834 :101EF0001430BBF10C0F2BD8DFE80BF0072A2A2A8D -:101F0000102A2A2A192A2A2A2200284602A909F078 -:101F100075FE2846082109F0ADFF19E0284602A900 -:101F200009F0B0FE2846082109F0ACFF10E0284671 -:101F300002A909F0EBFE2846082109F0ADFF07E0F1 -:101F4000284602A909F024FF2846082109F0ACFF21 -:101F5000A37B1BB12068012109F075FF20680121D6 -:101F600009F065FF237B0C2B14D8DFE803F007137F +:101F0000102A2A2A192A2A2A2200284602A90AF077 +:101F10007FF9284608210AF0B7FA19E0284602A9F5 +:101F20000AF0BAF9284608210AF0B6FA10E0284665 +:101F300002A90AF0F5F9284608210AF0B7FA07E0E5 +:101F4000284602A90AF02EFA284608210AF0B6FA15 +:101F5000A37B1BB1206801210AF07FFA20680121D0 +:101F60000AF06FFA237B0C2B14D8DFE803F0071379 :101F700013130A1313130D131313100023683433B0 :101F800007E02368383304E023683C3301E023682A :101F90004033BB514046A8F8049007B0BDE8F08F2D @@ -520,15 +520,15 @@ :102060002CB95A8001221A700068022206E05C88AE :102070009A80121B1A8100221A700068BDE8104075 :1020800000F090B8F00600207FB5044601A80D4688 -:10209000164609F0C4FE0123ADF80830204600239F +:1020900016460AF0CEF90123ADF808302046002399 :1020A00001A9ADF80450ADF80660ADF80A30ADF8FE -:1020B0000C3009F035FF04B070BD0000F7B5144DC9 -:1020C000144F060174193846002110220BF0D8FE77 +:1020B0000C300AF03FFA04B070BD0000F7B5144DC3 +:1020C000144F060174193846002110220CF0E2F971 :1020D000A368E27B6068ADF8043001A902238DF8A3 :1020E00007308DF80620FC60FFF7EEFD7059217B6C :1020F0000022FFF7C9FF20464FF6FF71012200F0D2 :1021000063FE20460021044A00F01CFE03B0F0BD2F -:1021100074F00008F006002055200008014B1889D3 +:1021100088F60008F006002055200008014B1889B9 :10212000704700BFF00600200E4A0F481388118048 :10213000C91A038089B240F68C2399420B4B1A7856 :1021400007D9032A03D90A4A1178013111700022F4 @@ -537,10 +537,10 @@ :10217000A107002006070020034B1878034B1B78AB :10218000C01A18BF01207047A107002004070020D3 :10219000024B1A78024B1A70704700BFA10700204B -:1021A000040700207FB5044601A80D46164609F035 -:1021B00036FE0123ADF808300023ADF80A30204682 +:1021A000040700207FB5044601A80D4616460AF034 +:1021B00040F90123ADF808300023ADF80A3020467D :1021C000032301A9ADF80450ADF80660ADF80C305A -:1021D00009F0A6FE04B070BD10B50F4B03EB001064 +:1021D0000AF0B0F904B070BD10B50F4B03EB00105E :1021E0008278C36832B9012282708180197B1868B5 :1021F00002220CE08288C1804478891A074A89B299 :1022000022F814100022018182701868197BBDE841 @@ -551,18 +551,18 @@ :102250008DF80620FFF738FD58F80700217B002293 :10226000FFF7A0FF204632464FF6FF7100F0ACFDAD :1022700020462946044A00F065FD02B0BDE8F08121 -:1022800074F0000820070020D9210008F7B5134E8C +:1022800088F6000820070020D9210008F7B5134E72 :102290000701134BBC1900251D70DC60A368E27BAD :1022A0006068ADF8043001A902238DF807308DF87D :1022B0000620FFF709FDB859217B2A46FFF772FF78 :1022C00020464FF6FF71012200F07EFD2046294690 -:1022D000044A00F037FD03B0F0BD00BF74F0000801 +:1022D000044A00F037FD03B0F0BD00BF88F60008E7 :1022E0002007002029210008014B33F81000704717 :1022F0000607002041717047426A806A131A5842EB -:10230000584170477FB5044601A80D46164609F0AE -:1023100086FD0123ADF808302046002301A9ADF861 -:102320000450ADF80660ADF80A30ADF80C3009F095 -:10233000F7FD04B070BD437913F0010307D00369C2 +:10230000584170477FB5044601A80D4616460AF0AD +:1023100090F80123ADF808302046002301A9ADF85C +:102320000450ADF80660ADF80A30ADF80C300AF094 +:1023300001F904B070BD437913F0010307D00369BC :10234000C169026A013B881A1840C0B2704718463A :102350007047437910B513F0010304460DD0FFF721 :10236000EAFF58B1226A6369985CE3680132B2FB04 @@ -583,14 +583,14 @@ :10245000A5626562A4F84252A4F844528DF8063091 :10246000C4F808900223A7718DF80730FFF72CFC01 :10247000206BFFF7A3FF41462046FFF78FFF322076 -:1024800002F029FF1A4BD4F834811B681D46B5FBB6 +:1024800002F07BFF1A4BD4F834811B681D46B5FB64 :10249000F9F1B1F5803F03D3012DF8D96D08F6E7C6 :1024A000144A4046B3FBF2F289B2D2B200F08CFC7F :1024B00040463146104A00F045FC256B012F14BF01 :1024C000022200222868297BFFF71CFF284631469C :1024D0000A4A00F037FC204603B0BDE8F08300BF95 -:1024E000B8140020B4F00008D4F0000844F000084C -:1024F0008401002040420F0015270008A125000894 +:1024E00054150020C8F60008E8F6000858F6000861 +:1024F0008801002040420F0015270008A125000890 :1025000003460A4690F84602D96A9B79FFF768BFEE :1025100010B590F83C220446C2B9836A416A9942D8 :1025200028D08069591CA162C05C2369C0B299425D @@ -603,7 +603,7 @@ :10259000404201332143A0F84012DBB2F3E710BD03 :1025A0002B4B10B54FF4127404FB00346379DB0736 :1025B0004DD594F838321BB3236B0021186809F00D -:1025C0007DFC94F83C3223B1B4F842320133A4F8D4 +:1025C00087FF94F83C3223B1B4F842320133A4F8C7 :1025D0004232A279236B012A1868197B0CBF0222B0 :1025E0000022FFF78FFE012384F83B32002384F89A :1025F000393284F83A3284F83832A4F8403210BDC7 @@ -612,7 +612,7 @@ :10262000012184F83B128A421868197B0CBF0222F0 :10263000002208E0002184F83B12012A1868197B67 :1026400014BF02220022BDE81040FFF75BBE10BDA0 -:10265000B8140020012280F8382290F83B22002391 +:1026500054150020012280F8382290F83B220023F4 :10266000012A80F839320BD1827980F83B32036B32 :10267000012A1868197B14BF02220022FFF742BE0C :102680007047427908B50346D0071CD5B3F840021D @@ -626,14 +626,14 @@ :102700002046FFF7BEFF2046BDE81040FFF7A2BFFE :1027100010BD0000064B10B54FF4127404FB0034DA :102720002046FFF7F5FE2046BDE81040FFF7CCBF7E -:10273000B8140020436B13B190F844007047826ACC +:1027300054150020436B13B190F844007047826A2F :10274000436AD31A5842584170471FB583680093B3 :102750000023ADF80430437903F0040101F0FF02D7 :1027600031B14FF40052ADF806204FF4806201E021 :10277000ADF80620ADF808200022ADF80C2013F0CB :10278000010218BF04229B07ADF80A2005D5BDF849 :102790000A3043F00803ADF80A30006D694609F0CD -:1027A00073FC05B05DF804FB8160FFF7CEBF41719B +:1027A0007DFF05B05DF804FB8160FFF7CEBF41718E :1027B000FFF7CBBF026B03691AB15168013B026C92 :1027C00002E0C169026A013B881A1840C0B2704732 :1027D000016B0346C26810B5406941B1196C541AC7 @@ -643,100 +643,100 @@ :102810008846174604D11046314600F0C9F807E053 :10282000474B984240F085801046314600F018F939 :1028300000250562C56185624562C0F82C8046713D -:10284000876085710446FFF780FF01A809F02EFF1D +:10284000876085710446FFF780FF01A80AF038FA17 :10285000E36CF20701934FF480530A934FF0800327 :102860000B95059507950693089527D5206BD0B154 -:10287000E36803950493202309936369029309F0A5 -:102880007FFE206B01A909F0F3FE206B012109F006 -:102890001AFF206D4021012209F06EFC206B09F027 -:1028A00027FF20640AE0206D40F2255109F06DFCFD -:1028B000206D40F22551012209F046FC01A809F0E3 -:1028C000F5FEA36C002501934FF480530A938027F3 +:10287000E3680395049320230993636902930AF0A4 +:1028800089F9206B01A90AF0FDF9206B01210AF0FA +:1028900024FA206D4021012209F078FF206B0AF014 +:1028A00031FA20640AE0206D40F2255109F077FFEB +:1028B000206D40F22551012209F050FF01A80AF0D5 +:1028C000FFF9A36C002501934FF480530A938027EE :1028D000B3070B95059507950697089523D5606B6B -:1028E000D8B12369099504931023039309F048FE96 -:1028F000606B01A909F0BCFE606B0122022109F0A6 -:10290000EDFE606B294609F0F1FE636B206D5D60A2 -:102910003946012209F030FC05E0206D40F22771B4 -:10292000012209F011FC206D012109F001FC204673 +:1028E000D8B1236909950493102303930AF052F990 +:1028F000606B01A90AF0C6F9606B012202210AF09F +:10290000F7F9606B29460AF0FBF9636B206D5D6097 +:102910003946012209F03AFF05E0206D40F22771A7 +:10292000012209F01BFF206D012109F00BFF204659 :1029300000E000200CB0BDE8F08100BF003801408D :102940000044004003469A6A9969406B1144C16093 :10295000596A914203D98A1A4260996204E019695E :102960008A1A426000229A62002283F844200121E0 -:1029700009F0A9BE10B5426A8469A154416A02698E +:102970000AF0B3B910B5426A8469A154416A026988 :102980000131B1FBF2F402FB14124262426B32B12C :102990001368DB070BD4BDE81040FFF7D3BF006D11 -:1029A00040F227710122BDE8104009F0CDBB10BDF7 +:1029A00040F227710122BDE8104009F0D7BE10BDEA :1029B000254B264A13B51A60254A98605A61254A64 :1029C0000C469A614FF48072DA601A61224A4FF421 :1029D00080401A6504329A64DA6402F5484254323F -:1029E0001A630121143A5A6309F0B6FC02238DF8E8 +:1029E0001A630121143A5A6309F0C0FF02238DF8DB :1029F00003304FF40073ADF80030A2074FF0180316 :102A00008DF8023003D515486946FFF75DF94FF49C :102A10008063ADF8003048238DF80230E30703D51A :102A20000E486946FFF750F90E238DF8043001A8CF -:102A300001238DF805308DF806308DF8073008F049 -:102A4000EFFF014802B010BD640A00205CF00008EE +:102A300001238DF805308DF806308DF8073009F048 +:102A4000F9FA014802B010BD640A002070F60008CF :102A5000A207002062090020003801400008014060 :102A6000224B234A13B51A608022DA6040221A6191 :102A7000204A98605A61204A0C469A611F4A4FF4D6 -:102A800000301A65012104329A64DA6409F070FC9E +:102A800000301A65012104329A64DA6409F07AFF91 :102A900002238DF803300423ADF80030A2074FF075 :102AA00018038DF8023003D515486946FFF70CF975 :102AB0000823ADF8003048238DF80230E30703D532 :102AC0000F486946FFF700F926238DF804300222EB :102AD000012301A88DF805308DF806208DF8073008 -:102AE00008F09EFF014802B010BD00BFB80A0020E8 -:102AF0005CF00008A20800202209002000440040E9 -:102B00000008014010B50B4C4FF4005009F0F4FDE3 -:102B1000606B002109F0D7FD626AA36A9A4204D073 +:102AE00009F0A8FA014802B010BD00BFB80A0020E2 +:102AF00070F60008A20800202209002000440040CF +:102B00000008014010B50B4C4FF400500AF0FEF8DD +:102B1000606B00210AF0E1F8626AA36A9A4204D06D :102B20002046BDE81040FFF70DBF012384F8443074 :102B300010BD00BF640A00200D4B186D02881206FC :102B400014D59A6A596A8A420BD09969895C013214 :102B5000C9B281801969B2FBF1F001FB10229A62BF -:102B6000704740F22771002209F0EEBA704700BFAB +:102B6000704740F22771002209F0F8BD704700BF9E :102B7000640A002038B51B4C236D1D88ADB2AA062F :102B800012D5E26A1AB1988880B290470CE09B880F :102B9000E2696169DBB28B54E269E3680132B2FB3E :102BA000F3F103FB1123E3612B0619D5A26A616AD5 :102BB0000C4B8A420CD09869196D805C0132C0B20E :102BC00088801969B2FBF1F001FB10229A6238BDCE -:102BD000186D40F227710022BDE8384009F0B4BA00 +:102BD000186D40F227710022BDE8384009F0BEBDF3 :102BE00038BD00BFB80A002010B50023094CDAB286 :102BF00054F8224001338442F8D10023064CD8B265 :102C000034F8104001338C42F8D102EB8000C0B29E -:102C100010BD00BF54F1000864F1000870B504460F -:102C20000026324B9D5DA5B92046022109F01DFA10 -:102C3000012857D12046022109F022FA29462046D0 -:102C4000FFF7D2FF2A4D05EB0015204609F000FAE8 -:102C500043E0042D14D12046294609F006FA012844 -:102C600040D12046294609F00BFA29462046FFF7B5 -:102C7000BBFF1F4D05EB0015204609F0ECF92CE0D9 -:102C8000082D14D12046294609F0EFF9012829D151 -:102C90002046294609F0F4F929462046FFF7A4FF0B -:102CA000134D05EB0015204609F0D8F915E00C2D61 -:102CB00018D12046102109F0D8F9012812D1204658 -:102CC000102109F0DDF929462046FFF78DFF084D58 -:102CD00005EB0015204609F0C4F9AB6801460BB1BD -:102CE000287B98470236082E9BD170BD64F10008FE +:102C100010BD00BF68F7000878F7000870B50446DB +:102C20000026324B9D5DA5B92046022109F027FD03 +:102C3000012857D12046022109F02CFD29462046C3 +:102C4000FFF7D2FF2A4D05EB0015204609F00AFDDB +:102C500043E0042D14D12046294609F010FD012837 +:102C600040D12046294609F015FD29462046FFF7A8 +:102C7000BBFF1F4D05EB0015204609F0F6FC2CE0CC +:102C8000082D14D12046294609F0F9FC012829D144 +:102C90002046294609F0FEFC29462046FFF7A4FFFE +:102CA000134D05EB0015204609F0E2FC15E00C2D54 +:102CB00018D12046102109F0E2FC012812D120464B +:102CC000102109F0E7FC29462046FFF78DFF084D4B +:102CD00005EB0015204609F0CEFCAB6801460BB1B0 +:102CE000287B98470236082E9BD170BD78F70008E4 :102CF0000C0B002070B50C4615461E46FFF774FFFE :102D00000F2805D8034B03EB001086600471057390 :102D100070BD00BF0C0B00200C2912D8DFE801F0B9 :102D200007111111091111110B1111110D000221BF :102D300004E0042102E0082100E01021012209F052 -:102D400090B8704738B504460D461346217B00689D +:102D40009ABB704738B504460D461346217B006890 :102D50002A46FFF7CFFF2068217BBDE83840FFF708 :102D6000DBBF07B500238DF804008DF8053001A8FE -:102D700001238DF806308DF8073008F051FE03B0BE +:102D700001238DF806308DF8073009F05BF903B0B8 :102D80005DF804FB7FB5044601A816460D4609F020 -:102D900033F80B4B013D5E430A4B20461B6801A9EB +:102D90003DFB0B4B013D5E430A4B20461B6801A9DE :102DA000B3FBF6F6013E0023ADF80850ADF8046021 -:102DB000ADF80A30ADF8063008F0D6FE04B070BDAC -:102DC00040420F008401002010B504460068FFF760 -:102DD000D9FF2068012109F02AF8607BBDE8104086 +:102DB000ADF80A30ADF8063009F0E0F904B070BDA6 +:102DC00040420F008801002010B504460068FFF75C +:102DD000D9FF2068012109F034FB607BBDE8104079 :102DE000FFF7BFBF0148FFF719BF00BF002C01402C :102DF0004FF08040FFF712BF0148FFF70FBF00BF41 :102E0000000400400148FFF709BF00BF0008004070 -:102E1000024800214FF480720BF032B80C0B0020F6 +:102E1000024800214FF480720BF03CBB0C0B0020E9 :102E200010B5FDF773FE0A49FDF7C4FE0949FDF729 :102E300075FF094B04461B681878FDF767FE0146CD :102E40002046FDF7B7FEFEF7A1F880B210BD00BF27 @@ -744,23 +744,23 @@ :102E600000201C78621C1A70FEF7BAFA0A4A04F0B5 :102E70000704002322F814001846D15A02330844EC :102E8000102B80B2F9D1C008FFF7CAFF034B1870AE -:102E900010BD00BF100C0020120C002048190020AB +:102E900010BD00BF100C0020120C0020E41900200F :102EA000074B084A1B7812889A4207D3064A1268D1 :102EB000907898428CBF0020012070470020704716 -:102EC000481900204A1900200C0C0020114B70B545 +:102EC000E4190020E61900200C0C0020114B70B50D :102ED0001860202500241E460020FEF781FA0444D5 -:102EE0000A2002F0F8F9013DF6D1C4F34F10FFF7C4 +:102EE0000A2002F04AFA013DF6D1C4F34F10FFF771 :102EF00097FF316801234C782246904203D3013377 :102F0000062B2244F9D1044A13708A785343034AAA -:102F1000138070BD0C0C0020010000204A19002015 +:102F1000138070BD0C0C002001000020E619002079 :102F20002DE9F04F0446008885B048B9B4F9023065 :102F300043B9B4F90430D3F1010338BF002302E0F0 :102F4000002300E0034613F0010377D13D4A00B2AD -:102F5000137000F0F5FD0646B4F9020000F0F0FD34 -:102F60000546B4F9040000F0EBFD0446304609F0D4 -:102F7000CDFB0746304609F03DFC8046284609F067 -:102F8000C5FB0646284609F035FC0546204609F0F3 -:102F9000BDFB8246204609F02DFC3946814650464D +:102F5000137000F0FDFD0646B4F9020000F0F8FD24 +:102F60000546B4F9040000F0F3FD0446304609F0CC +:102F7000D7FE0746304609F047FF8046284609F04D +:102F8000CFFE0646284609F03FFF0546204609F0D9 +:102F9000C7FE8246204609F037FF39468146504633 :102FA000FDF708FE394683464846FDF703FE5146C5 :102FB00001904046FDF7FEFD494602904046FDF770 :102FC000F9FD314603905046FDF7F4FD1E4C49468D @@ -784,3832 +784,3930 @@ :1030E000B4F90400FDF712FD294D06462968404653 :1030F000FDF760FDE96881463846FDF75BFD014656 :103100004846FDF74FFCA96981463046FDF752FD60 -:1031100001464846FDF746FC09F02EFB6968208011 +:1031100001464846FDF746FC09F038FE6968208004 :103120004046FDF747FD296981463846FDF742FDD7 :1031300001464846FDF736FCE96981463046FDF711 -:1031400039FD01464846FDF72DFC09F015FBA9683D +:1031400039FD01464846FDF72DFC09F01FFEA96830 :1031500060804046FDF72EFD696980463846FDF7E0 :1031600029FD01464046FDF71DFC296A0746304609 -:10317000FDF720FD01463846FDF714FC09F0FCFA86 +:10317000FDF720FD01463846FDF714FC09F006FE78 :10318000A080BDE8F88300BF480C002002000020AA :10319000240C002070B5124D06462B78114C9BB1C3 -:1031A00002F088F823683344984218D300232B7028 -:1031B00002F080F80C4B20601A780AB1013A1A70BC -:1031C0000A4B01221A7070BD02F074F82368323382 -:1031D000984204D301232B7002F06CF8206070BD7C -:1031E0004E0C00205C0C0020500C00204F0C0020E6 +:1031A00002F0DAF823683344984218D300232B70D6 +:1031B00002F0D2F80C4B20601A780AB1013A1A706A +:1031C0000A4B01221A7070BD02F0C6F82368323330 +:1031D000984204D301232B7002F0BEF8206070BD2A +:1031E0004F0C00205C0C0020510C0020500C0020E3 :1031F00073B5214D8DF807302B788DF8062002AA83 :103200008DF804008DF805101A4412F8042C443A85 :10321000D2B20A2A28D81949022B31F8124003D811 :1032200014B12046FFF7B6FF2B78022B0BD9144BB5 -:103230001E6802F03FF8001B864204D20E4A0023AB +:103230001E6802F091F8001B864204D20E4A002359 :103240001370104A1370104B1A78012A1A4600D0D6 :103250007CB92B78022B02D8074901330B7000236D :1032600013700A4A137004E0022B4FF03204D8D9CD -:10327000DAE702B070BD00BF530C00206CF100080B -:103280005C0C0020500C00204F0C00204E0C002045 -:10329000014B1860704700BF540C00202DE9F04727 -:1032A0003C4A0746537B91463B4D03B101234FF403 -:1032B00000702B7000F076F9384C30B3384EDFF8E0 -:1032C000E880336898F802001B68003018BF0120BE +:10327000DAE702B070BD00BF530C002080F70008F1 +:103280005C0C0020510C0020500C00204F0C002042 +:10329000014B1860704700BF580C00202DE9F04723 +:1032A0003F4A0746537B91463E4D03B101234FF4FD +:1032B00000702B7000F07EF93B4C30B33B4EDFF8D2 +:1032C000F480336898F802001B68003018BF0120B2 :1032D0005B68984740B10123237033681B68DB6843 :1032E000984708B10223237033681B689B6898478E :1032F00020B198F802300BB90223237033681B68A1 -:103300009B69984708B100232370202004F0CEFE6B -:1033100068B199F80A20234B12B91E4AD27A22B119 -:10332000214AD27A0AB9012200E000221A702378D9 -:10333000022B02D14C204E211CE0012B07D14D2144 -:1033400053204C220B46BDE8F047FFF751BF154B09 +:103300009B69984708B100232370202005F0D2F96B +:1033100068B199F80A20264B12B9214AD27A22B113 +:10332000244AD27A0AB9012200E000221A702378D6 +:10333000022B02D14C204E211CE0012B07D153203F +:103340004D214C220B46BDE8F047FFF751BF184B0B :103350001B78012B03D1532001464E2205E02B7828 :10336000012B04D15320014602464D23EBE727B140 -:1033700053204D210A464423E5E70C4B1B7823B12B -:103380003220BDE8F047FFF705BF094B1F70BDE8CD -:10339000F08700BFCC1F0020510C0020520C0020F1 -:1033A000540C0020580C0020BB1F0020500C0020A3 -:1033B0004E0C0020014B1870704700BF500C0020CD -:1033C0000E4B1A78452A16D15A88B2F5886F12D159 -:1033D0001A79BE2A0FD193F83D240020EF2A0CD190 -:1033E00013F8012B5040064A9342F9D1D0F1010065 -:1033F00038BF0020704700207047704700F8010870 -:1034000040FC0108C8230380142383701E23C3706B -:10341000012303716423C3804FF49673038128232F -:103420004381704710B50446272005F0F5FF207052 -:10343000102005F0F1FF6070002005F0EDFFA07096 -:10344000002005F0E9FF4FF4E1336360A360E3601F -:1034500023615223E070237510BD000030B51C4C71 -:103460001C4D85B0204604F057FE2946204604F046 -:103470006DFE05F1240001F0A9FD05F1680005F0DD -:10348000F5FA14F8500C02F09BFA04F1A40003F0D2 -:10349000B1FCA4F14C0004F073FB04F1980000F0BF -:1034A0009FFE05F1280001F08BFD05F14B03009311 -:1034B00005F13803019304F1A203029304F15800CB -:1034C000A91D2A4604F1A00302F030FF05B030BD6B -:1034D000E01D00201C1A002008B5054B054903EB30 -:1034E00000204FF4807200F59E70FDF76FFD08BD5F -:1034F0004C190020901D0020F8B5274B45221A706A -:103500004FF488625A80BE221A71EF2283F83D245C -:10351000002283F83E2411461F46BB5C0132B2F5FF -:10352000886F81EA0301F8D11B4B042683F83E140F -:1035300008F032FE0025013E16F0FF061ED03420B2 -:1035400008F03EFE154CC4F3090363B13A1902F1C9 -:103550007842A2F5FC322046116808F07BFE042870 -:10356000054607D0E7E7204608F056FE0428054642 -:10357000ECD0E0E70A4B04349C42E4D108F018FE9A -:10358000042D02D1FFF71CFF20B90A20BDE8F84046 -:1035900001F014BFF8BD00BF4C19002000F801086D -:1035A00040FC0108034B9B6818420CBF002001201F -:1035B000704700BF4C190020024B9A681043986076 -:1035C000704700BF4C1900202DE9F04FB74AB84DA5 -:1035D00085B010685168B74C02AB03C34FF48862E2 -:1035E000002128460AF04CFC00214FF4807220464E -:1035F0000AF046FC45232B70022003236B71FFF772 -:10360000DBFF4FF41673A5F8F030FA23A5F8F2307B -:103610002A23A5F8EE304FF4FA73A5F8F6302023EC -:1036200085F8F4306E2385F804312B2385F80531B5 -:10363000212385F8063140F24C43A5F8143140F2BD -:103640006C7300264FF0010840F2DC52A5F81631E9 -:1036500040F27E43A5F8122185F83C64A5F8FA6093 -:10366000A5F8F860A5F8FC6085F8E26085F8E360ED -:1036700085F8E460A5F8E660A5F8E860A5F8EA60DA -:1036800085F8ED6085F8EC8085F8076185F838618C -:1036900085F83A6185F8396185F8106185F8186117 -:1036A00085F8196185F81A6185F81B6185F81C8118 -:1036B000A5F8D03040F23A73A5F8D2304FF47A73BF -:1036C000A5F8D43040F27E53A5F8D63040F2EA5344 -:1036D000A5F8D83040F2B4534FF03209A5F8DA30EB -:1036E00005F590704FF4C873A5F8DE300192A5F887 -:1036F000DC90A5F8E09085F81E61FFF793FE40F698 -:10370000AC5308201E21AB81E07417230E20A17357 -:103710002376E17363760B215523A0726420A37195 -:1037200021722D231421E0777820DFF8B0A12374D3 -:10373000617263772175607350215F48E3755F4B59 -:103740002827A1774FF00A0B5A21E1726062AE730D -:10375000267027716771A67684F807906674E676FE -:10376000A674267784F815B0277384F82180C4F8EE -:1037700030A0E36323644FF08243E3624FF07C5355 -:10378000A3634F4B84F8501063644E4B84F854602D -:10379000A3644D4B84F85560E364412384F85130B1 -:1037A00084F85660019AA062C4F834A004F15C0069 -:1037B000A4F8582084F8529084F8536002F0E4F89A -:1037C000042384F86030152384F864303F4BC4F838 -:1037D00068A0E3663E4B3F48236705F58471A4F873 -:1037E0005A6084F8617084F8627084F8748004F020 -:1037F0006FFE4FF44873A4F8A430C82384F8E9306E -:103800004FF49663A4F8EA3040F2D933A4F8EC30D0 -:1038100040F64303A4F8EE3084F8A06084F8A16079 -:1038200084F8A27084F8A38084F8A66084F8E8B0D5 -:1038300023464FF47F72A4F8A8204FF4FA62A4F84C -:10384000AA2002A940F2DC52A4F8AC208A5D01361D -:1038500084F8AE20082E4FF0FF0284F8AF2004F168 -:103860000804E6D101221C4883F8F02083F8F120F7 -:1038700083F8F220FFF7C6FD0023EA181033002179 -:10388000C02B1161F9D10024281900F59E70094957 -:103890004FF4807204F58074FDF798FBB4F5407F17 -:1038A000F2D105B0BDE8F04FFFF726BEBCEF00082F -:1038B0004C190020901D0020000020408FC2753D53 -:1038C000CDCC4C3D0000A04000004040F6287C3F9D -:1038D0003D0A773F82F10008841E00209A99193F23 -:1038E00008B5FFF76DFD18B9BDE80840FFF76CBEDD -:1038F00008BD0000024B9A6822EA000098607047F9 -:103900004C19002010B5314C48F20103A268134055 -:1039100033B92F4B13401BB94FF40040FFF74CFE57 -:10392000A36803F42033B3F5203F03D14FF40030F4 -:10393000FFF7E0FFA368D90311D51A0702D50820C5 -:10394000FFF7D8FFA3681B0403D54FF40040FFF72F -:10395000D1FFA368D80702D50120FFF7CBFFA368EA -:1039600019070BD51A0403D54FF40040FFF7C2FF27 -:10397000A368DB0702D50120FFF7BCFFA26848F26D -:103980000103134048F20102934203D14FF4004077 -:10399000FFF7B0FFA26848F24003134048F240022C -:1039A000934202D14020FFF7A5FF0A4804F012FC21 -:1039B000094805F0AFFE084805F02AFE20B9064880 -:1039C000BDE81040FFF72EBD10BD00BF4C19002010 -:1039D00008000100541A00206C1A002007B5FFF7F8 -:1039E000EFFC10B90A2001F0E9FC104B1049184611 -:1039F0004FF48862FDF7EAFA90F83C24022A84BF6B -:103A0000002280F83C2490F83C2400EB022101F5D0 -:103A10009E714FF480720748FDF7D8FAFFF772FFE6 -:103A200003B05DF804EBFFF719BD00BF4C1900208F -:103A300000F80108901D002008B5FFF7CFFFBDE892 -:103A400008400F201421012207F0B2BD08B5054B34 -:103A500093F83C04FFF740FDFFF74EFDBDE808403A -:103A6000FFF7EABF4C190020014B9868704700BF70 -:103A70004C190020884203DB9042A8BF10467047D3 -:103A80000846704770B504460E461546FDF730FAF5 -:103A900030B920462946FDF749FA18B1284670BDCD -:103AA000304670BD204670BD0023036170472DE98C -:103AB000F041066904460136012E0D46066105D126 -:103AC0000023616021608360BDE8F081D0F8008050 -:103AD00008464146FCF764FF07463046FDF716F8F6 -:103AE00001463846FDF71AF901464046FCF75AFFF1 -:103AF0000646606031462846FCF752FF01463846CC -:103B0000FDF758F8A168FCF74DFF2660E060A06063 -:103B1000BDE8F08110B504460069012807DD0138D1 -:103B2000FCF7F4FF0146E068FDF7F8F810BD00204F -:103B300010BD08B5FFF7EEFFBDE8084008F0EABE8B -:103B400008B5FCF761FC04A3D3E90023FCF7C2FC31 -:103B5000FCF7D2FE08BD00BF399D52A246DF913F5F -:103B60002DE9F041069C002B06460F460CBF4FF096 -:103B700020084FF03008234613F8011B09B91546F9 -:103B800003E0002AFBDD013AF6E7002D04DD3046B4 -:103B90004146B847013DF8E714F8011B11B1304622 -:103BA000B847F9E7BDE8F081014B186801F036BB72 -:103BB000680C00202DE9F04788B006460F460392B6 -:103BC0001C46039A531C03931178002900F08D8042 -:103BD000252901D0304686E00023911C04930391EF -:103BE0005578302D05D1D31C039395784FF00108FB -:103BF00000E09846A5F13003DBB2092B06D8284631 -:103C000003A90A2204AB00F034F905466C2D05D156 -:103C1000039B5A1C03921D78012200E00022632DB1 -:103C20004FD006D8252D5CD0582D2AD0002D5CD041 -:103C3000C7E7732D4AD002D8642D14D0C1E7752D83 -:103C400002D0782D1DD0BCE704F1040905AD206831 -:103C50000A2122B100222B4600F090F80EE02B46FC -:103C600000F0BFF80AE005AD04F104092068294618 -:103C700012B100F0ABF801E000F0DBF84C46009523 -:103C800018E004F1040A0DF11409206810213AB17A -:103C9000B5F15804624262414B4600F06FF806E00D -:103CA000B5F158035A425A414B4600F09AF854462F -:103CB000CDF8009030463946049A4346FFF750FF4E -:103CC0007FE730462178251DB84708E02368304655 -:103CD00000933946049A0023251DFFF741FF2C4627 -:103CE0006FE730462946B8476BE708B0BDE8F08774 -:103CF0000FB407B50A4904AB08680A4953F8042B06 -:103D000009680193FFF756FF074B186801F0A5FA01 -:103D10000028F9D003B05DF804EB04B0704700BF91 -:103D2000640C0020600C0020680C0020034A044B47 -:103D30001A60044B00221A60704700BFA93B0008BC -:103D4000600C0020640C0020014B1860704700BF1D -:103D5000680C002070B50646B6FBF2F4084615461E -:103D600014B12046FFF7F6FF05FB1464024B1B5D00 -:103D700000F8013B70BD00BF8BF10008F0B50124D5 -:103D8000B0FBF4F58D4201D34C43F9E70026DCB1DA -:103D9000B0FBF4F504FB1500B4FBF1F41EB9002DE3 -:103DA00001DC002CF3D1092D03F101075FFA85FC3A -:103DB00004DD002A0CBF5725372500E03025654477 -:103DC0001D7001363B46E2E71C70F0BD00280B4633 -:103DD00003DA2D2240420A704B1C0A210022FFF711 -:103DE000CDBFF0B50124B0FBF4F58D4201D34C43B7 -:103DF000F9E70026DCB1B0FBF4F504FB1500B4FBD9 -:103E0000F1F41EB9002D01DC002CF3D1092D03F1D2 -:103E100001075FFA85FC04DD002A0CBF5725372512 -:103E200000E0302565441D7001363B46E2E71C701A -:103E3000F0BD00280B4603DA2D2240420A704B1CCD -:103E40000A210022FFF7CDBFA0F13003DAB2092A20 -:103E500001D818467047A0F16103052B01D85738E7 -:103E60007047A0F14103052B94BF37384FF0FF3066 -:103E700070472DE9F8430D6804460F469046994671 -:103E800000262046FFF7E0FF002806DB404504DC63 -:103E900008FB060615F8014BF3E73D602046C9F81C -:103EA0000060BDE8F883931E232B28BF0A22031E5F -:103EB00010B50C4603DA2D2001F8010B5842FFF72C -:103EC00049FF00230370204610BD000030B587B0C5 -:103ED00005460C4603A800210C2209F0D1FF284614 -:103EE0000021FDF723F820B128462949FCF75AFDA7 -:103EF00003E028462649FCF753FD2649FCF75AFE05 -:103F0000FDF71EF8054685EAE570A0EBE570694609 -:103F10000A22FFF7C8FF002DACBF20232D236846DF -:103F20008DF80C300AF0A2FB012807D130238DF860 -:103F30000D308DF80E308DF80F300CE0022805D1D1 -:103F400030238DF80D308DF80E3004E0032804BFC7 -:103F500030238DF80D30694603A80AF089FA03A8CA -:103F60000AF084FB0338C5B22A4603A920460AF0AA -:103F7000D5FB00236355204607490AF079FA03A9C7 -:103F8000204629440AF074FA204607B030BD00BF2D -:103F90006F12033A00007A4408FC00082DE9F04152 -:103FA00002780346202A00F10100F9D0092AF7D04F -:103FB0002D2A02D10346414D04E02B2A08BF0346B7 -:103FC0004FF07E551E460024334616F8012BA2F111 -:103FD0003007F9B209290DD839492046FCF7EAFD26 -:103FE00004463846FCF792FD01462046FCF7DAFC11 -:103FF0000446E9E72E2A17D1314F334616F8010B54 -:104000003038C2B2092A0FD8FCF780FD3946FCF7D8 -:1040100085FE01462046FCF7C5FC29490446384682 -:10402000FCF7C8FD0746E8E71A7802F0DF02452AE8 -:1040300038D15A782D2A02D10233012604E02B2AE6 -:1040400014BF013302330026013B002713F8012F70 -:10405000303AD1B2092903D80A2101FB0727F5E735 -:10406000B7F59A7F28BF4FF49A77B8464FF07E5144 -:10407000B8F1070F07D908461249FCF79BFDA8F1D4 -:1040800008080146F4E707F0070737B108460C496E -:10409000FCF790FD013F0146F7E72EB12046FCF703 -:1040A0003DFE04E04FF07E512046FCF783FD0146C3 -:1040B0002846FCF77FFDBDE8F08100BF000080BF0F -:1040C0000000204120BCBE4C014B00229A8070476A -:1040D000700C0020034BB3F90400D0F1010038BF8D -:1040E00000207047700C0020014B187A704700BF09 -:1040F000700C0020014B01221A727047700C0020D6 -:10410000064BB3F90400064B1B681B7803EB8303D3 -:104110009842D4BF00200120704700BF700C0020DF -:104120007C0C002010B50446FFF7EAFF002814BFFE -:104130002046002000F0010010BD0000074B1A6867 -:10414000074B1178B3F9040053780B4403EB830356 -:104150009842D4BF00200120704700BF7C0C002093 -:10416000700C0020024B9A8801329A80704700BF81 -:10417000700C002070B5FFF7C3FF30B3134C237AE7 -:104180000BB9A38070BD124EB578281C18BF012052 -:10419000FFF7C8FF88B1012373700E4B1A680E4BEE -:1041A000518919805189598052899A800B4A126825 -:1041B0005288DA80E3880133E380FFF7BFFF00B95C -:1041C0001DB9BDE8704000F01BBB70BD700C002035 -:1041D000BB1F0020800C0020142000207C0C00203D -:1041E000024B00221860024B9A8070477C0C002022 -:1041F000700C0020044B18600448054B036000233A -:10420000C3800372704700BF800C0020700C002038 -:10421000B0F10008044B9A8811B21429CCBF143AAB -:1042200000229A80704700BF700C0020032810B550 -:104230000D4B0DD80D4A126894888C4208D2D28852 -:104240008A4205D9012202FA00F01A781043187048 -:104250001B780F2B06D1044B00221A70BDE81040CA -:10426000FFF7D8BF10BD00BF6C0C00207C0C0020F5 -:1042700070B5744C86B0FFF759FDFFF731FBFFF7BF -:10428000ADFBA07B003018BF012001F02FF894F89F -:10429000073133B103F0F702012A02D18DF8003063 -:1042A00004E000238DF8003084F807316846FDF7FC -:1042B000A5F80220FFF776F910B16348FEF706FE75 -:1042C0006248634DFEF72CFE022003F0F9FE6148C0 -:1042D000B4F8EE1094F8ED20B5F95A3000F036FF3E -:1042E0002E4610B9032001F069F80A25192000F0C4 -:1042F000F2FF192000F0EFFF6B1E13F0FF05F5D160 -:1043000001F0EEFB6079544902F074F8FEF780FD8D -:10431000524805F091FA63790E2B01D0082B03D196 -:1043200001238DF80B3001E08DF80B5001214B4833 -:1043300005F0B4F98DF807004020FFF733F98DF848 -:1043400008004FF40040FFF72DF98DF804004FF4FA -:104350000030FFF727F98DF806000120FFF722F95A -:104360008DF8050002F076FC96F8F2308DF8090021 -:10437000C3F380038DF80A30B4F8DE304FF4804088 -:10438000ADF80E30B4F8E030ADF810304FF47A7379 -:10439000ADF81230FFF706F920B12A4BB3F8DA3046 -:1043A000ADF81230BDF80E30B3F5FA7F84BF0023AC -:1043B000ADF81230B4F81231ADF8143094F807317A -:1043C000012B04D0092B01D1072300E0002301A811 -:1043D0008DF80C30FDF7B2FC2148FFF70BFF214DA3 -:1043E0002860FEF755FF1E48296803F02DFF4FF4A3 -:1043F0008070FFF7D7F838B11B4A184894F81E119F -:10440000A2F1F00303F00CFC4FF40060FFF7CAF8D0 -:1044100008B104F0B3FB00F033FF144B186063796C -:10442000052B03D14FF4C87000F0B2FC4FF47A7042 -:1044300000F0D2FD0E4B01225A7300225A7006B0D2 -:1044400070BD00BF4C190020501A0020321A002005 -:10445000901D00202E1A00205C1900206C1A0020EC -:10446000541A0020941E0020841E0020880C002076 -:10447000BB1F002008B5FFF7FBFE00F0E7F9FCE7E3 -:1044800008B5034BB3F9D40002F0D0F8FEE700BF43 -:104490004C19002008B500F081FC28B100F0A2FD05 -:1044A00080F00100C0B205E0022003F0FFFD00280B -:1044B000F4D0012000F0010008BD0000044B1A6890 -:1044C00022B900F5F42000F590701860704700BF25 -:1044D0009C0C0020054A13683BB1C01A002804DB7D -:1044E00003F5F42303F59073136070479C0C0020D0 -:1044F000B04B2DE9F04FB3F90600AF4B85B0B3F8E0 -:10450000582090420FDBB0F5FA6F93F8564007DA67 -:10451000811A4C43A2F5FA6294FBF2F4643403E08E -:10452000C4F1640400E06424A44A93F85410B2F87F -:1045300012C192F9EC2093F8A05093F8A160524276 -:1045400093F8553092B201910021029203930A46EA -:10455000984B40F2E637CB5E0093CCEB030303F2BB -:10456000F31EBE4503D8002BB8BF5B4201E04FF4F9 -:10457000FA73022ADFF850822CD025B1AB42CCBFAF -:10458000C5EB030300236427DFF868A293FBF7FE63 -:104590006FF0630B3AF81E900BFB0E3B0EF1010E11 -:1045A0003AF91EA00FFA89FECEEB0A0E0EFB0BFEA7 -:1045B0009EFBF7FECE4428F801E0DDF8048003FB03 -:1045C00008FE7F4B9EFBF3F33B449BB2634393FB9C -:1045D000F7F714E026B1B342CCBFC6EB03030023C8 -:1045E000DDF808E003FB0EF7A8F80470039F002B2A -:1045F000B8BF5B427B43724F93FBF7F764376E4B58 -:10460000DFF8F48102EB030E9EF80490642307FBAD -:1046100009F999FBF3F902F808909EF80E909EF8BC -:1046200018E007FB09F907FB0EF7DFF8D08199FBCB -:10463000F3F902F80890DDF8008097FBF3F3614F7F -:10464000E045D355604F02DA7B5A5B427B52013220 -:10465000032A01F102017FF47BAF584C4FF4FA6258 -:10466000B4F81411FFF706FAB4F814314FF47A7560 -:10467000C01A4543C3F5FA63B5FBF3F5642153480B -:1046800095FBF1F36FF0630630F8132006FB03553A -:10469000013330F9130013B2C31A5D4395FBF1F1F6 -:1046A0004B4D0A446B7A484CFA80002B38D0494B6A -:1046B0001888494B1B88C01A00B2FFF741FA06461A -:1046C00008F024F80746304608F094F80646B4F996 -:1046D0000200FCF71BFA8046B4F90000FCF716FA5A -:1046E00039468146FCF766FA314682464046FCF779 -:1046F00061FA01465046FCF753F9FCF721FC3946B4 -:1047000020804046FCF756FA314607464846FCF7FB -:1047100051FA01463846FCF745F9FCF711FC608078 -:104720000220FEF73FFF2D4C88B12D4A137801334C -:10473000DBB213700622B3FBF2F102FB113313F06C -:10474000FF0F04D1FEF78AFBFEF7AAFB207020784A -:104750001F4C003018BF0120FEF7A0FDAB78ABB9AD -:10476000FFF798FE01232370A37813B9637B03B985 -:1047700023702B781B4C1BB11B4B00221A6002E0EC -:104780002068FFF79BFE2068FFF7A4FE04F0D6F92F -:1047900005F062F8202003F089FC18B1114B18686D -:1047A00003F016FC114B9B680BB11148984705B0FC -:1047B000BDE8F08F14200020901D00204C1900202F -:1047C0000CFEFFFFD31E0020E21F0020EA1F002086 -:1047D000BB1F0020DA1E0020A21E0020970C002024 -:1047E000990C0020840C00209C0C0020B81E002096 -:1047F000981E002002200020D61E0020D01E00207F -:10480000024B9A780AB100229A707047BB1F0020B1 -:104810000B4B19781A4651B1997879B9597831B951 -:1048200001229A70074B1A88074B1A8070479378B9 -:1048300023B90220FF21012206F0BABE704700BF53 -:10484000BB1F0020DA1E0020A21E00202DE9F84F19 -:104850008C4F03F043FD386803F068FD8A4C002854 -:1048600000F0DE81386803F011FE4FF48040FEF75F -:1048700099FE20B1854B1B780BB9FFF7C1FF03F000 -:104880003BFE4FF40070FEF78DFE88B13B68804A16 -:10489000804D934208D92B681B681B6A984718B94A -:1048A0002B681B685B6A98472B681B685B69984795 -:1048B0000022B4F81451B4F81661134676489B08E8 -:1048C000115E0232A942C4BF63F07F03DBB2B14282 -:1048D000B8BF43F04003082A8146EFD16F4EDFF89E -:1048E000D88132789A4205D198F80020F92A04D864 -:1048F000013200E0002288F800204FF4804033703D -:10490000FEF750FE58B1B4F81211B4F8DC20B9F932 -:104910000630881A834202DD0A4493420ADB4FF4D0 -:104920008040FEF73FFEC8B9B9F90620B4F814314B -:104930009A4213DA01F02CF801F032F8584BB3F830 -:1049400076305BB1514B1A78564B002A00F0DB8170 -:104950001A78002A00F0D781FFF75AFF98F8003044 -:10496000142B40F0BD804F4B4D4D93F802B09A464A -:10497000BBF1000F18D0B5F8763023B933785F2B30 -:1049800001D1FFF73DFF94F81A31002B00F0A88009 -:10499000B5F87630002B40F0A38033787D2B40F0C3 -:1049A0009F80FFF72DFF9BE03378572B11D14FF4F9 -:1049B0007A7000F011FB4FF48070FEF7F3FD08B140 -:1049C00002F080FA082003F071FBF0B9364B188032 -:1049D0001BE00420FEF7E6FDB8B1304B1B785A2BE4 -:1049E00013D1324B1A782AB183F800B0304B012230 -:1049F0001A700AE02F4A137883F0010313700BB189 -:104A0000022000E00320FEF7D5FC33785D2B00F098 -:104A100081815B2B00F080815E2B00F07F81B5F8F7 -:104A200076302BB932786F2A02D1FFF7F1FE13E00E -:104A300094F81A211AB113B933787E2BF5D0337854 -:104A4000972B04D14FF4C87000F0A2F904E0A72B13 -:104A500004BF01238AF80E303378BB2B03D1B5F89D -:104A60005E30023304E0B72B05D1B5F85E30023B6F -:104A7000A5F85E3029E0BE2B20D1B5F85C300233BA -:104A800021E000BF840C00204C190020CC1F002026 -:104A9000404B4C00941E002014200020A00C00204D -:104AA000901D0020BB1F0020DA1E0020A10C00205A -:104AB000980C0020960C0020940C0020BD2B0FD1E8 -:104AC000B5F85C30023BA5F85C3094F83C04FEF786 -:104AD00003FDFEF711FDFEF7AFFF002388F800305D -:104AE0000420FEF75FFD48B3964A974B117871B1E9 -:104AF0009649897859B1B9F90600B4F81411884279 -:104B000005DD197819B992483225058011705B7C52 -:104B100053B1904B1A782AB98F4A127812B98C4A3D -:104B200032211180012208E08B4B1A7832B1874A7A -:104B300092781AB91A70894B01221A708848012399 -:104B4000002230F8021F5E1EA1F21555B5F5C77F91 -:104B50008CBF002501259D4009B22A4340F2135520 -:104B6000A942CCBF00250125B5402A4340F2A465E7 -:104B7000A942D4BF002101215D1CA94003330A438F -:104B80000D2B92B2DDD1002376496F4E01EB43012C -:104B9000B1F876100A420CBF00210121995501336A -:104BA000152BF1D17378694D23B1022003F07EFA01 -:104BB00068B914E04FF40070FEF7F4FC78B16A4B6A -:104BC0001B681B689B6898470028EED107E0EB78CC -:104BD0003BB900F0DDFE5D4B0122DA7001E00023FD -:104BE000EB70B3784BB10023EB702B7933B900F045 -:104BF000CFFE564B01221A7100E02B71202003F0EA -:104C000055FA08B103F088F9337B03B10123AB7285 -:104C10006379082B01D00E2B24D100236B7221E085 -:104C2000524D2B68042B1DD8DFE803F00305080B59 -:104C3000160001232B602B6801332B602B68013396 -:104C40002B602B684FF4807001332B60FEF7AAFCB9 -:104C500010B102F05DF905E000234FF400502B6025 -:104C6000FEF7A0FC00F00CFBA2893860404B1AB1A3 -:104C70001968411A00293ADB1044186001F050F914 -:104C8000FFF736FC00F0FCFA3A4B3B491A68186013 -:104C9000344B821A93F8A63038600A8053B12B4BFC -:104CA000DA780AB91B792BB1344B354A1188DA8886 -:104CB0000A44DA80202003F0F9F940B1234BDA7975 -:104CC0000AB91A7A1AB11B7B0BB103F083F82D488D -:104CD0002D4B00F14C01B4F8F6201D6800F158038B -:104CE000A84701F0B5FC01F031FC01F08BFC274B2B -:104CF0001B7823BB4FF40060FEF754FCF8B1BDE80D -:104D0000F84F03F065BF9B78002B3FF427AEFFF709 -:104D100077FD23E6012202E0022200E003225FFA8F -:104D200082FB0BF1FF3384F83C34FEF7E5FBFEF722 -:104D300055FE022028215A4606F03AFC6FE6BDE8EF -:104D4000F88F00BF960C0020CC1F0020BB1F002056 -:104D5000A40C0020950C0020A10C0020980C002031 -:104D60001A200020901D0020941E0020900C00208E -:104D70008C0C0020880C0020A20C0020E21F0020D8 -:104D8000FA0D0020941D00200800002008140020C7 -:104D9000014B1880704700BFB20C0020034B1888ED -:104DA000D0F1010038BF0020704700BFB20C0020D6 -:104DB000204B00222DE9F0411968804613461E4C15 -:104DC0001E4E25881E4FB5F5C87F04BF0025F5503F -:104DD000F05832F907C0194D844446F803C0043333 -:104DE00000260C2BD6538E5202F10202E7D1238803 -:104DF000012B19D12B68404603F1C8024FF4C87348 -:104E000092FBF3F20A806A68C83292FBF3F24A809E -:104E1000AA68C83292FBF3F30A4A12889B1A8B8065 -:104E200000F0B2FDFEF712FE2388013B2380BDE8AF -:104E3000F08100BFB40C0020B20C0020C40C002094 -:104E4000F41E0020040000202DE9F041354D0446F9 -:104E50002B88322B0ED1344B1A68344B11881980B1 -:104E60005188928859809A80314B02881A804288F2 -:104E70005A8001E0002B34D02B490022D1F800C029 -:104E800013460F46298832292A4904BF0020C850FA -:104E90002948CE5832F900804644CE5004330021D0 -:104EA0000C2B11522CF8021002F10202EAD12B88CD -:104EB000012B13D1214A02201170214A1370FEF7F1 -:104EC00079FA1A4A3B68118819805188928859806A -:104ED0009A80174B1A885B88228063802B88013B5D -:104EE0002B80184B1A78DAB1124900221A700E4B37 -:104EF00008681B68322290FBF2F01880486890FB2B -:104F0000F2F058808968204691FBF2F20E49098838 -:104F1000521A9A8000F038FDBDE8F041FEF796BDC8 -:104F2000BDE8F081A40C0020B40C0020A80C0020E7 -:104F3000AE0C0020B80C0020F41E0020950C0020C0 -:104F4000A10C0020980C002004000020064B0288D1 -:104F500019888A1A1A80598842888A1A5A80998828 -:104F600082888A1A9A807047F41E00200F4B10B571 -:104F70005B6804460E4898470E4B0D481A78014668 -:104F8000FEF764F80C4B1B8813B12046FFF710FFA7 -:104F90000420FEF707FB10B12046FFF755FFBDE8E0 -:104FA0001040064B1868FFF7D1BF00BFA41E0020B9 -:104FB000F41E0020A60C0020B20C0020B40C00202F -:104FC000014B1860704700BFB40C0020014B186003 -:104FD000704700BFDC0C0020014B1880704700BFF9 -:104FE000EC0C0020034B1888D0F1010038BF0020E2 -:104FF000704700BFEC0C00203C4B2DE9F74F5B687D -:105000003B4898473B4B3A481A780146FEF71EF852 -:10501000394B374F1A889846DFF8E8A0002A3CD071 -:10502000364B00251B68364E93F800B02C46B8F876 -:105030000030DFF8D490B3F57A7F05D100233046F5 -:1050400049F80430FEF730FD785F59F80430034426 -:1050500049F80430FBF75AFD01463046FEF727FDBC -:1050600000237B532AF80530B8F80030012B25D1F6 -:105070003046FEF75EFD0346BBF1000F0FD05846E9 -:105080000193FBF743FD019B01461846FBF74EFFDA -:1050900028B1194B4FF47A721A8000231BE059F89B -:1050A00004304FF47A7203F5FA7393FBF2F30A209B -:1050B0000F2101222AF8053006F07AFA04340C2C6C -:1050C00005F1020506F11406B1D1B8F80030013B34 -:1050D000A8F80030E1E7F95A3AF803208A1AFA52A0 -:1050E0000233062BF7D103B0BDE8F08FB81E0020C5 -:1050F000DC1E00202C0D0020EC0C0020DC0C00201D -:10510000F00C0020D40D0020E00C0020034B0146E1 -:10511000002203481A70FCF72FB900BF2C0D0020A5 -:10512000B81E002003780BB1054A137043780BB109 -:10513000044A137083780BB1034A1370704700BFA1 -:105140002C0D0020A60C0020D80C00202DE9F843DF -:105150008046084614461E46FFF7D8FF054600283D -:105160004AD0274B0022022C1A70264F07D0072C5A -:1051700001D054B903E0022002F0AAFF05E0224862 -:10518000FCF7AAF808B102233B703B782BB90CB1AD -:105190001C46E6E7022002F09BFF4046FFF7C2FFF5 -:1051A000022002F083FF10B1174B1B689847174B82 -:1051B000174C1B689847082002F078FF0746C8B1D3 -:1051C0004FF0640896FBF8F52846FBF79FFC8146F4 -:1051D00008FB156000B2FBF799FC0E49FBF7EAFCEF -:1051E00001464846FBF7DEFB0B49FBF7E3FC3D4677 -:1051F000206001E0002323602846BDE8F88300BF5B -:10520000A60C0020D00C0020A41E0020B81E0020F8 -:10521000040E00208988883C0000204108B50368FE -:105220001B68984708BD38B505460C4614F8011BA5 -:1052300019B12846FFF7F2FFF8E738BD08B5036853 -:105240005B68984708BD08B503689B68984708BD28 -:1052500008B50368DB68984708BD08B503681B6993 -:10526000984708BD08B503685B69984708BD704753 -:10527000024B1A6801321A60704700BF300D0020DF -:1052800010B5094A094913688C6812689342F8D12D -:10529000074A106811684FF47A725043001BB0FB44 -:1052A000F1F002FB030010BD300D002010E000E023 -:1052B000340D0020014B1868704700BF300D0020EE -:1052C00038B50446FFF7DCFF0546FFF7D9FF401B62 -:1052D000A042FAD338BD10B504462CB14FF47A7011 -:1052E000FFF7EEFF013CF8E710BD000030B587B0D6 -:1052F00006F0D4F92648012107F03AF844F61D20BB -:10530000012107F029F80120014607F019F80025CE -:1053100007F052F806AC4FF6FF7369461D4824F8B3 -:10532000183D8DF80250FCF7CFFC69461A48FCF78F -:10533000CBFC69461948FCF7C7FC194B5A6842F088 -:1053400000725A60FFF793FF01A806F0ADFF019BC2 -:10535000144AF021B3FBF2F3134A14481360144BC0 -:105360001A684FF47A73B2FBF3F2124B013A5A60A7 -:10537000114A82F8231007229D601A60FCF752FA46 -:10538000FCF728FC6420FFF7A6FF07B030BD00BF84 -:105390000700400000080140000C014000100140DF -:1053A0000000014040420F00340D00200058004032 -:1053B0008401002010E000E000ED00E040F2DB148A -:1053C000604308B5841E2046FFF785FF1920FFF7CC -:1053D00082FFF8E710B1034A034B1A60034A044BFB -:1053E000DA607047EFBEADDEF04F00200400FA0532 -:1053F00000ED00E02DE9F04F87B005937A4B049261 -:10540000B3F90220B3F90030002AB8BF5242002B92 -:10541000B8BF5B4200249A42B8BF1A4607460392BF -:105420002546A146A0460294019426466F4BDA78A1 -:1054300012B91B79002B38D0022E36D06A4BDDF81A -:1054400010C0E85E6A4BCCF10001EB5E624603EBF4 -:105450004000FEF70FFB674BDDF814C035F903B0D1 -:105460003CF90530CBEB000000EB030BF879FA7E3A -:1054700000FB0BF064236FF0040190FBF3F0514349 -:1054800002EB8202FEF7F6FADFF888A1019054F8E9 -:105490000A005949584442F21072FEF7EBFA7B7C3D -:1054A00044F80A00584300130290504BDA781AB1BE -:1054B0001B790BB9022E33D14B4B502035F90380A9 -:1054C000DFF83CA100FB08F0BB5D35F90A20DFF8EE -:1054D000489190FBF3F0042392FBF3F3C01A54F8C5 -:1054E00009304FF47A5218444449FEF7C3FA35F9AB -:1054F0000A3049F80400002BB8BF5B42B3F5206FB7 -:10550000C4BF002349F8043059F804207D2392FBDE -:10551000F3F9BB199B7A03FB09F9402399FBF3F9D3 -:10552000324B1A79D2B1022E18D0DDF80CC04FF4EC -:10553000FA710CFB08F2CCF5FA73DDF804C003FB3A -:105540000C22DDF80CC092FBF1F20CFB09F0DDF847 -:1055500008C003FB0C0393FBF1F308E0DB780BB10D -:10556000022E02D14B46424601E0029B019A244999 -:10557000DFF8A8B0695A04200FFA81FC16F80BB0C6 -:105580009CFBF0FA0BFB0AFB6FF04F0A9BFBFAFA4D -:1055900002EB0A0B1B4A35F902A0A952CAEB0C0C0C -:1055A0009CFBF0F0184ADFF878C054F802A054F8D9 -:1055B0000C10A050154A5144B25C014451432022C2 -:1055C00091FBF2F15B1A124801369B44032E44F81A -:1055D0000CA025F800B004F1040405F102057FF4E5 -:1055E00025AF07B0BDE8F08FE21F0020BB1F0020F1 -:1055F000B2100020080E0020F0D8FFFF80C1FFFF8E -:10560000FC0D00205C0D00207C0D0020D31E00202E -:10561000CA1E0020940D0020700D0020D61E002010 -:10562000640D00202DE9F04F002485B006468A461F -:105630009346039307462546022DDFF83C814FEA47 -:10564000450908D19AF80530B8F904801B3308FBE6 -:1056500003F35B1128E03F4B38F9150033F915309F -:105660005A4603EB4000CBF10001FEF703FA3A4B38 -:1056700033F91530C01A039B33F915201044374A0B -:10568000D37873B99AF8043038F909801B3308FBD2 -:1056900003F312791B113AB1727C504303EB2023C0 -:1056A00002E0F37943431B112D4A705D32F9098002 -:1056B000042298FBF2F8C8EB030800FB08F0DFF8BF -:1056C000BCC0C0110290BCF80000264B00FB08F0E3 -:1056D000E258B97AC01201FB00202349E0504FF490 -:1056E00000120193CDF800C0FEF7C4F9019BDDF86C -:1056F00000C0E0501D4B4FF6FF72E15844F80380A4 -:10570000BCF80030C1EB08011B09B2FBF3F35943AD -:10571000DFF86CC0164B891154F8038054F80C2044 -:10572000E150029B424403EB60303B7D0A445A4304 -:105730000135104B00EB2222032D44F80C8023F896 -:10574000092007F1010704F104047FF475AF05B0E7 -:10575000BDE8F08FB2100020080E0020BB1F002013 -:10576000FC0D0020700D00200000E0FF500D002017 -:10577000A80D0020CA1E0020E21F0020A20C00205D -:10578000880D00202DE9F04F89B00693684B8046C4 -:1057900018880591FBF7B6F96649FBF70BFA002468 -:1057A0000490464625462746022FDFF8CC910BD1C0 -:1057B000059AB9F9040053790A335843FBF7A6F95F -:1057C0005D49FBF7ABFA37E05C4B39F90500EB5E5E -:1057D0005B4918444FF4FA72FEF74CF9594BDFF865 -:1057E0009CB1EB5EC01A069B5A5F1044FBF78EF922 -:1057F0005549FBF793FA9BF803208246C2B9059BF3 -:1058000039F905001A7914325043FBF77FF94A49F8 -:10581000FBF784FA9BF80420814672B1D8F848104F -:105820005046FBF7C7F901464846FBF7BBF803E0D3 -:10583000D8F84410FBF7BEF98146444B0137585F56 -:10584000FBF764F9424B0436D968FBF7B3F982469B -:1058500051464846FBF7A4F8F1698346FBF7AAF9DD -:10586000DFF81C91049907905846FBF7A3F9B16A39 -:10587000FBF7A0F954F80910FBF794F8354A3649BC -:10588000FEF700F944F80900DFF8F890834654F871 -:1058900009105046FBF784F844F809A00246049921 -:1058A0004FF07E500192FBF739FA019A01461046FB -:1058B000FBF780F9294B2A4A54F803C0A1588146C6 -:1058C000604601920293CDF80CC0FBF76BF8494695 -:1058D000FBF768F8DDF80CC0029B019A214944F8F7 -:1058E000039044F802C0FBF719FA716BFBF762F9F9 -:1058F0001D4A1E49FEF7C6F8594681460798FBF730 -:1059000051F84946FBF74CF806F036FF18494FF4BA -:105910007A72FEF7AFF8174B032F585304F10404C3 -:1059200005F102057FF440AF09B0BDE8F08F00BF7C -:10593000A20C0020BD37863500004842B21000207E -:105940000CFEFFFF080E002000002041FC0D00208F -:10595000B81E002000007A4300007AC3B40D002076 -:105960009C0D00200000404000009643000096C3BC -:1059700018FCFFFFCA1E0020E21F0020BB1F0020F2 -:10598000380D0020440D0020002303804380704721 -:10599000024B00221A605A60704700BF940D00202D -:1059A000054B00221A605A609A60044B00221A606C -:1059B0005A609A60704700BF700D0020380D0020BB -:1059C0000128054B03D0022803D0044A02E0044A10 -:1059D00000E0044A1A60704708000020F5530008F0 -:1059E00025560008855700082DE9F84F384E044623 -:1059F0003768384606F08AFE0546384606F0FAFE55 -:105A000076688046304606F081FE8346304606F0D2 -:105A1000F1FED4F80490064629464846FBF7CAF83A -:105A2000A768824641463846FBF7C4F8014650460F -:105A3000FAF7B6FF216882465846FBF7BBF84146A5 -:105A400004464846FBF7B6F83146FBF7B3F8014683 -:105A50002046FAF7A7FF314604463846FBF7AAF876 -:105A60002946FBF7A7F801462046FAF79BFF0146B7 -:105A7000504606F04DFF1749FBF79CF8FAF7D6FCA5 -:105A800011A3D3E90023FAF74FFE134B044618681D -:105A90000D46FAF7CBFC02460B4620462946FAF79C -:105AA00067FB00220D4BFAF73FFEFAF725FF06F0E1 -:105AB00063FE83B21A0444BF00F5B4739BB218B2FC -:105AC000BDE8F88FAFF30080182D4454FB21094046 -:105AD000C80D00200000E144040E00200000244016 -:105AE00010B5254C2088FBF711F82449FBF762F824 -:105AF00006F042FE224B18802088FBF707F801468B -:105B00002048FBF70BF92049FBF708F91F4B1860F9 -:105B10001F4BB3F8A400FAF7F9FF01461D48FBF745 -:105B2000FDF8FAF783FC0EA3D3E90023FAF7D2FCC1 -:105B3000FAF7E2FE184B1860184BD868FAF776FCB3 -:105B400009A3D3E90023FAF7C5FC09A3D3E900238D -:105B5000FAF7C0FCFAF7D0FE114B186010BD00BF79 -:105B60003B597E90A9E78140399D52A246DF913F83 -:105B7000000000A0F7C6B03E04000020C903683F43 -:105B8000C40D00200AE81C4100401C46F01E002005 -:105B9000901D0020000061440C1F0020B81E002052 -:105BA000101F0020AFF300802DE9F041044600688B -:105BB0000D460146FAF7FEFFD4F80480064641463A -:105BC0004046FAF7F7FF01463046FAF7EBFEA768C2 -:105BD000064639463846FAF7EDFF01463046FAF7F1 -:105BE000E1FE06F097FE00210646FBF777F970B953 -:105BF00020683146FBF792F8314628606068FBF771 -:105C00008DF831466860A068FBF788F8A860BDE8A9 -:105C1000F0812DE9F04F0C68836889B0D0F800A0BE -:105C2000D0F804800646204603938B4606F06EFDAE -:105C30000746204606F0DEFDDBF80440814620469C -:105C400006F064FD0546204606F0D4FDDBF808208A -:105C500004461046019206F059FD019A834610460B -:105C600006F0C8FD394602905846FAF7A3FF3946B8 -:105C700004900298FAF79EFF594605904846FAF7B5 -:105C800099FF029906904846FAF794FF2946079033 -:105C90005846FAF78FFF01465046FAF78BFF214628 -:105CA00083460698FAF786FF01460598FAF77AFECA -:105CB00001464046FAF77EFF01465846FAF772FE63 -:105CC000214683460498FAF775FF01460798FAF7CC -:105CD00067FE01460398FAF76DFF01465846FAF74A -:105CE00061FE3060029905F10040FAF763FF01465A -:105CF0005046FAF75FFF214683460798FAF75AFFA6 -:105D000001460498FAF74CFE01464046FAF752FF66 -:105D100001465846FAF746FE214683460598FAF7AB -:105D200049FF01460698FAF73DFE01460398FAF747 -:105D300041FF01465846FAF735FE2146706050464D -:105D4000FAF738FF2946044609F10040FAF732FF16 -:105D500001464046FAF72EFF01462046FAF722FE9A -:105D6000394604462846FAF725FF01460398FAF714 -:105D700021FF01462046FAF715FEB06009B0BDE8E4 -:105D8000F08F80EAE073A3EBE0738B4206DB002820 -:105D900001DD401A704702D0084470470020704768 -:105DA0002DE9F041524B86B01A685B6802F100425F -:105DB00003F1004301934F4B0646B3F900000092F4 -:105DC000FAF7A4FE00F10040FAF730FB46A3D3E94E -:105DD0000023FAF77FFBFAF78FFD474C0290B4F9E6 -:105DE0000000FAF793FE0390B4F90200FAF78EFE72 -:105DF0000490B4F90400FAF789FE404D0590694615 -:105E000003A8FFF706FF95F87430012B15D13C4B22 -:105E10003C4C9B7863B92368402093FBF0F0181A40 -:105E2000FAF774FE0599FAF7BDFDFBF789F82060D3 -:105E30002068402390FBF3F001E0334B1888FAF719 -:105E400065FE01460598FAF7ABFD05903046FAF776 -:105E500059FE2E490746FAF7A5FD01463846FAF7DE -:105E60005DFFDFF8B8800746D8F800400598214666 -:105E7000FAF796FD01463846FAF79CFE01462046A1 -:105E8000FAF790FD224C0746C8F800000398D4F8B2 -:105E9000008006F071FC95F86210FFF772FF404435 -:105EA00020600498D4F8048006F066FC95F862102F -:105EB000FFF767FF404460603846D4F8088006F07A -:105EC0005BFC95F86110FFF75CFF124B40441A68C9 -:105ED000A06016441E60104B1A6801321A6006B0AA -:105EE000BDE8F081AFF30080399D52A246DF913FBB -:105EF000C80D0020DA1E0020041F0020901D002085 -:105F0000BB1F0020D00D0020040000203661823C21 -:105F1000E41E0020EC0D0020F40D0020F00D002008 -:105F20002DE9F04F89B0FFF767F8022002F0BEF8C4 -:105F30009B4D9C4F002800F0B2819B48FFF716F85C -:105F4000FFF79EF9994C06462368C3EB00094846C3 -:105F5000FAF7D8FD964B1968FAF72CFE954A266099 -:105F600092F860300026039002933446B246285FD0 -:105F7000FAF7CCFD0399FAF71DFE029A0DF1140809 -:105F800048F806005AB31046FAF7C0FD01464FF034 -:105F90007E50FAF7C3FEDFF850B2024611464FF0CA -:105FA0007E500092FAF7FCFC56F80B10FAF702FE4E -:105FB0008446385FCDF804C0FAF7A8FD009A114670 -:105FC000FAF7F8FDDDF804C001466046FAF7EAFC8E -:105FD0004BF80600FAF7B4FF774A105302E0395B3A -:105FE000754AA152744A0436A15E0234062C01FBA4 -:105FF00001AA9346BBD1714A6424128804FB0AF3B8 -:1060000052436F48414693FBF2F4FFF702FE08202B -:1060100002F04CF820B16B484146FFF7FAFD07E06B -:1060200069484146FFF7F5FD67480146FFF7BCFDAB -:10603000493C664EA4B23B2CB6F8F00006D90820C5 -:10604000B6F8F24002F032F848BB53E0FAF75AFDD6 -:106050004FF07E518046FAF7A5FC01464FF07E5086 -:10606000FAF75CFE00240746DFF854A140465AF8D0 -:106070001410FAF79FFD03463BF904000193FAF769 -:1060800045FD019B01461846FAF78CFC3946FAF7A4 -:1060900091FD4AF814000234062CE5D1CFE74B4BB2 -:1060A000B3F8F200FAF72EFD80462046FAF72AFDF3 -:1060B0004FF07E51FAF776FC01464FF07E50FAF72A -:1060C0002DFE002407463F4E404656F81410FAF7BE -:1060D00071FD3F4B8246185FFAF718FD01465046A6 -:1060E000FAF760FC3946FAF765FD46F81400023409 -:1060F000062CE8D1374B324CB3F90000FAF706FD15 -:10610000A668014630464FF00107FAF70FFF00B9C5 -:106110000746314B314660685F7306F0F9FB2F4E3E -:10612000D4F808A03060206800F10047606801469C -:10613000FAF740FD514680465046FAF73BFD0146CE -:106140004046FAF72FFC06F0E5FB0146384606F01C -:10615000DFFB70603068FAF769F90FA3D3E9002319 -:10616000FAF7B8F9FAF7C8FB06F006FB1C4F3880BF -:106170007068FAF75BF908A3D3E90023FAF7AAF9E4 -:10618000FAF7BAFB06F0F8FA7880082001F08EFFE3 -:10619000144E58B30B482AE03B597E90A9E7814042 -:1061A000DC1E0020F41E0020EC1D0020C00D00208D -:1061B000101F0020901D0020041F0020040000205C -:1061C000141F00200C0E00200C0000204C19002091 -:1061D000B01E0020C40D0020BB1F0020C80D0020F1 -:1061E000080E0020DA1E0020DC0D00204048FFF7DA -:1061F000FBFB30804846FFF7D3FD3E4A92F8A630BD -:10620000002B4FD0206867680146FAF7D3FC394667 -:1062100006463846FAF7CEFC01463046FAF7C2FB8E -:10622000A468064621462046FAF7C4FC01463046DB -:10623000FAF7B8FB06F06EFB01462046FAF76EFD52 -:106240002D490646FAF75EFE2C4C10B10023238040 -:1062500028E0304606F00CFB294B1968FAF7AAFC37 -:1062600006F08AFAB0F5617FA8BF4FF46170FAF7C3 -:10627000CBF81DA3D3E90023FAF756FAFAF73CFB53 -:1062800006F0B8FA1B4B064693F8A600FAF73EFC58 -:106290003146FAF78FFC06F06FFA208002E0388072 -:1062A0007880B880174B5B79012B174B06D02A8872 -:1062B0001A806A885A80AA889A8010E0134AB5F931 -:1062C0000410B2F9000001EB4001032091FBF0F152 -:1062D00089B211802A8899801A806A885A8009B008 -:1062E000BDE8F08FAFF30080A2EB0FE5DD1696401E -:1062F0000C000020901D00208FC2753CFA0D00207C -:106300000C1F00204C190020FC0D0020F80D00206F -:1063100010B5054C00202188FBF752FE6188012052 -:10632000BDE81040FBF74CBE1800002010B5094C2A -:1063300020600948016009490A60094A1360094A56 -:10634000029B1360084A039B1360084A049B136076 -:1063500010BD00BF180E0020F40E0020F80E002023 -:10636000240E0020200E00202C0E0020F00E002015 -:106370000A4B1A6802EBC002D379FF2B07D00849F9 -:106380000978994203D9074A32F8130004E0072834 -:10639000D4BF908840F2DC5000B27047180E002045 -:1063A0001020002014200020054B1B6803EBC000C8 -:1063B00090F9063019420CBF01204FF0FF307047B2 -:1063C000180E002010B500244FF48040FDF7EAF8C5 -:1063D00008B1054B00E0054B1B68054A9B88A3529A -:1063E0000234182CF0D110BDF40E0020F80E00205D -:1063F000381F00202DE9F0413B4BDFF80481C40039 -:10640000187008EB04035B78384E054620200F46D1 -:106410003360FDF7C7F8424608B101233360162DFB -:106420001AD1002438590021FAF758FD28B14FF449 -:106430008040FDF7B7F848BB24E02D4E3B192644B9 -:106440000FCB86E80F002B4B10341A78C02C02F1CA -:1064500001021A70E6D1EAE7144412F83570254BB0 -:10646000D4F804E01F70BEF1000FE0D00024BC425D -:10647000DDDA1F4E23011E4473440FCB013486E83E -:106480000F00F4E7082D1C4B24D125E0194B1F7891 -:10649000012FF7D9194C0026BE4204F11004F1DA9D -:1064A00054F8100C4FF07C51FAF784FB4FF07C51FC -:1064B00044F8100C54F8140CFAF77CFB4FF07C51A4 -:1064C00044F8140C54F80C0CFAF774FB013644F839 -:1064D0000C0CE1E70E2D01D1012200E000221A741C -:1064E000BDE8F041FFF76EBF1C0E0020FC0E00203F -:1064F000300E00202A0E0020BB1F0020380E002086 -:10650000B8F300082DE9F0418C46461C0023002218 -:106510004CF803201033C02BF9D10B4B03EBC60210 -:10652000576898466FB1002418F836309C4208DA54 -:1065300023010CEB03053B440FCB013485E80F002E -:10654000F2E7BDE8F08100BFB8F30008284B10B5B2 -:106550001B68002B4AD0274B1B78013B142B3DD8DE -:10656000DFE803F00B3C3C24403C3C1C3C3C3C3C06 -:106570003C2C3C3C3C3C3C242C001F4B1B685B7877 -:1065800033B11E4B00205989BDE81040FBF718BD00 -:106590001B4B98780028F4D10146F5E7174C0020F2 -:1065A000E188FBF70DFD01202189EDE7134C002068 -:1065B0002189FBF705FD01206189E5E70F4C0020EB -:1065C000E188FBF7FDFC01202189FBF7F9FC0220A3 -:1065D0006189FBF7F5FC0320A189D5E72020FCF7B2 -:1065E000E1FF18B1BDE81040FFF792BE10BD00BF3B -:1065F000FC0E00201C0E0020240E0020180000209D -:10660000BB1F002010B50023D8B25C1C054B1B78C3 -:10661000834206D9044B33F81010FBF7C5FC234620 -:10662000F2E710BD2A0E0020201F0020064B1A782A -:106630000023D9B2914204D2044921F81300013356 -:10664000F7E7FFF7DFBF00BF2A0E0020201F002062 -:106650002DE9F74FA94E3378032B0FD9A84BA94C3E -:10666000B3F904206FF06301002AB8BF5242891ABF -:10667000B4F904006432FDF7FDF9A0803778012FEA -:106680001ED8A14AA14C13789046013B142B00F26E -:10669000D281DFE813F09100D001D00168009F00A3 -:1066A000D001D0012901D001D001D001D001D00109 -:1066B000BD00D001D001D001D001D0019201A901CB -:1066C0008F4B9349B3F806A08E4B0968B3F802804C -:1066D000B3F80090B3F904B08E4C01910025BD428F -:1066E00004F11004CDD20FFA8AF0FAF70FFA54F839 -:1066F000101CFAF75FFA03460FFA88F00093FAF7D6 -:1067000005FA54F8081CFAF755FA009B014618469A -:10671000FAF748F903460FFA89F00093FAF7F6F909 -:1067200054F80C1CFAF746FA009B01461846FAF793 -:1067300039F9019A034692F90000009340420BFB9D -:1067400000F0FAF7E3F954F8041CFAF733FA009B67 -:1067500001461846FAF726F9FAF7F2FB6E4B23F8D2 -:1067600015000135BBE702210420FFF71DFE654D32 -:106770000121AF8878431FFA80F90420FFF714FE47 -:106780006D8800FB05901FFA80F90420FFF7F0FDEB -:106790004844208102210520FFF706FE78430121AD -:1067A00087B20520FFF700FE00FB057087B20520C9 -:1067B000FFF7DEFD38440BE005200121FFF7F4FD73 -:1067C000504B9D88684385B20520FFF7D1FD2844D2 -:1067D000608130E1514B00201D68FFF7C9FDDFF8F3 -:1067E000549195F90630B9F902203227534393FBAF -:1067F000F7F3184420800120FFF7BAFD95F90E3019 -:10680000B9F90020534393FBF7F73844608012E155 -:10681000434B9A789946434B1B6812B99B88E38196 -:1068200007E0374A1988B2F906005A88FDF722F9BD -:10683000E081394BE2893C4F1A803B68374D1B7829 -:1068400043B30220FFF794FD2B68B3F91010B3F99E -:106850001220FDF70FF9354B1B685989344B081A84 -:106860001A8800B20FFA82FE864503DA386800788B -:10687000024403E003DD38680078121A1A802A689F -:10688000B3F9003092F916205343642293FBF2F3DC -:106890001944A18099F80A3063B1194B1A88D5F8C8 -:1068A00000A0E28022819A88184F62815B880325CC -:1068B000A38101E0134BF1E70AEBC50393F906301E -:1068C000B7F90690284609FB03F9642399FBF3F90D -:1068D000A7F80690FFF74CFD01354844072DF880D6 -:1068E00007F10207E8D1A6E00D4B9A781F460D4B41 -:1068F0001B680ABB9B88E38126E000BF2A0E0020AC -:10690000E21F0020CA1E00201C0E002018000020DC -:10691000240E0020300E0020201F0020180E002022 -:10692000BB1F0020F80E0020200E00202C0E00209F -:10693000280E0020080E0020B54A1988B2F906007A -:106940005A88FDF797F8E081B24BE289B24D1A8080 -:10695000BB7A032001211BB1FFF726FDAC4F02E0FB -:10696000FFF722FDAD4FB7F80290022100FB09F0BE -:106970001FFA80FA0320FFF717FD3F88012100FB73 -:1069800007A0E8800420FFF70FFD00FB09F00221BB -:106990001FFA80F90420FFF707FD00FB079028810C -:1069A0000320FFF7E5FCE3881844E0800420FFF7AC -:1069B000DFFC2389184420813DE001210420FFF7FA -:1069C000F3FC964D6F88784387B204202781FFF748 -:1069D000CFFC3844208101210520FFF7E5FC2D88FC -:1069E000684385B26581EFE68C4B0325B3F804A0BC -:1069F000994628460221FFF7D7FC00FB0AF0012147 -:106A000087B22846FFF7D0FCC5F106035B0839F8CA -:106A1000133000FB037087B224F815702846FFF787 -:106A2000A7FC384424F815000135072DE1D1784B37 -:106A3000DA88784B1A802020FCF7B4FD784F0028C4 -:106A400049D00020FFF794FC208081460120FFF709 -:106A50008FFC744B704D1B7A6080002B3BD0724BC7 -:106A60001B681B7813F0020F704B1ED0D7F800E0A4 -:106A7000B3F900109EF90E209EF906E0B3F902303A -:106A80004A43CEF1000E03FB0EF3322192FBF1F2EA -:106A90006FF0310E92B293FBFEFE9644F14493FBED -:106AA000F1F1A5F800900A4413E03968B3F902E067 -:106AB00091F90620B3F900300EFB02FE32229EFB54 -:106AC000F2FEF144A5F8009091F90E104B4393FBB0 -:106AD000F2F21044688000253B68605F03EB85029A -:106AE00033F92510B2F90220FCF7C4FF60530235D8 -:106AF000102DF1D14C4B1B681B785B0704D4454D1E -:106B000032782F8801231CE098F800300E2B0AD031 -:106B1000082B08D0464A02EBC3035B78002B14BF56 -:106B20000225002500E004250024424B601903EBF8 -:106B30004403C0B219890134FBF742FA042CF4D1A2 -:106B4000DDE7934208D235F913103FB2B942A8BF2E -:106B50000F46BFB20133F4E70024A14633789945CC -:106B600074D2DFF8E0803AB2D8F800305B889A42FD -:106B700003DD2A5BDB1B13442B534FF48040FCF7EF -:106B800011FDDFF8C4B02B4BC0B1B3F90620DBF820 -:106B900000305B899A42284B06DD1A68D8F800302D -:106BA0005188285F5A8805E0D8F800201B68918832 -:106BB000285F1A88FCF75EFF28531FE0D8F80020F2 -:106BC000285F118852880093FCF754FF009B2853DC -:106BD000B3F90620DBF80030DFF868A09B8905EBED -:106BE00004089A420ADA1020FCF7DCFCDAF80030DC -:106BF00008B91B8800E09B88A8F800300F4B9B78F1 -:106C000013B90F4BE35A2B5309F101090234A5E7DD -:106C1000E21F0020201F002018000020CA1E0020B4 -:106C2000180E0020CC1F0020F00E0020080E0020BF -:106C3000B8F3000814200020F40E0020BB1F002031 -:106C4000381F0020F80E00202C0E002003B0BDE8F5 -:106C5000F08F00BF024B1868003018BF012070474A -:106C6000FC0E002044F25063984203DDA0F50C4076 -:106C7000A0387047034B9842BCBF00F50C40A030D1 -:106C8000704700BFB0B9FFFF10B5044C002320705F -:106C90002361FEF70FFB606110BD00BF34110020BF -:106CA00010B5F9F733FF00210446FAF73FF908B1B0 -:106CB000204601E004F100400549FAF72FF80549A4 -:106CC000F9F778FF05F022FD034B186010BD00BFF7 -:106CD0008096184B35FA8E3C28000020F8B5101A23 -:106CE0000C461F46F9F712FF0546381BF9F70EFF51 -:106CF000174B079E1968F9F75DFF29460446284699 -:106D0000F9F758FF214607462046F9F753FF014699 -:106D10003846F9F747FE05F0FDFD0E49F9F74AFF41 -:106D2000FAF734F9069B2146186005F1004005F09A -:106D3000EFFD0949F9F73EFF0849F9F733FEFAF785 -:106D4000FFF80028BCBF00F50C40A0303060F8BD53 -:106D5000280000202C7D8E3FA00CB34500A00C46DF -:106D6000F8B51D4614460E46F9F7D0FE6968F9F7E6 -:106D700021FF3146F9F71EFF2168F9F713FE206065 -:106D8000FAF7DEF8ED68074605F10040FAF7D8F8A3 -:106D900006462846FAF7D4F8314602463846FCF74C -:106DA00069FEF9F7B3FE2060FAF7CAF8F8BD0000F3 -:106DB00030B5002213460E49CC5C0D469CB12E2CFA -:106DC00004D1013378B11D4400242C540A246243B9 -:106DD000C95CA1F13004092C9CBF303A52180E2B2B -:106DE00003D80133E7E7104630BD002030BD00BFB7 -:106DF0007C100020014B1860704700BF5811002024 -:106E0000F8B52B4B2B4C1B7813B1012B0AD04CE05F -:106E10006278294B03EB0213284A59681068FEF781 -:106E200017FA3FE0254D2868FEF717FA2E4600288E -:106E30003BD02378012B1ED1FEF73CFA636906464E -:106E4000C31A632B33D92369042B12D81A4F28682D -:106E500007EB03135968FEF7FBF96378286807EB23 -:106E60000317B968FEF7DFF923696661013323610F -:106E70001BE0022017E023693BB962780E4B2868BB -:106E800003EB02135968FEF7E3F92369094D8B2BD5 -:106E900008D80B4A3068D15CFEF7C0F92B69013382 -:106EA0002B6102E00320FFF7EFFE00236360F8BDD3 -:106EB000B01000203411002068F800088C10002069 -:106EC000DAF7000810B50B4CE37A8BB10A4B1B784C -:106ED000042B0DD9094A0A4B1068526818605A6091 -:106EE000FFF7DEFE074B1A88074B1A800123237336 -:106EF00010BD00BFBB1F0020A81F0020901F002056 -:106F0000741F0020DA1E0020A210002000000000E4 -:106F10002DE9F04F994B8BB01B68BBB9984C237887 -:106F2000013B032B00F2CB85DFE813F08F058F05C3 -:106F3000A90592052068FEF786F9924B04461B7856 -:106F4000012B00F0DD8008D3022B06D08B4C20688B -:106F5000FEF774F90028EDD1E0E7242C07D18A4A26 -:106F600000231370894A1370894A1370C4E02C2CD3 -:106F700002D02A2C40F08380844E864B3278824D9A -:106F8000002098542A788449B2B90A701A78472A9E -:106F900068D15A78502A65D19A78472A40F07E8580 -:106FA000DA78472A40F07A851A79412A40F07685C6 -:106FB00001220A7000F072BD097801293AD1022A33 -:106FC00005D1184601F018F8744B18604AE0032AFE -:106FD00007D11B78532B45D1704B1A6852421A6067 -:106FE00040E0042A05D1184601F006F86B4B5860C2 -:106FF00038E0052A07D11B78572B33D1674B5A68E5 -:1070000052425A602EE0062A07D11A78644B302A81 -:1070100094BF00220122DA7224E0072A04D1FFF78C -:10702000C7FE604B18701DE0092A1BD1FFF7C0FE98 -:107030005D4B16E0022915D1072A0CD10120FFF77C -:10704000B7FE41F2184358434FF47A72B0FBF2F3A3 -:10705000564A138006E0082A04D10120FFF7A8FE53 -:10706000534B18802B782A2C03F101032B704FF01F -:107070000003337037D14F4B01221A703CE00D2CC6 -:107080004C4B01D00A2C24D11A78F2B1414908782E -:107090004978A0F13002D2B2092A84BFA0F13702A8 -:1070A000D2B202F00F021001A1F13002D2B2092ACD -:1070B00084BFA1F13702D2B2354902F00F02024477 -:1070C0000978D2B28C1A62426241002119707AB9F1 -:1070D00012E02E490A780E2A03D8501C08702D4958 -:1070E0008C541B7843B92A4B1A7854401C7003E027 -:1070F000294B1B78012B00D0002303F0010358E13A -:107100002D4B00221978082900F25281DFE801F0A6 -:107110000A05111927607D96A100622801D102227B -:1071200005E01A70B52C40F043811A7801321A70CC -:107130003EE103221A70214B1870214B1870214B2D -:107140000BE01F4904221A701E4B0A78187822445B -:10715000D2B20A7002441A701B4B1C7028E1184905 -:1071600005221A70174B0A7818782244D2B20A7096 -:1071700002441A70154B1C801AE100BF8C100020CD -:1071800034110020B010002024110020C010002075 -:107190008B1000207C100020A4100020901F0020E5 -:1071A000BB1F0020A81F0020621F0020661F0020B8 -:1071B00068100020310F0020300F00202C1100201B -:1071C0009D100020A0100020290F00209E100020FC -:1071D000624906221A70624B0A7818782244D2B2A9 -:1071E0000A7002441A705F4B1A8802EB0424A4B29E -:1071F000B4F5007F01D81C8003E000221A805A4BAE -:107200001A705A4A00231380D3E05448544A017834 -:1072100015782144C9B201702944117053490A8874 -:10722000C72A9CBF52488454013292B20A804D4909 -:107230000988914240F0BC80072278E708221A7042 -:10724000464B1B78834200F0B380474A00231370FB -:10725000AFE01A70424B1B78834240F0A980454B47 -:107260001B78062B39D004D8022B12D0032B24D044 -:107270009EE0122B44D0302B40F09A803C4B1A7980 -:107280003D4B102A88BF10221A701978384A002303 -:1072900044E0374B394A59685160996811601A695E -:1072A0004FF47A7392FBF3F2354B1A80354B1A7810 -:1072B000354BDA720122354B20E02D4A537913F019 -:1072C000010303D01379D81E434243412D4A137062 -:1072D000002B38D12C4AD37235E0254BDA7A12F0E4 -:1072E000010203D09A7AD11E4A424A4125490A70C6 -:1072F0000AB92549CA7293F82F20254B1A7022E04B -:107300001B4B24495A690A809A6942F2107392FB16 -:10731000F3F2214B1A800122204BEFE78B4202F15E -:107320000C0210DA12F8044C1D481C5412F8034CDD -:107330001C481C5412F8014C1B481C5414781B4860 -:107340001C540133EAE711490B788BB3134B1A78BD -:1073500072B300221A700A7001232AE09D100020E7 -:10736000A01000209E100020300F002026110020C9 -:10737000A00F0020290F0020A91F0020901F00202F -:10738000621F002054110020BB1F00209C10002011 -:10739000A81F0020661F0020681000202D1100206B -:1073A000501F00207E1F0020981F0020AA1F0020D1 -:1073B0000023002B3FF4CAAD8B4CA368E360FDF7BC -:1073C00079FFA060202000F07BFE884B884C1A7863 -:1073D000012A0CBF002201221A70E37A002B3FF42D -:1073E000B5AD844B1B78042B7FF6B0ADA37803B901 -:1073F0002373227B12B90BB1FFF764FD7E4B4FF074 -:10740000050E1A787D4D013292FBFEFE0EEB8E0EBC -:10741000CEEB020E83F800E0794B1B780593794B95 -:1074200003EB8E0E0023784A78499858DFF81C82C7 -:10743000774E585090FBF8F19951764EDFF8109244 -:1074400006FB010003EB830A5EF80A6053F809703B -:1074500042F2107CBF1B90FBFCFC05264EF80A0094 -:10746000384443F8090090FBF6F008FB01016A4834 -:107470001FFA8CFC1950059803EB020B012825F824 -:1074800002CF164606D1ACF1020CBCF5797F98BF4D -:10749000CBF800100433082BC5D1FDF70BFF5F4F6D -:1074A0005F4D3B68C01AF9F72DFB5E49F9F736FCD2 -:1074B0002860FDF7FFFE38602F684FF07E51384698 -:1074C000F9F716FD08B94FF07E5706AA2F60564B04 -:1074D000009207AA019296E803000CCBFFF7FEFB8F -:1074E000069A64235149B2FBF3F207980A80504A86 -:1074F00090FBF3F31380237B0BB90B801380DFF831 -:1075000054A14C4F9AF80030002B36D029684FF028 -:107510007E50F9F703FC3B6880463068C01AF9F7E3 -:10752000F5FA4146F9F746FBF9F70AFD7B681FFAC1 -:1075300080FB70680FFA8BFBC01AF9F7E7FA3E4B35 -:107540001968F9F737FB4146F9F734FBF9F7F8FC0E -:107550003A4B00B2B3F902204FF0020E8118B3F992 -:10756000002037485A4491FBFEF192FBFEF289B2AB -:1075700092B24180028059801A8001238AF800303B -:1075800071683068237A7960386023B9184BDB79E9 -:10759000002B3FF4DBACDFF8C0B0DFF8C080294C33 -:1075A000CDF800B0CDF8048094E80C00FFF796FB0E -:1075B00073686068244FC01AF9F7A8FA1E4BBA46E0 -:1075C0001968F9F7F7FAF9F7BBFC226833687860B5 -:1075D000D31A3B600A4B93F90030012B40D0022BA9 -:1075E00000F0D980B2E400BF341100206211002005 -:1075F000BB1F0020A81F002070110020CA1000200F -:10760000280F0020000F0020901F00204C110020A8 -:10761000B8100020806967FF340F0020301100206F -:107620005C11002000007A44741F0020701F0020AD -:107630007C1F00209010002028000020E410002073 -:1076400010110020A81000206811002080969800DA -:107650001C11002071110020C4100020E010002037 -:107660007D4D00245AF81460DFF830923046F9F767 -:107670004DFA7A4B7A4F1968F9F79CFAF9F760FCE2 -:1076800034F809B0774BCBEB00001FFA80FB24F8ED -:1076900003B00FFA8BFB5846F9F738FA3968F9F757 -:1076A00089FAF9F74DFC704A1FFA80F811680BEB64 -:1076B00006002A463B46FFF753FB6C4EBF686A4BF9 -:1076C00040445AF814B0A053686804971F68C0EB90 -:1076D0000B00F9F71BFA3946F9F720FB644B2861D8 -:1076E0001B6884469878D5F80880CDF80CC0F9F767 -:1076F00009FAF8F79BFE56A3D3E90023F8F7EAFE50 -:107700000B4602465B490020F9F70EF8F9F7F4F84A -:107710003946F9F747F901463846F9F7FFFADDF837 -:107720000CC0074641466046F9F73AF9014638462B -:10773000F9F740FA01464046F9F734F9C5F804B0C4 -:1077400001462861A8600498F9F734FAF9F7F8FBC4 -:1077500049494FF4FA62FCF78DF934F8093047498A -:1077600031339BB2622B335B98BF0020184480B248 -:10777000305340F6B83200B2FCF77CF90A2262437B -:10778000305355F8141B3E4B0234042CD1507FF477 -:1077900069AFFFF7DBBB364BDBF800701B68394C79 -:1077A000B3F908607B089E4228BF1E46B4F80090DB -:1077B000B6B232B20FFA89F39A4208DD324928682C -:1077C000F9F7F8F9F9F7BCFB484486B226802F4B4D -:1077D000D8F800401B682E4DC3EB04084046FFF765 -:1077E00041FA0028D8BF404241F293139842CCBFDF -:1077F00000200120002853D04046F9F787F9254999 -:10780000F9F7D8F904F0F6FF80463846F9F77AF927 -:1078100001464046F9F7CEF9F9F792FB1E4B80B2CC -:107820001880164900B240F6B832FCF723F948F642 -:10783000A0432044984203DDA0F50C40A03804E0AA -:107840000028BCBF00F50C40A030286029E000BF34 -:10785000182D4454FB211940E81000206C10002022 -:10786000D0100020141100205C110020C81000204E -:10787000581100200000F03F30F8FFFF48F4FFFFF0 -:10788000500F0020601100200000C8422811002085 -:107890002C0F0020D30237393C0F0020101100209C -:1078A0002C6028688A4DC0F50C502830F9F72EF965 -:1078B0008849F9F77FF9044604F028FF099020462B -:1078C00004F098FF0024089030B2F9F71FF908ABD4 -:1078D00053F81410F9F76EF97F4B0746185FF9F764 -:1078E00015F901463846F9F75BF8F9F729FBDFF897 -:1078F0002C9280B24FF47A7224F80900774900B2D2 -:10790000FCF7B8F880B20FFA80FA754F24F8090036 -:107910005046F9F7FBF83968F9F74CF9F9F710FB1D -:10792000DFF8FC8180B22A463B46D8F8001004906C -:107930005046FFF715FABF68844634F909A0686815 -:107940000597D8F80070C0EB0A00CDF80CC0F9F725 -:10795000DDF83946F9F7E2F9DFF8C8912861D9F87E -:10796000003083469878F9F7CDF8F8F75FFD56A315 -:10797000D3E90023F8F7AEFD0B4602465949002033 -:10798000F8F7D2FEF8F7B8FF3946F9F70BF80146D9 -:107990003846F9F7C3F9D5F80880074641465846F6 -:1079A000F8F7FEFF01463846F9F704F9014640466C -:1079B000F8F7F8FFDDF80CC0049F01462861A860C5 -:1079C000C5F804A005986744F9F7F4F8F9F7B8FA90 -:1079D0003844454F80B2E053444940F6B83200B2D3 -:1079E000FCF748F80A226243385355F8141B404B01 -:1079F0000234042CD1507FF467AFD9F800301A79E3 -:107A000032B13C4A1168642291FBF2F13A4A11808A -:107A10003A4A1B8812689A420ED9394B1868394B7A -:107A20001B68C01AFFF71EF942F210730028B8BF96 -:107A3000404298427FF78AAA334B01221A70334B97 -:107A40001A882D4B1A80FFF781BAFFF7D9F936E073 -:107A5000636805220133636063780133DBB2B3FBF3 -:107A6000F2F202EB82029B1A6370FDF723FC284AB4 -:107A700000231370274AA060D37201200BE0FDF7AA -:107A800019FCA36840F6C412C01A904217D92020EE -:107A900000F01EFB0420FFF7F7F810E09B781E4A69 -:107AA000522B7FF4DFAAD3784D2B7FF4DBAA137916 -:107AB000432B7FF4D7AA02230B70FFF7D3BA0BB086 -:107AC000BDE8F08FAFF30080182D4454FB2119401E -:107AD000500F0020D30237391011002018FCFFFF8F -:107AE000400F00200000F03FC810002048F4FFFFC6 -:107AF000E81000202C0F0020C81E0020C410002019 -:107B0000E010002028110020280F0020A2100020E3 -:107B1000A81F0020BB1F00207C1000201411002093 -:107B20005C1100205811002010B500231A460E49A0 -:107B3000002050520D490E4C50520E495052002117 -:107B400019511C446060A1600B4C023219511C4455 -:107B50006060A160094C042A19511C446060A16056 -:107B600003F11403E3D110BDB210002098100020DF -:107B7000780F0020C8100020E8100020500F0020CF -:107B800070B504460079F8F7BDFF1E49F9F7C6F84D -:107B90001D4D1E4E2860A07BF8F7B4FF1949F9F778 -:107BA000BDF8EE6068606079F8F7ACFF1849F9F746 -:107BB000B5F8184D2860E07BF8F7A4FF1149F9F7F4 -:107BC000ADF86860607EF8F79DFF1349F9F7A6F8F5 -:107BD000EE60A860A079F8F795FF0D49F9F79EF8D7 -:107BE0000E4D2860207CF8F78DFF0649F9F796F8CE -:107BF0006860A07EF8F786FF0749F9F78FF8EE6016 -:107C0000A86070BD0000C8426C1000200000FA445B -:107C100000002041D010002000007A44400F0020D6 -:107C20002DE9F7439946214B214C18600025C36884 -:107C30006570204E06EB05104068B046984206D0AD -:107C40000135EDB2042DF4D90023637000E06570B6 -:107C5000194B1A4E002031701A60FFF715F8FDF726 -:107C600029FB33780025AB42A06048460CBF0127B2 -:107C700003276560FFF784FF66783B4608EB06162E -:107C8000009510202946726801F06EFD0C4B1860BB -:107C900030B94FF4807003B0BDE8F043FBF72ABE63 -:107CA000012003B0BDE8F043FEF7EEBF64110020F1 -:107CB0003411002068F8000858110020B01000208E -:107CC0008C10002073B51D4B1D78032D31D1202061 -:107CD00001F01EFC1A4E044638B101F0C7FD3368AE -:107CE00020461969FDF7B4FA09E03368009021468F -:107CF0001A6920202B4601F037FD0446D8B1114DFA -:107D00002868FDF79BFA30B12868FDF79CFA014618 -:107D10002046FDF783FA2046FDF790FA0028EED0C2 -:107D200020462D68FDF78FFA01462846FDF776FAC2 -:107D3000E5E7022000E0284602B070BD34110020C3 -:107D4000641100208C100020F7B50368174C184D03 -:107D500023600B68174E63600068FEF7A1FF95E88B -:107D60000300154B0196009394E80C00FEF7B6FF54 -:107D70003668124B60681E606B68114FC01AF8F7C6 -:107D8000C5FE104B1968F8F715FFF9F7D9F8226806 -:107D90002B687860D31A3B600B4B1E600B4B1B6843 -:107DA000DA880B4B1A8003B0F0BD00BFA81000208A -:107DB000901F0020E0100020C41000202C0F002095 -:107DC00068110020280000202811002058110020F0 -:107DD000601100202DE9F84F484BDFF834A1B3F9CA -:107DE0000000F8F793FE4649F8F7E4FE044604F075 -:107DF00001FD0746204604F089FCDAF8003006460B -:107E000093F80390DFF80C813E4DB9F1000F43D099 -:107E10003D4CB8F90200B4F802B00FFA8BF3C01A67 -:107E2000FEF720FFC9F100014A46FBF723FEB4F834 -:107E3000009058446080B8F900000FFA89F3C01A26 -:107E4000FEF710FFDAF80030DA785142FBF712FE45 -:107E500048441FFA80F9A4F80090B4F90200F8F73A -:107E600055FE80460FFA89F0F8F750FE3146044679 -:107E70004046F8F79FFE394681462046F8F79AFEBD -:107E800001464846F8F78CFD2049F8F747FFF9F717 -:107E900057F8288040461DE0B8F90200F8F736FE92 -:107EA0008146B8F90000F8F731FE314604464846ED -:107EB000F8F780FE394680462046F8F77BFE0146FB -:107EC0004046F8F76DFD1149F8F728FFF9F738F843 -:107ED000288048463946F8F76DFE31460746204669 -:107EE000F8F768FE01463846F8F75CFD0749F8F7F1 -:107EF00015FFF9F725F86880BDE8F88FDA1E002035 -:107F000035FA8E3CB210002098100020000020416D -:107F100058110020C810002038B5244CE37A2546BB -:107F2000002B3CD0224B1B78042B38D9214B9A7A5A -:107F30007AB1E379002B37D101221F48E2711F4A41 -:107F4000011D13702372FFF7FFFE1D4B02221A70F2 -:107F500038BDDB7AE271BBB11A4B1B68588900F05F -:107F6000C5F888B1237AFBB9144A17481370174B28 -:107F700001251A685B68011D436025720260FFF7E6 -:107F8000E3FE0F4B1D7038BD00232B720B4B1A788C -:107F900052B901221A70BDE83840FFF7C5BD084A42 -:107FA0000023EB712B72137038BD00BFBB1F002084 -:107FB000A81F0020CC1F0020741F00202C000020D0 -:107FC000280F002058110020681F0020901F00205B -:107FD000074B1A68821A002A08DB064A1278042A1C -:107FE00004D900F5123000F5F8701860704700BF32 -:107FF00018110020A81F0020294BF0B51D6802466B -:1080000000F1100716781446AB195978013201F0C7 -:10801000040101F0FF0369B1BA42F3D10020F0BDC1 -:108020001BB103EB83035B00DBB210F8012B303A8A -:108030001344DBB2221A022AF2DC002184420AD95C -:1080400019B101EB81014900C9B210F8012B303A96 -:108050001144C9B2F2E72E2E14D1013404200022BB -:10806000267802EB8202AF197F7852007F0792B226 -:1080700003D5303A3244013492B2013810F0FF0097 -:10808000EED100E00022074806244143642000FBB3 -:1080900002120548B2FBF4F200FB0320F0BD00BF62 -:1080A000A001002040420F0080969800034B1B68FF -:1080B00018420CBF00200120704700BF741100203F -:1080C000024B1A6810431860704700BF74110020FB -:1080D000024B1A6822EA00001860704774110020F1 -:1080E000014B1868704700BF74110020094BB3F9A9 -:1080F0000020002AB8BF5242824209DAB3F90230A6 -:10810000002BB8BF5B428342ACBF00200120704708 -:1081100000207047E21F002010B54478007800234B -:1081200003FB03F11939614301F6C411594341437B -:1081300040F6C41291FBF2F1034A22F81310013306 -:10814000072BEDD110BD00BF022000202DE9F04724 -:108150008278C6781E4BC2F1640802EB820C54424E -:108160005FFA88F84FEA4C0CC6F16409A4B203F137 -:108170001807A5B228B2002804DC002D14BF15464C -:10818000012500E0454600FB00FA6D430AFB06FAB4 -:108190009AFBF5F54D4468434FF00A0A90FBFAF05C -:1081A000604480B258800D88B1F802A000B2C5EBDF -:1081B0000A0A00FB0AF04FF47A7A90FBFAF00544C1 -:1081C00023F8025F0A34BB42A4B2D2D1BDE8F087E3 -:1081D000E81F0020014B1860704700BF001200200C -:1081E000074B1B681B7A032B09D8DFE803F0020258 -:1081F000040600F0F3BB00F037BA00F01BBB704779 -:108200000012002008B5037A032B12D8DFE803F030 -:108210000202070C0A490B4A00F0E8FB08E0084993 -:10822000084A00F029FA03E00549064A00F00AFB73 -:1082300028B90820FBF75EFB024B00221A6008BD3C -:1082400010200020F8110020174B10B518600446CC -:1082500000236089154A98520233242BF9D1144B1C -:1082600008201960FBF79EF910B12046FFF7CAFFFE -:108270004FF48030FBF796F920B120460D490E4AA5 -:1082800000F09AF90120FBF78DF928B109480A4955 -:10829000BDE8104000F09EB94FF40040FBF782F9B2 -:1082A0000028F3D110BD00BF0012002014200020D0 -:1082B000F411002010200020F8110020037A032B75 -:1082C00009D8DFE803F00202040600F0C9BB00F0A1 -:1082D00001BA00F0D7BA00207047000010B5104C6A -:1082E000002308202370FBF75DF920B10D4B1868BF -:1082F000FFF7E4FF20704FF48030FBF753F910B123 -:1083000000F050F9207023784BB14FF40070FBF768 -:1083100049F920B1044B1B681B681B68984710BDC6 -:10832000FC11002000120020F4110020054B1B78E6 -:108330002BB9054B1B68C01AC043C00F7047012002 -:10834000704700BFFC110020041200200E4A0F4BA2 -:10835000127802F0030202EB800223F8121003EB02 -:10836000C00233F8301053880B449188D2880B44F4 -:108370001344074A9BB222F810301BB2042293FB2D -:10838000F2F080B2704700BF7811002092110020F7 -:108390007A1100202DE9F04740F20120FBF702F9A5 -:1083A00028B1F9F7E9FE8246F9F7F2FE01E04FF055 -:1083B000010A0026234BF4B21B78A34240D9224B7A -:1083C000224F1B68DFF88C802BB9D8F800305B890E -:1083D00027F8143032E0D8F80020072C94BF12F8A8 -:1083E0000490A14617484946984705464FF4007047 -:1083F000FBF7D8F848B1BAF1000F06D0144B484645 -:108400001B6829461B68DB699847A5F2EE2240F2FB -:10841000DC5392B29A4288BFD8F8003048F201008B -:1084200088BF5D89FBF7BEF810B927F8145005E046 -:1084300020462946FFF78AFF27F814000136B9E7DE -:10844000BDE8F08710200020F81100201420002043 -:10845000F41100200012002010B5064C237843B11F -:10846000054B1B681B681B689847FFF793FF0023A9 -:10847000237010BDFC110020F4110020024B1A786B -:1084800001321A70FFF786BF7811002008B500F599 -:108490009C400D4B203018604FF40070FBF782F8C1 -:1084A00020B10A4B1B681B681B69984748F2010002 -:1084B000FBF778F818B9BDE80840FFF7CDBFBDE875 -:1084C0000840FFF7DBBF00BF04120020F4110020BA -:1084D000F8B505460F46441E14F8011F49B1054E74 -:1084E000304605F0EBFF0028F6D0861B631BBB551A -:1084F000F2E7F8BDB8F8000810B51F4B1A681C4623 -:10850000127C3AB123681B7C5BB11C4A013B32F8F8 -:1085100013001BE04FF40030FBF744F80028F1D1C2 -:1085200010BD4FF40030FBF73DF878B1F9F7F6FDD8 -:10853000114B80B21B685B7C012B07D103B2B3F5F2 -:108540007A7FC8BF002000F57A7080B200B24FF485 -:108550007A720021A0F57A70FBF78CFAF8F7D6FA58 -:108560000749F8F7DBFB0749F8F724FBF8F70EFD9E -:10857000054B188010BD00BF001200201420002001 -:1085800000007A4400C07F4412200020014B33F8E1 -:108590001100704714200020014B01221A7070470F -:1085A00008120020034B187810B100221A70012025 -:1085B000704700BF0812002008230B700AB1024B5D -:1085C00013600120704700BF8D8500080846F9F749 -:1085D0008BBE0000084B10B50B6004464FF4004002 -:1085E000FAF7E0FF08B1082323700120FAF7DAFF59 -:1085F00008B10C23237010BDCD850008034B53F840 -:108600002100400800F5777080B2704714120020F6 -:1086100038B50446FCF734FE0F4B40F6C4111A6817 -:108620001860821A8A420D4A84BF002111701378A3 -:108630000BB90F2C0FD10A48002101704BB1094D25 -:10864000182B1D4405F8014C03D101231170037050 -:1086500038BD0133137038BD0C12002010120020F9 -:108660001112002044120020024B43608360032358 -:1086700043737047A0860100F7B500250746052320 -:108680000E4614460E49009508200E4A01F06CF87B -:1086900079890D4BA1F57771186049002B460B4A7B -:1086A00099500433302BFAD10CB1094B23600030C0 -:1086B0004FF00C0318BF0120337003B0F0BD00BFB2 -:1086C00011860008A086010060120020141200200C -:1086D000FD850008344B10B51A780AB9002010BD8A -:1086E00000221A70314B9A7D1207F7D45878197806 -:1086F0002F4A00F0070441EA04211160997801F043 -:108700003F04640144EAD0005060D878800040EA19 -:108710009110197901F0010440EA842090605879A1 -:1087200000F00F04E40144EA5101D160997901F0AD -:108730007F04240144EA10101061D879400040EA17 -:10874000D111187A00F0030441EA44215161597AA9 -:1087500001F01F04A40144EA90009061987AC000DF -:1087600040EA5111187BD161D97A00F0070441EA3F -:1087700004211162597B01F03F04640144EAD000F6 -:108780005062987B800040EA9110D97B1B7C01F0FD -:10879000010403F00F03DB0140EA842043EA5101A6 -:1087A0009062D162012010BD1112002044120020FD -:1087B00014120020024B53F82100C0F3CF00704781 -:1087C0009412002010B50446FCF75AFD144B1A68A9 -:1087D0001860821AB2F57A6F124A84BF00211170B4 -:1087E000137823B9A82C1AD10F490B7006E0022B7D -:1087F00002D10E490C7001E0242B01D80C49CC5455 -:108800000133DBB21370094A1278520005329342E9 -:1088100005D1044B00221A70034B01221A7010BDBF -:1088200064120020D41200208E1200206812002052 -:10883000691200204FF4E1334360836001234373E6 -:108840007047000037B5002300930D4601231446FE -:10885000082009494FF4E13200F086FF074B186009 -:108860000CB1074B236000304FF0100318BF0120FC -:108870002B7003B030BD00BFC587000890120020E8 -:10888000B5870008134B10B51A780AB9002010BD3F -:1088900000221A70104B5B78012BF7D10F4B1A781E -:1088A000102A84BF10221A700D4A19780023D8B2FA -:1088B000884202F102020AD212F8010C12F8024CAC -:1088C00040EA0424074840F823400133EFE7012041 -:1088D00010BD00BF8E120020691200206812002017 -:1088E0006C12002094120020114B10B501221A7056 -:1088F0000446FCF7C5FC0F4A014613681160C31A11 -:108900000D4841F28832934203600C4B84BF002231 -:108910001A701B780A4AE4B20F2BD45403D1094BC6 -:1089200001221A7010BD054A0133137010BD00BF3B -:108930001013002028130020D8120020DC12002081 -:1089400013130020D61200202DE9F0411C4B0478AF -:108950001A781D46FAB11B4B1E781B4B1F78022359 -:108960001A4803F10108C25C324102F00F02A24230 -:108970000CD20B2A0AD810F803C010F808000CEA31 -:10898000070C00EB0C2C124840F822C00233102BCD -:10899000E6D100232B708C420ED90E4B187860B1B3 -:1089A0000D4B1A780A4B53F8210002B1400800F52C -:1089B000777080B2BDE8F0810020BDE8F08100BF93 -:1089C000D6120020D512002012130020131300200D -:1089D000E012002010130020111300204FF4E133A7 -:1089E00043608360012343737047000013B5037A2B -:1089F00014465BB1012B13D1134A03201070134AA4 -:108A000007201070124A13700C2308E00E4A02204F -:108A100010700E4A032010700D4A137007230B705C -:108A200000230093082001230A494FF4E13200F0AB -:108A30009BFE094B18600CB1084B2360003018BF37 -:108A4000012002B010BD00BFD5120020121300207B -:108A500011130020E9880008241300204989000828 -:108A6000014B1878704700BFD6120020014B1860E8 -:108A7000704700BF30130020034B1B681878D0F1FB -:108A8000010038BF0020704730130020034B1B68E3 -:108A90001878431E58425841704700BF30130020D9 -:108AA000034B1B681878831E58425841704700BF1B -:108AB0003013002008B54FF40060FAF773FD20B1C1 -:108AC0000420BDE8084000F007BE08BD084B1B7835 -:108AD00063B1084B1B685B7813B1074B187D01E04D -:108AE000064B9878003018BF01207047012070476E -:108AF0002C13002030130020CC1F0020BB1F0020AF -:108B000008B5FFF7B9FF18B1BDE8084000F082BA18 -:108B1000FFF7BCFF18B1BDE8084000F04DBC08BD30 -:108B200008B5FFF7A9FF08B100F0B0F8FFF7AEFFF6 -:108B300018B1BDE8084000F015BB08BD38B50D4BB5 -:108B40001B78B3B1FFF7C2FF0B4B04461A781D46E2 -:108B500082420ED050B1FFF78FFF08B100F0AEF89F -:108B6000FFF794FF20B100F03DFB01E0FFF7D8FFD5 -:108B70002C7038BD341300202D13002008B50121BE -:108B8000042000F0B5FD0F4B1870FFF793FF0E4B5C -:108B90001870FFF771FF18B10C4B186800F070F8EF -:108BA000FFF774FF18B1094B186800F0F3FAFFF7EC -:108BB00077FF18B1054B186800F001FCBDE80840CC -:108BC000FFF7BCBF2C13002034130020301300200B -:108BD00008B50C4B1B789BB1FFF778FF80B1FFF70E -:108BE0004BFF08B100F0ACF8FFF750FF08B100F000 -:108BF0002BFBFFF755FF18B1BDE8084000F0E0BBC4 -:108C000008BD00BF3413002038B5064C05465E2170 -:108C10002068FCF703FB20682946BDE83840FCF7D4 -:108C2000FDBA00BF4C130020024B5E211868FCF710 -:108C3000F5BA00BF4C13002010B50A4C5E2801465F -:108C4000206805D15D21FCF7E9FA20683E2105E0A6 -:108C50005D2903D1FCF7E2FA20683D21BDE8104010 -:108C6000FCF7DCBA4C13002010B50446C0B2FFF785 -:108C7000E3FFC4F30720BDE81040FFF7DDBF0000AD -:108C8000014B1860704700BF4413002010B5084B1B -:108C9000084C19782068FCF7E5FA074B206819683A -:108CA000FCF7D6FA20680421BDE8104000F05CBC57 -:108CB000401300204C1300203813002073B504200B -:108CC00000F026FC144C01462060144E144D90B167 -:108CD00043794FF41651337083682B60FCF7B8FA70 -:108CE00020680221FCF7BEFA2068042102B0BDE82A -:108CF000704000F029BC0B4B4FF416521B68042047 -:108D00009B780093022300F02FFD4379206033709D -:108D100083682B6002B070BD4C130020401300200C -:108D2000381300204413002008B5044B1868FCF7E2 -:108D300085FAD0F1010038BF002008BD4C13002097 -:108D40002DE9F843FFF7F0FF002800F04481FCF71D -:108D5000B1FAA24B1A68821A7C2A40F23C81A04EDA -:108D60001860337800240133337004F12400C0B25A -:108D7000FFF74AFF9B4B33F91400F7F7C7FE9A4BF6 -:108D800005461888F7F7C2FE01462846F7F7C6FFE2 -:108D90009649F7F70FFFF8F7D3F8013400B2FFF761 -:108DA00063FF032CE1D13020FFF72EFF904BB3F986 -:108DB0000000FFF759FFFFF737FF307810F0030787 -:108DC00029D18C4D1020FFF71FFF2B68642493FBE3 -:108DD000F4F000B2FFF748FF2120FFF715FF2B68E2 -:108DE00093FBF4F004FB103484EAE470A0EBE4702D -:108DF00000B2FFF739FF1420FFF706FF7E4BB3F9EF -:108E00000000FFF731FF1C20FFF7FEFE3846FFF79A -:108E10002BFFFFF709FF33785B0740F0B680022095 -:108E2000FFF7F2FE754B0A25B3F9000090FBF5F051 -:108E3000FFF71AFF0220FAF7B5FB00284CD0DFF845 -:108E4000CC816F4F98F800303A7840F63401B2FB8D -:108E5000F3F24A436B4C2A21B2FBF1F2218806203F -:108E600091FBF3F903FB19194FEA09191FFA89F964 -:108E700049EA02291FFA89F9C2F3032249EA0209E1 -:108E8000FFF7C2FE0FFA89F0FFF7EEFE228898F88E -:108E90000030013292B292FBF3F103FB11232380E5 -:108EA0003B786E245C43152394FBF3F43A204FF097 -:108EB0006408FFF7A9FEB4FBF8F708FB174438462F -:108EC000A4B2FFF7D1FE05343B20FFF79DFE94FBD3 -:108ED000F5F000B2FFF7C8FE2020FFF7E7F8002802 -:108EE00051D0494C1320FFF78FFE2368DFF8208113 -:108EF000002BB8BF5B4293FBF8F000B2FFF7B4FE63 -:108F00001B20FFF781FE23680A27002BB8BF5B42B6 -:108F100093FBF7F342F2107593FBF5F205FB123069 -:108F200000B2FFF7A1FE2320FFF76EFE2368002B9F -:108F3000ACBF4E205320FFF797FE1220FFF764FED0 -:108F40006368002BB8BF5B4293FBF8F000B2FFF7F9 -:108F50008BFE1A20FFF758FE6368002BB8BF5B42F8 -:108F600093FBF7F797FBF5F305FB137000B2FFF7E0 -:108F70007BFE2220FFF748FE6368002BACBF452034 -:108F80005720FFF771FEFFF74FFE3378282B22D1D1 -:108F9000134B00221A70FCF78DF94FF47A763C24BB -:108FA000B0FBF6F61720FFF72FFEB6FBF4F5B5FB86 -:108FB000F4F004FB1050000200B2FFF755FE182039 -:108FC000FFF722FE04FB156000B2FFF74DFEBDE87F -:108FD000F843FFF729BEBDE8F88300BF481300201F -:108FE0003C130020041F00200400002000007A44ED -:108FF000E80D0020D40C0020DA1E0020981E00206E -:10900000481900203E130020901F0020010000207E -:10901000A08601004FF416507047000010B5054CB3 -:109020002068FCF70BF918B12068FCF70CF9F6E79B -:1090300010BD00BF90130020DFF890C02DE9F04371 -:10904000204E91FBFCF406FB04180627C90F07FB12 -:1090500008F8417292FBFCF106FB01261A4B04EB67 -:10906000840498FBF3F903FB19887E434FFA89F9CE -:1090700004EB840409EB8404A4B28472240AC4724D -:1090800096FBF3F403FB146301EB810164B201EB83 -:109090008101642504EB810198FBF5F893FBF5F35E -:1090A00089B280F80C80D20F4FEA2828C17343742C -:1090B000090A1B1280F80D80827301748374BDE865 -:1090C000F08300BF806967FF40420F0080969800E0 -:1090D00010B5174B174A1B78D27A0446837612B91B -:1090E0002D23C37610BD042B8CBF33233223C376CC -:1090F000114B93E80600FFF79FFF104B1A8864237B -:10910000B2FBF3F303EBC3039B009BB2E3711B0AB7 -:1091100023720B4B1B88E3741B0A2375094B1B88B6 -:1091200063751B0AA375084B1B88237710BD00BF0E -:10913000A81F0020BB1F0020901F0020661F0020DA -:10914000701F0020621F00207C1F0020044A0023A3 -:109150001278837003718277C37702754375704705 -:109160004819002010B5084B084C19782068FCF706 -:1091700079F8074B20681968FCF76AF82068042121 -:10918000BDE8104000F0F0B99613002090130020C5 -:1091900080130020F8B5104C104B2C2718600021CC -:1091A00020463A4604F06CFE8E2363707C26E02352 -:1091B0007D25E370267084F82B50094C0021204651 -:1091C0003A4604F05DFE8A236370A0232670E370A4 -:1091D00084F82B50F8BD00BF511300209C130020D1 -:1091E000A413002073B5042000F092F9134C01463B -:1091F0002060134E134D90B143794FF49641337074 -:1092000083682B60FCF724F820680121FCF72AF81A -:109210002068042102B0BDE8704000F095B90090CC -:109220004FF496420123042000F09EFA4379206017 -:10923000337083682B6002B070BD00BF90130020B4 -:1092400096130020801300202DE9F843FCF718F84E -:109250004C4D4D4A2B680446C31A934206D94B48DD -:10926000FFF774FF4A48FFF733FF2C60494E4A4F1F -:1092700096F80090B9F1000F0ED1DFF82881D8F8E8 -:109280000000FBF7DBFF012806D90228434D46D03A -:10929000FFF7C4FE01232B703D68DFF8FCC0002DF2 -:1092A0006ED037783B4A3E4E3FB1336840F6B73117 -:1092B000E31A8B420BD8BDE8F88301231370394BB6 -:1092C00002211868FBF7CEFF374B1F7024E0374FA1 -:1092D00034483B784BB900680121CCF8003013705A -:1092E000FBF7C0FFFFF79AFE16E0013BD9B23970D9 -:1092F0002D4A2F4B19B911784D1C157006E015F841 -:10930000011B1778CCF800500F4417701A780068CA -:1093100001321A70FBF782FF3460BDE8F8832A78C7 -:10932000244B1AB11C6085F80090B5E71B68E31A5E -:10933000B3F57A6FB0D30123D8F800002B70FBF798 -:1093400082FF0546D8F80000FBF77DFF802DA3D1F2 -:109350008A2802D08E280AD09EE72020FEF7A6FE9B -:10936000002899D03378002B96D1094B03E033784D -:10937000002B91D1054B3B600C4B2D221A708BE7D3 -:10938000BDE8F883881300203F0D0300511300202F -:10939000A41300208C130020A01300202D00002017 -:1093A00084130020901300205013002095130020F8 -:1093B00094130020981300204FF496407047704794 -:1093C00002F0E0B810B500230C245C430549DAB282 -:1093D000615C814203D00133042BF5D11A4610465B -:1093E00010BD00BF30000020037A0022D0B201324D -:1093F00013B1581E0340F9E70A7AD9B2013312B10A -:10940000511E0A40F9E7884294BF002001207047AE -:10941000004870476000002000230549DAB2595C1B -:10942000814203D00133092BF7D11A461046704709 -:10943000C1F800082DE9F74F137C81460E4614460B -:10944000032B40D80C225A43214903F1010A01EBB6 -:10945000020898F8080019EA000F31D08B5C43B17C -:10946000012B06D0022B04D0032B14BF04250325A7 -:1094700000E01D46174B4FEA051B402003EB0B078E -:109480000193FAF78FF8019B20B913F80B30023BD8 -:10949000012B15D9737B13B13A7B134210D071683D -:1094A0007A6891420CD3B168BA68914208D82570A5 -:1094B000A760C4F80480E66084F810A0204603E0AA -:1094C0005FFA8AF3BCE7002003B0BDE8F08F00BF6D -:1094D00030000020CCF8000870B50A4C06460D4656 -:1094E00020460021142204F0CBFC074804210C2262 -:1094F000064B04F00FFD304629462246BDE8704079 -:10950000FFF798BFD013002030000020E993000837 -:109510000B4AA2F13003197A81420BD00C339342EB -:10952000F9D1084B197A014004D10C339342F9D197 -:10953000084670470BB1586870471846704700BF1F -:10954000600000203000002010B50023054A1A44B6 -:109550005468844203D00C33302BF7D1002251726F -:1095600010BD00BF300000200023064A1A44516895 -:10957000814203D00C33302BF7D1002200235372E9 -:10958000704700BF3000002038B5002205461D4955 -:109590001301585CA84204D00132062AF7D10020FA -:1095A00038BD194C0B44042D0FCB84E80F001BD0A1 -:1095B00007D8012D0FD0022D21D1144B1B689B68B9 -:1095C00010E0102D15D0202D09D0082D17D12046E0 -:1095D000FEF706FE11E00D4B1B685B680CE00B4BC1 -:1095E0001B681B69636007E0FFF78AFA6060A06090 -:1095F00003E0064B1B68DB68A360204638BD0248C9 -:1096000038BD00BF0CF90008F8130020F413002047 -:10961000214B10B518600120FFF7B6FF014601206D -:10962000FFF75AFF08B9002010BD0220FFF7ACFF7A -:1096300001460220FFF750FF0028F4D01020FFF76A -:10964000A3FF01461020FFF747FF04464FF4807048 -:10965000F9F7A8FF08B1002CE5D00820FFF794FF28 -:1096600001460820FFF738FF04460820F9F79AFF63 -:1096700008B1002CD7D00420FFF786FF0146042054 -:10968000FFF72AFF04464FF40060F9F78BFF08B19B -:109690000CB9C8E7012010BDF413002070B50E46C8 -:1096A00000240C4D0023605DE95CEA18814203D080 -:1096B0001033602BF8D100221146FFF70DFF8368AD -:1096C0001B78B34204D01034602CEAD1002070BD66 -:1096D000012070BD0CF9000810B50446FFF754FFD7 -:1096E00001462046FFF7F8FE003018BF012010BDEC -:1096F00038B505460C46FFF747FF01462846FFF7F9 -:10970000EBFE28B143681B7A1C420CBF00200120ED -:1097100038BD0000F8B505460020FFF753FE104E97 -:109720000C272B780F4C07FB0060E35C03720120D1 -:10973000FFF748FE6B7807FB0060E35C03720220D2 -:10974000FFF740FEAB7807FB0060E35C0372032089 -:10975000FFF738FEEB7807FB0060E35C0372F8BDAF -:1097600030000020C1F800082DE9F04F87B098467E -:1097700082460F4616469DF84040FFF705FF0DF163 -:10978000080E0546034600F1100C18685968724629 -:1097900003C2083363459646F7D12B7B0BB903967A -:1097A0000496504602A9FFF797FE054640B143686C -:1097B000586830B1504602A92A46FFF73BFEF4E74D -:1097C00030E0AB6895F800B093F80090B9F1030F62 -:1097D00028D8DFE809F002050E100094134801E0D4 -:1097E00013480094394632464346F9F70BF80446CD -:1097F0000BE0002000E00120394623463246F8F70E -:10980000EFFD41460446FBF72DFD54B1094B84F8AA -:10981000049043F82B406B6820465C605146FFF78C -:1098200093FE204607B0BDE8F08F00BF003801402E -:1098300000440040E413002038B5064C0546206083 -:10984000FFF768FF284601F093FD2068BDE8384027 -:1098500000F0E6BEF4130020034B1B780BB100F0C0 -:10986000E7BD01F01BBE00BF0814002010B5044680 -:109870002046FBF7F2FC18B90A20FBF72CFDF7E7AE -:1098800010BD0000232801D100F0D2BD044B1B689D -:109890001B7D834202D10120FBF79CBD704700BFB6 -:1098A000F413002010B5441E14F8011F21B1034B1E -:1098B0001868FBF7B3FCF7E710BD00BF40140020A9 -:1098C0000148FFF7EFBF00BFF8FA000810B50748DE -:1098D000FFF7E8FF0024064B06481A19E1585268C2 -:1098E0000C34FAF705FAC02CF5D110BD36FB000890 -:1098F00014FA00084CFB000870B5FBF7DBFC244BA6 -:109900004FF47A711A78234BB0FBF1F11B7822489F -:10991000FAF7EEF9FEF7E4FB204B05461968204BF9 -:109920002048B1FBF3F1FAF7E3F900241E4AE3B251 -:1099300052F8231049B1012202FA03F32B4202D05C -:109940001A48FAF7D5F90134F0E70220FEF7AEFB2A -:1099500068B1174B17481A78174B53F82210FAF7CB -:10996000C7F9164B197A11B11548FAF7C1F915481C -:10997000FFF798FF144B1C88F8F7FCF821460246C5 -:109980004FF488631148BDE87040FAF7B1B900BFE1 -:10999000481900200100002054FB00088401002029 -:1099A00040420F0092FB0008000A0108B0FB0008CB -:1099B000D00C0020B4FB0008D4FA0008A41E00203C -:1099C000BEFB000824FE0008A20C0020C2FB000819 -:1099D00038B50C680546204604F048FE214602468C -:1099E0002868BDE8384004F071BE000037B503793F -:1099F00004460D46052B34D8DFE803F003060A0DB4 -:109A00001114836819782DE0836893F9001029E018 -:109A10008368198826E08368B3F9001022E0836820 -:109A200019681FE0836869461868FAF74FFA01461B -:109A30001248FAF75DF9F5B1E068F7F767F869469B -:109A4000FAF744FA01460E48FAF752F92069F7F797 -:109A50005DF86946FAF73AFA01460948FAF748F913 -:109A600009E000210748FAF743F925B10648E16803 -:109A70002269FAF73DF903B030BD00BFBBFB000817 -:109A8000BAFB0008F8FB0008F4FB000808B506481C -:109A9000FFF708FF054B1868FFF7E8FEBDE8084030 -:109AA0000020FBF797BC00BFFBFB00084014002020 -:109AB00008B50748FFF7F6FE064B93F83C04F9F7A4 -:109AC0000BFDF9F719FDBDE80840FFF7DFBF00BF48 -:109AD0000AFC00084C1900207FB5044604F0C6FDBE -:109AE000082825D100231F49E25C09681144497800 -:109AF00001F00301022908BF203AE2540133082B88 -:109B0000F1D10025665D1848314604F0D7FC28B134 -:109B100001356019314604F0D1FC18B11348FFF744 -:109B2000C1FE1DE0082DEDD120461149FEF7D0FC05 -:109B30001048FFF7B7FE00230F4A04A91A4492F811 -:109B400008210A440849595C0133082B02F80C1C0F -:109B5000F2D10023094801A98DF80C30FAF7C8F8B2 -:109B600004B070BDA0010020B8F8000814FC000883 -:109B7000541A002034FC00084C1900204FFB000848 -:109B800008B5FEF79FF8022802D0032800D008BDD0 -:109B90000248BDE80840FFF785BE00BF49FC000849 -:109BA0002DE9F041054604F061FD0446F9F75CFF3C -:109BB00006468CB92948FFF775FE294B53F8241047 -:109BC00041B10123A340334202D02648FAF790F86E -:109BD0000134F2E7244821E028462449224604F0D3 -:109BE00075FD58B92248FFF75DFE224C54F8041F5A -:109BF0000029EFD01B48FAF77BF8F7E72B7800260F -:109C00002D2B03BF013504F1FF344FF001084FF055 -:109C10000008134B53F8267027B91748BDE8F041E8 -:109C2000FFF740BE28463946224604F04FFD98B95A -:109C30000120B040B8F1000F03D0F9F75BFE0F48E8 -:109C400002E0F9F7B9FC0E48FFF72CFE39460D4843 -:109C5000BDE8F041FAF74CB80136DAE76FFC0008CE -:109C60006CF90008B0FB000824FE0008DE070108BC -:109C700082FC000868F9000897FC0008B1FC0008A5 -:109C8000BBFC00084FFB000810B504460848FFF76E -:109C900009FE084A00231370074A1360074A13702D -:109CA000FCF790FB2046BDE81040FFF701BF00BF66 -:109CB000C4FC0008091400203C14002008140020F3 -:109CC00008B50448FFF7EEFDF9F77EFCBDE8084053 -:109CD000FFF7DCBEDCFC00082DE9F04389B0044648 -:109CE00004F0C4FCC6B2002E6CD17B48FFF7DAFD4D -:109CF0007A4C20690021F7F7F1F840BB013678482B -:109D00003146F9F7F5FF206904A9FAF7DFF80146B3 -:109D10007448F9F7EDFF606904A9FAF7D7F801462E -:109D20007048F9F7E5FFA06904A9FAF7CFF80146F2 -:109D30006C48F9F7DDFFE06904A9FAF7C7F80146B6 -:109D40006948F9F7D5FF0C2E04F11004D1D1002594 -:109D5000664C2F462B464FF00008B04504F1100426 -:109D600015DA184654F8101CF6F71CFE54F80C1CB3 -:109D700081462846F6F716FE54F8081C0546384674 -:109D8000F6F710FE08F101084B460746E5E758488C -:109D9000019302950397FFF785FD002401ABE0587E -:109DA000544920F00040F7F7C1F8534B534A0434AC -:109DB000002814BF10461846FFF774FD0C2CEDD197 -:109DC0004F4871E020464F49052204F07FFC38B926 -:109DD000424B002203441030C0281A61F8D177E0CA -:109DE00020464949042204F071FC054620460DBB7B -:109DF000202104F063FB00286AD0461C304604F0A2 -:109E000035FC2C460746414B53F824500DB94048C9 -:109E10004AE030462946FAB204F058FC40B92046E0 -:109E20003C49FCF76FFB3C482946F9F761FF47E0E6 -:109E30000134E8E703F0D0FF461E0B2E074643DC53 -:109E40002046202104F03AFB054640B1451C284637 -:109E5000FAF7A4F8214B3F01D851012400E0044651 -:109E60002846202104F02AFB054640B1451C28461F -:109E7000FAF794F8194B013403EB0613586128469E -:109E8000202104F01BFB054640B1451C2846FAF78B -:109E900085F8124B013403EB061398612846202104 -:109EA00004F00CFB18B91D48FFF7FCFC10E0013072 -:109EB000FAF774F8094B032C03EB0616F061F2D1A4 -:109EC0001748FFF709FF03E016480C21F9F710FFC8 -:109ED00009B0BDE8F08300BFFDFC00084C1900206C -:109EE00028FD00082EFD00084FFB00086019002027 -:109EF00032FD00080AD7233CF9FC0008F5FC0008F5 -:109F000024FE000841FD000847FD0008B8F90008DC -:109F10004CFD00085C19002064FD000877FD000876 -:109F200063000108B1FD0008F8B5074604F09EFB88 -:109F3000044638B91A4B1B485A791B4B013A53F85F -:109F4000221028E038461949224604F0BFFB60B9C8 -:109F50001748FFF7A7FC174C54F8041F19B116480F -:109F6000F9F7C6FEF8E7154805E000250E4B53F853 -:109F7000256026B91248BDE8F840FFF793BC384683 -:109F80003146224604F0A2FB01350028EED1044BF5 -:109F90000C485D713146BDE8F840F9F7A9BE00BF35 -:109FA0004C190020D9FD0008B8F90008DE070108A7 -:109FB000EDFD0008B4F90008B0FB000824FE00081D -:109FC0004CFD000800FE00082DE9F047074604F0AC -:109FD0004DFB4D4D064620B1012818D13B782A2B68 -:109FE00015D14A48FFF75EFC002429594848F9F783 -:109FF0007FFE28193146FFF7F9FC4648FFF752FC6F -:10A00000143440F6EC139C42EFD1BDE8F08738469B -:10A010003D2104F053FA00285BD0441C204603F095 -:10A02000DBFE82462046F9F7B9FF002406464FF0D2 -:10A03000140909FB04F955F80980404604F016FBA1 -:10A0400041460246384604F041FB002839D12E4FE4 -:10A050004F44F868F6F75AFD01463046F6F75CFFC4 -:10A0600000282CD03869F6F751FD01463046F6F746 -:10A0700049FF20B33B79052B4FF0140303FB045435 -:10A08000227918BF5646052A0FD8DFE802F00303ED -:10A090000606090CA268167007E0A268168004E0A4 -:10A0A000A268166001E0A3681E6041461A48F9F7ED -:10A0B0001FFE20460021BDE8F047FFF797BC174878 -:10A0C00003E001347F2CB2D11548BDE8F047FFF71B -:10A0D000E9BB04462E593946304604F0A5FC58B178 -:10A0E0000B483146F9F704FE074800212044FFF7EA -:10A0F0007DFC0848F9F7FCFD143440F6EC139C4253 -:10A10000E8D1BDE8F08700BF200A010812FE000870 -:10A11000ECFF000824FE000827FE000832FE0008BD -:10A1200057FE000810B50446204604F09FFA10F0D0 -:10A13000FF0F07D10B4B0C4893F83C14BDE81040BF -:10A14000F9F7D6BD204603F047FE022808D8054B94 -:10A15000064C83F83C04F9F7CFF9F9F73FFCE3E745 -:10A1600010BD00BF4C19002074FE000863000108F8 -:10A1700070B5044604F07AFA08B9204830E0204669 -:10A180001F4904F051FD00242646254678B12CB124 -:10A19000012C06D103F020FE064602E003F01CFE6F -:10A1A000054617490020013404F03EFDEEE70B2D73 -:10A1B00005D9BDE8704013480C21F9F799BD012C71 -:10A1C00008DC114B294633F915201048BDE87040D2 -:10A1D000F9F78EBDA6F57A73B3F57A7F04D90C48EA -:10A1E000BDE87040F9F784BD0A4829463246F9F7C0 -:10A1F0007FFD054B23F8156070BD00BF8AFE000887 -:10A200002D000108C4FE0008381F0020EAFE0008E7 -:10A2100002FF000824FF000838B5054604F026FABE -:10A22000C0B268B90446124B214603EB44031148FF -:10A23000B3F876200134F9F75BFD152CF3D138BD66 -:10A24000284603F0C9FD142804460BDC20212846CB -:10A2500004F034F903F0C0FD054B03EB4404A4F80B -:10A26000760038BD04481521BDE83840F9F740BDF7 -:10A27000901D00203DFF000849FF00082DE9FF4721 -:10A28000584C5948F9F734FD5848FFF7C5FF627933 -:10A29000574B013A53F822105648F9F729FD206927 -:10A2A0000021F6F71BFE274600285AD105462669ED -:10A2B00000213046F6F712FE00284ED101354E48F7 -:10A2C0002946D4F814A0D4F81890D4F81C80F9F7D3 -:10A2D0000FFD30460021F6F70BFE10B14748F9F7A5 -:10A2E00007FD69463046F9F7F1FD01464448F9F7A4 -:10A2F000FFFC50460021F6F7FBFD10B13F48F9F78F -:10A30000F7FC69465046F9F7E1FD01463C48F9F78C -:10A31000EFFC48460021F6F7EBFD10B13748F9F79E -:10A32000E7FC69464846F9F7D1FD01463448F9F79C -:10A33000DFFC40460021F6F7DBFD10B12F48F9F7AE -:10A34000D7FC69464046F9F7C1FD01462D48F9F7AB -:10A35000CFFC0C2D04F11004A9D12B48691CF9F78E -:10A36000C7FCF9F781FB294C054654F8041F19B1C5 -:10A370002748F9F7BDFCF8E70C46264B53F82410A4 -:10A3800041B10123A3402B4202D02348F9F7B0FC8E -:10A390000134F2E7CB1993F8083104AA13441F4A99 -:10A3A0008A5C0131082903F8102CF3D100241C48E1 -:10A3B00069468DF80840F9F79BFC1A4D1A48615917 -:10A3C000F9F796FC28190021FFF710FB1748FFF753 -:10A3D00069FA143440F6EC139C42EED104B0BDE8A7 -:10A3E000F08700BF4C1900206FFF000863000108D0 -:10A3F000B8F900089FFF0008AAFF00082D00010817 -:10A40000BBFB00084FFB0008B2FF000868F900081A -:10A41000C4FF00086CF90008D2FF0008B8F8000873 -:10A42000DFFF0008200A0108E8FF000824FE0008FA -:10A430002DE9F0476C4B86B01A7899466B4F7AB984 -:10A4400001233868022189F80030FFF77DF8386869 -:10A45000F9F77AFC6648FFF725FA6648FFF722FA13 -:10A460003868FAF7EBFE002800F0BB805F4B624CC7 -:10A470001868FAF7E8FE0928014601D03F2852D1B2 -:10A480004FF00008D4F800A05C4E4546BAF1000F2A -:10A4900005D05B483168524604F018F910B9B0464F -:10A4A00005B93546574B0C369E42EFD3CDB1D5F8A2 -:10A4B00000E0D8F800C053461EF803601CF8030003 -:10A4C000B04201D023600CE05A1C4D4930B92D2B0D -:10A4D00004D82026CE542260885402E0CE5413467D -:10A4E000EAE723681BB1454501D1554611E04648CE -:10A4F000FFF7D8F9454508D855F80C0BFFF7D2F906 -:10A5000038680921FAF78AFEF4E73A48FFF7CAF9F2 -:10A51000002523689D42A3D2394B3868595DFAF76C -:10A520007DFE0135F5E723682BB9042836D1344880 -:10A53000FFF7AAFB55E00C2801D134488BE70A2924 -:10A5400001D00D2944D13248FFF7ACF92C4D2268D7 -:10A550000023AB5404932F4B03A8009327491022E8 -:10A560000C23039503F03CFC064638B1006804F068 -:10A570007DF80130B3682844984702E02648FFF789 -:10A5800091F91F480021302203F07AFC0023236058 -:10A5900099F80030002B7FF460AF22E00C28CCD07B -:10A5A0007F2903D15CE72F2B3FF65AAFA1F12002A0 -:10A5B000D2B25E2A3FF654AF13B920293FF450AF10 -:10A5C0005A1C22600E4A3868D154FAF727FE47E732 -:10A5D0007F29E8D10A4A013B00212360D1540F486A -:10A5E0003CE706B0BDE8F0870814002040140020C6 -:10A5F000F2FF00082A0001083C14002014FA0008A9 -:10A6000009140020D4FA00082F00010834000108C2 -:10A6100024FE0008D19900083F00010860000108ED -:10A6200037B505460220FEF773FF064C0146206051 -:10A6300030B90090AA6802200323FFF795F8206044 -:10A6400003B030BD40140020F8B5154E154C164D22 -:10A650000746C1B230682170FAF7E0FD22782B7806 -:10A66000C7F30721534030682B702170FAF7D6FDED -:10A6700022782B78C7F30741534030682B70217044 -:10A68000FAF7CCFD22782B78390E534030682B70C6 -:10A690002170FAF7C3FD2B78227853402B70F8BD58 -:10A6A0004C1400204A14002045140020F8B50C4E2C -:10A6B0000C4D0D4CC1B2074630682970FAF7AEFD5B -:10A6C0002A782378C7F30721534030682370297014 -:10A6D000FAF7A4FD23782A7853402370F8BD00BF11 -:10A6E0004C1400206614002045140020054B10B5C2 -:10A6F000044621461868FAF791FD034B1A78544036 -:10A700001C7010BD4C14002045140020034A13781F -:10A71000591C1170024AD05C704700BF47140020DA -:10A720006C14002010B5FFF7F1FF0446FFF7EEFFB1 -:10A7300004EB002080B210BD10B5FFF7F3FF044614 -:10A74000FFF7F0FF04EB004010BD000038B50446F1 -:10A7500024200D46FFF7CAFF4D20FFF7C7FF002C4E -:10A760000CBF3E202120FFF7C1FF064B28460022E8 -:10A770001A70FFF7BBFF044B1878BDE83840FFF7AD -:10A78000B5BF00BF4514002065140020014600201D -:10A79000FFF7DCBF01460120FFF7D8BF014B187857 -:10A7A000FFF7A4BF4514002070B5064608460D46C5 -:10A7B000FFF7ECFF0024E3B29D4204D0305DFFF7C9 -:10A7C00095FF0134F7E770BD10B5441E14F8010F72 -:10A7D00010B1FFF78BFFF9E710BD00002DE9F0473E -:10A7E000002701240025154B1B789D421DDA144BD0 -:10A7F000144E15F803800C2303FB0863586803F01C -:10A8000035FFB24681460CB9264601E007440AE00E -:10A810004E4508DA0C2303FB08A35B68985DFFF73D -:10A8200065FF0136F4E70135DDE724B1F8B2FFF743 -:10A83000ADFF0024D6E7BDE8F08700BF4814002034 -:10A840005014002068000020F8B5D94B1B787B2BF2 -:10A8500000F0468300F2C6806E2B00F0BA8360D809 -:10A86000682B00F0598325D8652B00F04E8219D84B -:10A87000642B40F064850720CE4CFFF787FFE6206D -:10A88000FFF734FF6079FFF731FF0020FFF72EFF5D -:10A8900094F81B01C84BC94A00280CBF1046184643 -:10A8A00000F02ABD662B00F0B082672B40F0478590 -:10A8B000C34832E36B2B00F06A8323D8692B00F086 -:10A8C00053836A2B40F03B851020FFF75FFFBD4BA1 -:10A8D000BD4CD87AFFF70AFFBC4B1878FFF706FF8C -:10A8E0002068FFF7B1FE6068FFF7AEFEB84BB3F922 -:10A8F0000000FFF7DBFEB74BB3F90000FFF7D6FE11 -:10A90000B54B63E36C2B00F054836D2B40F017853F -:10A910000620FFF73BFFB14B1868FFF795FEB04BE1 -:10A9200054E3732B00F021843DD8702B00F0818319 -:10A93000C0F06083712B00F0EF83722B40F0FF8436 -:10A940009C4C1620FFF722FF0020FFF7AFFEB4F962 -:10A95000D000FFF7ABFEA34DB4F9D200FFF7A6FE7F -:10A96000B4F9D400FFF7A2FEB5F9EA00FFF79EFEA6 -:10A970000020FFF79BFE0020FFF766FEB5F95A00A6 -:10A980000A2390FBF3F0FFF791FE94F80401FFF720 -:10A99000ADFE94F80601FFF7A9FE94F80501FFF754 -:10A9A000A5FE00F011BC762B00F0EA830DD8742BC5 -:10A9B00000F0C983752B40F0C2842F20FFF7E6FE1C -:10A9C0008948FFF701FF00F0BDBC772B00F0BE8384 -:10A9D000782B40F0B484834C3820FFF7D7FE04F185 -:10A9E00040054BE2D02B00F0228400F29B80CA2B62 -:10A9F00000F0068139D8A42B00F0818411D8A02B57 -:10AA000040F09D840C20FFF7C1FE784B1868FFF7DB -:10AA10001BFE774B1868FFF717FE764B186800F09F -:10AA20006BBCC82B00F0B580C92B40F08884FFF7C1 -:10AA30006DFE644B644CD872FFF768FE634B187070 -:10AA4000FFF77AFE2060FFF777FE6060FFF76AFE8F -:10AA50005F4B1880FFF766FE5E4B1880664B1A78D6 -:10AA600042F002021A7000F02EBCCD2B00F0E683FB -:10AA700024D8CB2B00F08B80CC2B40F06084FFF7E8 -:10AA800045FE584C84F85000FFF740FE84F8510012 -:10AA9000FFF73CFE84F85400FFF738FE84F85500B9 -:10AAA000FFF734FE84F85600FFF730FE84F85200BA -:10AAB000FFF72CFE84F8530000F005BCCE2B00F00D -:10AAC000C683CF2B40F03B84FFF72CFEFFF72AFE16 -:10AAD000384C444DA4F8D000FFF724FEA4F8D2006F -:10AAE000FFF720FEA4F8D400FFF71CFEA5F8EA004B -:10AAF000FFF718FEFFF720FEFFF714FE00EB8000C3 -:10AB00004000A5F85A00FFF701FE84F80401FFF7A2 -:10AB1000FDFD84F80601FFF7F9FD84F80501FFF754 -:10AB2000F5FDD0E3D52B00F0E98111D8D22B00F050 -:10AB3000D880C0F04D83D32B00F0E280D42B40F0BE -:10AB4000FE83284C0020FFF721FE04F14005A9E117 -:10AB5000F02B00F0C4830FD8D62B00F0B980EF2B78 -:10AB600040F0ED83FFF7DEFD1E4CA4F85E00FFF71A -:10AB7000D9FDA4F85C00A6E3FA2B00F09783FE2B26 -:10AB800040F0DD830820FFF701FE00249FE300244E -:10AB90008EE00024FFF7C6FD184B18530234102C2A -:10ABA000F8D10020FFF7F2FDFDF7F6FCCAE300BF85 -:10ABB000651400204C1900201C0000801400008047 -:10ABC00018000020BB1F0020901F0020A81F00209D -:10ABD000621F0020661F002068100020FC1E00205D -:10ABE000E80D0020901D00200C140108E8F7FF1F5D -:10ABF000ECF7FF1FF0F7FF1F621100201420002068 -:10AC0000C84B1A781C46022A42D103F1200503F1F1 -:10AC10002C06FFF77BFDF5F775FFC349F6F77EF8C5 -:10AC200045F8040FFFF772FDF5F76CFFBF49F6F723 -:10AC300075F8E860FFF76AFDF5F764FFBC49F6F7C1 -:10AC40006DF8B542A861E4D10325072D12D1FFF7B5 -:10AC50005DFDF5F757FFB449F6F760F8A064FFF71C -:10AC600055FDF5F74FFFB049F6F758F8E064FFF7E8 -:10AC70004DFD09E0FFF74AFD66193071FFF746FD0B -:10AC8000B073FFF743FD307601350A2DDDD11AE3AD -:10AC90005C1E03F10905FFF739FD01342071FFF750 -:10ACA00035FDA073FFF732FDAC422076F3D10AE305 -:10ACB000A04B1B789C4280F006839F4BE55CFFF71E -:10ACC00031FD984B013403EB4505A5F87600EFE71D -:10ACD0000024FFF727FD994B18530234102CF8D1AC -:10ACE000F1E2974B9C78002C40F0ED82FFF70EFDCF -:10ACF000944B022894BF83F83C0483F83C44DEE282 -:10AD0000FFF710FD904B1880DDE20B20FFF73EFDB2 -:10AD10008E4BB3F90000FFF7C9FCF6F72BFF00B22A -:10AD2000FFF7C4FC0220FDF7C1F905460420FDF73A -:10AD3000BDF904460820FDF7B9F9800040EA440453 -:10AD40002020FDF7B3F92C43A4B244EAC00084B23A -:10AD50001020FDF7ABF944EA001000B2FFF7A6FCA3 -:10AD6000774A00201479D378A40044EA4304937806 -:10AD70001C43937944EAC304537944EA4314537A55 -:10AD800044EA8314724BD97944EAC114197A44EA2B -:10AD90000124597A44EA4124D17944EA8124117A80 -:10ADA000927A44EAC12444EA02345A7B44EA4234A7 -:10ADB0009A7B44EA82341A7C44EA02441A7944EACF -:10ADC00002145A7C44EA42449A7C44EA8244DA7C83 -:10ADD0001B7D44EAC24444EA0354564B19780346A7 -:10ADE0008B420CD2544A9D5C012202FA05F52542A1 -:10ADF00018BF9A4003F1010318BF1043F0E7FFF7B3 -:10AE000023FC504B93F83C04DFE11220FFF7BEFC1B -:10AE1000504B514C1B88B3F5806F22D90025605FE1 -:10AE2000082390FBF3F00235FFF740FC062DF6D126 -:10AE30004A4CB4F90000FFF739FCB4F90200FFF7FF -:10AE400035FCB4F90400464CFFF730FCB4F90000BF -:10AE5000FFF72CFCB4F90200FFF728FCB4F904005A -:10AE600047E2B4F90000FFF721FCB4F90200FFF754 -:10AE70001DFCB4F90400FFF719FCD9E7B4F9A800E8 -:10AE8000FFF714FCB4F9AA00FFF710FCB4F9AC000A -:10AE9000FFF70CFC083494F8A600FFF727FCAC423F -:10AEA000ECD14FE2FFF73EFCA4F8A800FFF73AFC14 -:10AEB000A4F8AA00FFF736FCA0F57A7307289BB226 -:10AEC00098BF84F8AF00B3F57A7F98BFA4F8AC00C0 -:10AED000FFF71CFC083484F8A600AC42E2D131E252 -:10AEE0000820FFF753FC00240E4B234493F8AF00D7 -:10AEF0000834FFF7FBFB402CF6D123E20020FFF7DC -:10AF000045FC0024FFF702FC064B23440834402C88 -:10AF100083F8AF00F6D115E212481021FFF744FC88 -:10AF200010E200BF901D0020000020410000C84238 -:10AF300000007A444814002050140020381F0020DC -:10AF4000BB1F00204C190020C81E0020A20C0020AE -:10AF5000CC1F002004000020041F0020FC0D002056 -:10AF6000B01E0020201F0020BC4D00242878400087 -:10AF700000F0FE00FFF70AFC2B789C4280F0E28193 -:10AF8000B74B33F91400FFF791FB0134F4E70520C8 -:10AF9000FFF7FCFBB34BB3F90000FFF787FBB24BA5 -:10AFA000B3F90000FFF782FBB04B187800F0010006 -:10AFB0000BE1AF4C0620FFF7E9FBB4F90000FFF707 -:10AFC00075FBB4F90200FFF771FBAA4BB3F900005F -:10AFD0008FE10720FFF7DAFBA74B1878FFF786FB16 -:10AFE0000020FFF763FBA54BB3F90000FFF75EFB02 -:10AFF00000207EE1A24C0720FFF7C8FB94F8500028 -:10B00000FFF774FB94F85100FFF770FB94F85400BD -:10B01000FFF76CFB94F85500FFF768FB94F85600B7 -:10B02000FFF764FB94F85200FFF760FB94F85300BD -:10B03000CBE01E20FFF7AAFB914B1A781C46022A90 -:10B040005AD103F1200503F12C0655F8040F8D4960 -:10B05000F5F7B0FD01F090FBFA220021F8F70AFDA8 -:10B06000C0B2FFF743FB8849E868F5F7A3FD01F09C -:10B0700083FBFA220021F8F7FDFCC0B2FFF736FB94 -:10B080008249A869F5F796FD01F076FB002164225C -:10B09000F8F7F0FCC0B2FFF729FBB542D5D1032584 -:10B0A000072D1BD17749A06CF5F784FD01F064FBF7 -:10B0B000FA220021F8F7DEFCC0B2FFF717FB714956 -:10B0C000E06CF5F777FD01F057FB0021FA22F8F765 -:10B0D000D1FCC0B2FFF70AFB002007E06619307907 -:10B0E000FFF704FBB07BFFF701FB307E0135FFF774 -:10B0F000FDFA0A2DD4D125E15C1E03F109050134C6 -:10B100002079FFF7F3FAA07BFFF7F0FA207EFFF734 -:10B11000EDFAAC42F3D115E15D4D002428784000F2 -:10B1200000F0FE00FFF732FB2B789C4280F00A8192 -:10B13000584BE25C524B013403EB4203B3F9760007 -:10B14000FFF7B4FAF0E7FFF749FBFBE0504D0024AE -:10B150002878FFF71BFB2B789C4280F0F3804D4B47 -:10B16000185DFFF7C3FA0134F5E70820FFF70EFB7F -:10B170000124E0B20134FFF7B9FA092CF9D1E1E07A -:10B18000FFF7C4FA06461220FFF700FB0EB9424B48 -:10B1900002E0102E03D1414B1D685C6801E00024E1 -:10B1A00025463046FFF7A2FA2846FFF74DFA20461B -:10B1B000FFF74AFA3A4B1868FFF746FA0020FFF704 -:10B1C00075FA0020FFF772FA0020FFF78FFAB9E056 -:10B1D000FFF79CFA0546FFF7AFFA0746FFF7ACFA10 -:10B1E0000646FFF7A9FA0446FFF79CFAFFF79AFA1A -:10B1F000FFF78CFA5DB9284B01225E601F60294B76 -:10B20000DD711A73002C5ED0254B1C605BE0102DA5 -:10B2100059D1224B1F605E600CB1214B1C601F484E -:10B22000214B0222011D1A70FCF78EFD4BE01D4BD5 -:10B230009B78002B47D1F8F7C7F942E0194B9B7870 -:10B24000002B40D14FF4C870F9F7A2FD3BE0154B3D -:10B250009A78002A37D101229A7334E01020002016 -:10B2600014200020701F00207C1F0020621100208D -:10B27000080E0020DA1E00204819002012200020AD -:10B28000901D0020000020410000C84200007A44C8 -:10B290004814002050140020741F0020681F002054 -:10B2A000001F0020BB1F0020280F0020274B9B7889 -:10B2B000002B44D1264B93F83C04F8F70DF9F8F72E -:10B2C0001BF9F8F78BFB0020FFF760FA3AE0214BFF -:10B2D000185F0234FFF7EAF9082CF8D132E01E4C6F -:10B2E0000420FFF753FAB4F95E00FFF7DFF9B4F971 -:10B2F0005C00FFF7DBF925E0FFF7A6F922E0174D28 -:10B300000024287880000130C0B2FFF73FFA287887 -:10B31000FFF7ECF92B789C4214D2114B185DFFF724 -:10B32000E5F9104B185DFFF7E1F90F4B185DFFF7DA -:10B33000DDF90E4B185DFFF7D9F90134EAE700207B -:10B34000FFF728FABDE8F840FFF728BABB1F002036 -:10B350004C1900209A1E0020901D0020A91F0020DB -:10B36000501F00207E1F0020981F0020AA1F0020D1 -:10B370002DE9F341454DFF2115220746284602F0ED -:10B380007FFD002302202B70FCF790FE012418B1F2 -:10B3900002236C70AB7003240420FCF787FE68B1B5 -:10B3A00003234FF40050661C2B55F8F7FBF820B12F -:10B3B000364B042202349A5500E034460220FCF752 -:10B3C00075FE48B12A19052306212B55A31C51707F -:10B3D0000722EA54033404E00820FCF767FE002843 -:10B3E000F0D12020F8F7DEF810B108232B550134F6 -:10B3F0004FF48070F8F7D6F828B10A222A55631C5A -:10B400000B22EA540234224A53799046082B01D089 -:10B410000E2B02D10C232B5501340D230420661C66 -:10B420002B55F8F7BFF818B1184B11229A55A61CE6 -:10B4300098F839011323003018BF0120741CAB5554 -:10B44000F8F7B0F818B1114B14221A55B41C114B6F -:10B4500000221C70104B1A601D467A6800240021DF -:10B46000009101200323FEF77FF920B94CB94FF476 -:10B4700096420124F3E72A68002AEED1064B1860B1 -:10B48000EBE702B0BDE8F041FDF7C2BF5014002069 -:10B490004C190020481400204C14002010B5304CEA -:10B4A0002068F9F7CBFE002858D02068F9F7CBFECA -:10B4B0002C4C034622786AB9B0F12402534253411E -:10B4C0002370002BEBD1284B9B78002BE7D1FEF7A4 -:10B4D000D9F9E4E7012A04D14D2814BF002302233F -:10B4E0003AE0022A04D13C2814BF0023032333E0AE -:10B4F000032A0FD140284FF0000201D92270CEE775 -:10B500001A49042308701A490A701A490A701A4A1B -:10B51000107021E0042A08D1184A1070164A1178D8 -:10B5200080EA01031370052316E0052AB7D11048FD -:10B530000E4A017812788A420F4A07D914785C4083 -:10B5400014704A1C02700E4A5354A8E712789A42AB -:10B5500001D1FFF779F900232370A0E710BD00BFE8 -:10B560004C14002046140020BB1F0020441400206F -:10B5700049140020471400204514002065140020C1 -:10B580006C14002010B5074C074A2368D25C074BA7 -:10B590001A70FFF759F923680133092B88BF00237C -:10B5A000236010BD68140020EB140108651400200E -:10B5B0002DE9F04106460F4690460025EBB2434583 -:10B5C0000DD20024E3B2B34204D23846F9F783FE29 -:10B5D0000134F7E73C20F9F77EFE0135EEE7BDE8E0 -:10B5E000F08100000F4B1A6842F001021A6059689E -:10B5F0000D4A0A405A601A6822F0847222F480329E -:10B600001A601A6822F480221A605A6822F4FE0234 -:10B610005A604FF41F029A60044B4FF000629A6028 -:10B62000704700BF001002400000FFF800ED00E08E -:10B63000144A154B516801F00C01042903D0082964 -:10B6400004D0124914E01249096811E051685068A9 -:10B65000C1F38341C00301F1020101D40D4806E0AA -:10B66000506810F4003F0A48006818BF4008414382 -:10B67000196052680849C2F30312895C1A68CA400B -:10B680001A607047001002408401002000127A0006 -:10B690008001002000093D00700100201FB500233B -:10B6A0000093019302934FF4E0130393504B1A68F5 -:10B6B00042F480321A609A6942F010029A611A6864 -:10B6C00002F400320192009A01320092019A1AB9F2 -:10B6D000009AB2F5A06FF2D11968454A11F4003111 -:10B6E00001D0022215E0146844F0010414600091B6 -:10B6F0001A6802F002020192009A01320092019A45 -:10B700001AB9009AB2F5A06FF2D11A68920739D52A -:10B7100001220292374A384C116841F01001116041 -:10B72000116821F003011160116841F002011160FC -:10B730005A685A605A685A605A6842F480625A607D -:10B740002E4A1168043A21F0704151602C490C6076 -:10B750005C6824F47C145C60546844F000445460D9 -:10B76000D46824F40044D4609268140449BF254A84 -:10B770004FF4E0120A604FF480120392029A012AF9 -:10B7800001D117E0FEE7022A18D168B1039AB2F599 -:10B79000801F02D14FF4A01205E0039AB2F5E01F1A -:10B7A00002D14FF4001203925968039A0A4342F4FB -:10B7B000803202E05A6842F460125A601A6842F01D -:10B7C00080721A6019680A4A8901FBD5516821F014 -:10B7D00003015160516841F0020151605A6802F062 -:10B7E0000C02082AFAD1FFF723FF04B010BD00BFF6 -:10B7F000001002400020024000127A0004100140B4 -:10B8000080010020001BB70008B5154B98420BD1F2 -:10B810004FF48050012100F0B7FDBDE808404FF41F -:10B820008050002100F0B0BD0E4B984207D14FF47C -:10B830008040012100F0B4FD4FF4804009E00A4B44 -:10B8400098420BD14FF40040012100F0A9FD4FF4C4 -:10B8500000400021BDE8084000F0A2BD08BD00BFC7 -:10B860000030014000380040003C00400B8810B51B -:10B870004C88028823438C8802F441522343CC88AD -:10B8800023430C8923434C8923438C892343CC894C -:10B89000234313439BB20380838B23F400631B0475 -:10B8A0001B0C83830B8A038210BD038819B19BB2E2 -:10B8B00043F0400303E023F040031B041B0C038010 -:10B8C000704781817047808980B27047038919422F -:10B8D0000CBF00200120704743680A6823F47023DE -:10B8E00023F4807313430A7910B543EA02234360BB -:10B8F0008A68CB6884681A43084B234013434A790B -:10B9000043EA420383600B7CC26A013B22F470026B -:10B91000DBB242EA0353C36210BD00BFFDF7F1FF83 -:10B92000836811B143F0010301E023F00103836058 -:10B930007047836811B143F4807301E023F480738E -:10B9400083607047836843F00803836070478068B2 -:10B95000C0F3C0007047836843F0040383607047FE -:10B960008068C0F380007047836811B143F4A0037E -:10B9700001E023F4A00383607047092970B50DD955 -:10B98000A1F10A0404EB44040725A540A340C668BE -:10B9900026EA050545EA0304C4600BE001EB410417 -:10B9A0000725A54003FA04F4066926EA050545EAD9 -:10B9B00004030361062A0CD8013A02EB82021F231A -:10B9C000934001FA02F2446B24EA03031A434263F0 -:10B9D00070BD0C2A0CD8073A02EB82021F23934059 -:10B9E00001FA02F2046B24EA03031A43026370BDF6 -:10B9F0000D3A02EB82021F23934001FA02F2C46A5D -:10BA000024EA03031A43C26270BD000040F0BF6025 -:10BA1000024B40F40030D860704700BF00ED00E0FA -:10BA2000C27810B50378FAB1154A4478D26803F1A8 -:10BA30006043D243C2F30222C2F1040104FA01F1CD -:10BA40000F2424FA02F2847803F5614322400A436A -:10BA50001201D2B283F8002303780122590903F0BE -:10BA60001F0302FA03F306E05909012203F01F0342 -:10BA700002FA03F32031034A42F8213010BD00BF1F -:10BA800000ED00E000E100E030B5048C24F001049A -:10BA90002404240C0484058B048CADB225F0F3053A -:10BAA0002A4342EA03139DB2104BA4B2984215D028 -:10BAB00003F50063984211D0B0F1804F0ED0A3F58A -:10BAC000983398420AD003F58063984206D003F574 -:10BAD0008063984218BF24F00A0401D124F00204C4 -:10BAE00044F0010421430583018430BD002C014052 -:10BAF00030B5048C24F010042404240C0484048B3A -:10BB0000058C24F440742405240D44EA022242EA00 -:10BB10000333144AADB290429BB212D002F50062D8 -:10BB200090420ED0B0F1804F0BD0A2F598329042E7 -:10BB300007D002F58062904203D002F58062904205 -:10BB400007D125F0200545F0100545EA011189B21D -:10BB500004E025F0A00545F0100529430383018486 -:10BB600030BD00BF002C0140224A038890429BB2A6 -:10BB700012D002F5006290420ED0B0F1804F0BD08F -:10BB8000A2F59832904207D002F58062904203D02D -:10BB900002F58062904203D14A8823F07003134378 -:10BBA000154A904208D002F58062904204D023F4F6 -:10BBB0004073CA889BB2134303808B8883850B88AC -:10BBC00003850C4B98420FD003F5006398420BD0CD -:10BBD00003F54063984207D003F58063984203D091 -:10BBE00003F58063984201D10B7A03860123838297 -:10BBF000704700BF002C014000100040038C70B55E -:10BC000023F001031B041B0C0384038C8488028B28 -:10BC10000D8822F073021204120C2A434E880D89FB -:10BC200023F002031B043543ADB21B0C2B43144D10 -:10BC3000A4B2A8420FD005F50065A8420BD005F5C7 -:10BC40004065A84207D005F58065A84203D005F5F8 -:10BC50008065A8420ED14D8923F008032B438D88BF -:10BC600023F004032B43CE898D8924F4407435439B -:10BC7000ADB22C4384800283CA888286038470BD5F -:10BC8000002C0140038C30B523F010031B041B0C67 -:10BC90000384038C8288048B0D8824F4E6442404F6 -:10BCA000240C23F0200344EA05241B040D891B0CFB -:10BCB00043EA05134D8892B243EA0513124DA4B22C -:10BCC000A8429BB203D005F50065A84215D14D8965 -:10BCD00023F080039BB243EA05134FF6BF751D4066 -:10BCE0008B8822F4406245EA03138D899BB242EAB5 -:10BCF0008502CD8942EA850292B28280CA88048395 -:10BD00000287038430BD00BF002C0140038C30B596 -:10BD100023F480731B041B0C0384038C8288848BA4 -:10BD20000D8824F073042404240C23F400732C43A2 -:10BD30001B040D891B0C43EA05234D8892B243EA8C -:10BD40000523124D9BB2A84203D005F50065A84219 -:10BD500015D14D8923F400639BB243EA05234FF6C6 -:10BD6000FF351D408B8822F4405245EA03238D891C -:10BD70009BB242EA0512CD8942EA051292B2828054 -:10BD8000CA8884838287038430BD00BF002C0140B1 -:10BD9000038C30B523F480531B041B0C0384038CE9 -:10BDA0008488828B0D8822F4E6421204120C23F45C -:10BDB000005342EA05221B040D891B0C43EA05339C -:10BDC0004D88A4B243EA05330A4D92B2A8429BB211 -:10BDD00003D005F50065A84205D18D8924F480447F -:10BDE00044EA8514A4B284808283CA88A0F84020E3 -:10BDF000038430BD002C01404FF6FF738380002385 -:10BE00000380C38043800372704700230380438014 -:10BE10008380C380038143818381C3817047002372 -:10BE20000122038043808280C3800381704703889E -:10BE300019B19BB243F0010303E023F001031B049B -:10BE40001B0C03807047B0F8443029B16FEA4343BC -:10BE50006FEA53439BB201E0C3F30E03A0F84430F2 -:10BE6000704783899BB20AB1194301E023EA0101BB -:10BE700081817047038B23F008031B041B0C1943BB -:10BE800001837047038B23F400631B041B0C43EAFC -:10BE900001218BB203837047838B23F008031B04BB -:10BEA0001B0C194381837047838B23F400631B04AD -:10BEB0001B0C43EA01218BB2838370478184704756 -:10BEC000038B23F00C031B041B0C0383038B9BB21B -:10BED000194301837047038B23F440631B041B0C3D -:10BEE0000383038B9BB243EA01218BB20383704728 -:10BEF000838B23F00C031B041B0C8383838B9BB26B -:10BF0000194381837047838B23F440631B041B0C0C -:10BF10008383838B9BB243EA01218BB28383704777 -:10BF200070B50E880D4604464988AA882B893EB90B -:10BF3000FFF7AAFD2046E988BDE87040FFF7C0BFC3 -:10BF4000042E07D1FFF7D4FD2046E988BDE87040F4 -:10BF5000FFF7C1BF082EEE88058C39D125F4807516 -:10BF60002D042D0C0584808B258C80B220F0F300ED -:10BF700040EA03139BB21A43344BADB29C4212D039 -:10BF800003F500639C420ED0B4F1804F0BD0A3F5B3 -:10BF900098339C4207D003F580639C4203D003F59D -:10BFA00080639C4207D125F4007545EA012189B2DE -:10BFB00041F4807104E025F4206541F48071294347 -:10BFC000A283204621843146BDE87040FFF790BF30 -:10BFD00025F480552D042D0C0584808B258C20F4B0 -:10BFE00040700005000D40EA0220184A40EA033381 -:10BFF0009442ADB29BB212D002F5006294420ED0D0 -:10C00000B4F1804F0BD0A2F59832944207D002F5DC -:10C010008062944203D002F58062944207D125F4F5 -:10C02000005242EA013292B242F4805205E047F6F1 -:10C03000FF522A4041F480510A43A38320462284C0 -:10C040003146BDE87040FFF75EBF00BF002C0140E5 -:10C05000808E80B27047008F80B27047808F80B230 -:10C060007047B0F8400080B27047038A828911EAB5 -:10C07000030092B203D011420CBF00200120704790 -:10C08000C94389B201827047038ACA889BB223F4EC -:10C090004053134330B503820D4682890989AB882A -:10C0A00092B20B43698922F4B0520B4322F00C0286 -:10C0B00013439BB28381838AAA899BB223F4407382 -:10C0C00087B013430446838201A800F0EDF81749B6 -:10C0D000049A039B8C4208BF1346A289192112B20D -:10C0E0005943002A2A684FF06403B4BF52009200FB -:10C0F000B1FBF2F1B1FBF3F21201100903FB1011D5 -:10C10000A08900B2002806DAC9003231B1FBF3F38E -:10C1100003F0070305E009013231B1FBF3F303F04B -:10C120000F031A4392B2228107B030BD003801409C -:10C13000838919B19BB243F4005303E023F4005305 -:10C140001B041B0C83817047C1F3421310B50124FB -:10C1500001F01F01A34204FA01F101D10C3003E008 -:10C16000022B0CBF1030143003680AB1194301E0F0 -:10C1700023EA0101016010BD838A9BB20AB1194311 -:10C1800001E023EA010181827047090A01238B4003 -:10C19000DB439BB203807047034B044A5A6002F1B1 -:10C1A00088325A60704700BF002002402301674573 -:10C1B000024B1A6942F080021A6170470020024067 -:10C1C000014BD860704700BF00200240084BDA687E -:10C1D000D10709D4DA68520708D4DB6813F0100FCE -:10C1E0000CBF0420032070470120704702207047D5 -:10C1F0000020024010B50446FFF7E8FF012806D1F1 -:10C200001CB1FFF7E3FF013CF8E7052010BD002C4F -:10C2100008BF052010BD000038B505464FF430209A -:10C22000FFF7E8FF042812D1094C4FF430202369AE -:10C2300043F0020323616561236943F040032361F6 -:10C24000FFF7D8FF226941F6FD731340236138BD23 -:10C250000020024073B5002306464FF400500D46FF -:10C260000193FFF7C7FF04281AD10E4C4FF400507A -:10C27000236943F001032361ABB23380FFF7BAFFB8 -:10C28000042808D102360196019B2D0C1D804FF425 -:10C290000050FFF7AFFF226941F6FE7313402361A0 -:10C2A00002B070BD002002401F4B10B55A6802F06A -:10C2B0000C02042A03D0082A04D01C4A14E01C4AA9 -:10C2C000126811E05A685968C2F38342C90302F147 -:10C2D000020201D4174906E0596811F4003F1449DD -:10C2E000096818BF49084A4302605A681249C2F3F4 -:10C2F00003128C5C0268E24042605C68C4F3022472 -:10C300000C5D22FA04F484605C68C4F3C224095D05 -:10C31000CA40C2605B680949C3F38133CB5CB2FB9E -:10C32000F3F2026110BD00BF0010024000127A005B -:10C330008001002000093D008C01002088010020C0 -:10C34000044B5A6909B1104301E022EA0000586128 -:10C35000704700BF00100240044B9A6909B11043B6 -:10C3600001E022EA00009861704700BF001002401F -:10C37000044BDA6909B1104301E022EA0000D861F8 -:10C38000704700BF00100240044BDA6809B1104347 -:10C3900001E022EA0000D860704700BF00100240B0 -:10C3A000044B1A6909B1104301E022EA0000186148 -:10C3B000704700BF00100240024B5A6A42F0807280 -:10C3C0005A6270470010024008B50B4B984207D1E3 -:10C3D0004FF400100121FFF7E3FF4FF4001006E0D7 -:10C3E0004FF480000121FFF7DBFF4FF480000021B4 -:10C3F000BDE80840FFF7D4BF00540040F0B587B057 -:10C400000446868801A80D46314FFFF74DFF03987B -:10C4100026F03F063604B0FBF7F7360C1FFA87FC10 -:10C420004CEA0606A68021882A6821F00101294BE2 -:10C430000904090C9A4221800DD85300B0FBF3F394 -:10C440009BB20CF1010C032B1FFA8CFC98BF042348 -:10C45000A4F820C022E0E9884BF6FF73994205D189 -:10C4600002EB4202B0FBF2F39BB206E01923534306 -:10C47000B0FBF3F39BB243F48043C3F30B020AB95E -:10C4800043F001034FF4967257434FF47A7297FBCF -:10C49000F2F70137BFB243F400432784A383238814 -:10C4A00069899BB243F0010323802388AA8823F47F -:10C4B000816323F002031B040A431B0C13439BB24A -:10C4C00023802A89AB8913439BB2238107B0F0BD37 -:10C4D00040420F00A086010041F288330360002330 -:10C4E00083804BF6FF72038143814FF48043C28007 -:10C4F00083817047038819B19BB243F0010303E0C5 -:10C5000023F001031B041B0C03807047038819B13F -:10C510009BB243F4807303E023F480731B041B0C71 -:10C5200003807047038819B19BB243F4007303E0A2 -:10C5300023F400731B041B0C03807047038819B19C -:10C540009BB243F4806303E023F480631B041B0C61 -:10C550000380704783889BB20AB1194301E023EA44 -:10C5600001018180704701827047008AC0B2704724 -:10C5700012B141F0010101E001F0FE0101827047BA -:10C5800002684FF6FE7313400360002303604360AC -:10C590008360C3602A4B984222D02A4B984229D00C -:10C5A000294B984230D0294B984237D0284B98429B -:10C5B0003ED0284B984206D153F8682C42F47002C2 -:10C5C00043F8682C7047244B984206D153F87C2CD2 -:10C5D00042F0706243F87C2C7047204B984206D1A1 -:10C5E00053F8042C42F00F0243F8042C70471C4B04 -:10C5F000984206D153F8182C42F0F00243F8182C58 -:10C600007047184B984206D153F82C2C42F47062B4 -:10C6100043F82C2C7047144B984206D153F8402C09 -:10C6200042F4704243F8402C7047104B984205D1B9 -:10C6300053F8542C42F4702243F8542C704700BF36 -:10C64000080002401C00024030000240440002404A -:10C65000580002406C000240800002400804024082 -:10C660001C040240300402404404024058040240CA -:10C670008A6810B50C6A036814430A6923F4FF43FF -:10C6800014434A6923F0700314438A691443CA6946 -:10C6900014434A6A14438A6A224313430360CB68F3 -:10C6A00043600B6883604B68C36010BD0023036068 -:10C6B00043608360C360036143618361C36103625C -:10C6C00043628362704719B1036843F0010303E0DA -:10C6D00002684FF6FE7313400360704703680AB1A7 -:10C6E000194301E023EA010101607047416070478E -:10C6F000406880B270470000C3004CBF014B024B42 -:10C7000058607047000402400000024000B5194A1A -:10C7100020F00043934283B0014617DDB3F1FF4F91 -:10C7200004DBF4F73DF903B05DF804FB694600F063 -:10C7300037FB00F00302012A0098019911D0022A68 -:10C740000AD09AB1012201F0EFF8ECE7002100F0E5 -:10C75000EFFC03B05DF804FB00F0EAFC00F10040E0 -:10C76000E1E701F0E1F800F10040DCE700F0E0FC77 -:10C77000D9E700BFD80F493F30B5C0F3C754A4F183 -:10C780007F031E2B83B0014620DC581C1BDB162BBD -:10C790004FEAD17509DDC1F3160040F40000963C64 -:10C7A000A04005B1404203B030BD114B53F82540C5 -:10C7B0002046F4F7F7F8019001982146F4F7F0F8D5 -:10C7C00020F0004333B9002003B030BDF4F7B8FBCC -:10C7D00003B030BDC0F31604C0F3C75044F40004E6 -:10C7E000C0F1960024FA00F0002DDCD0DAE700BF9B -:10C7F000F814010800B51D4A20F00043934283B0AD -:10C80000014618DDB3F1FF4F04DBF4F7C9F803B0BC -:10C810005DF804FB694600F0C3FA00F0030001284C -:10C8200018D002280ED0D0B10098019900F080FCF9 -:10C8300000F10040EBE70021002201F075F803B0A1 -:10C840005DF804FB00980199012201F06DF800F1F8 -:10C850000040DCE70098019900F06AFCD7E70098F7 -:10C860000199012201F060F8D1E700BFD80F493FDC -:10C8700070B58AB0054600F09BF8224C064694F944 -:10C880000030013303D0284601F02CFA10B93046AD -:10C890000AB070BD284601F0DBF94FF07E51F4F785 -:10C8A00045FB0028F3D018490122002328460092B6 -:10C8B00008930191F3F7BAFD02460B461348CDE900 -:10C8C0000423CDE9022301F0A7F894F90030CDE963 -:10C8D0000601022B0BD0684601F09CF838B1089B8A -:10C8E00053B9DDE90601F4F707F80AB070BD01F0AD -:10C8F00099FA21230360F2E701F094FA089B0360A0 -:10C90000EFE700BF9C010020001501080815010891 -:10C9100000F0B6B970B58AB0054600F0B5FB224C00 -:10C92000064694F90030013308D0284601F0DAF9C0 -:10C9300020B128460021F4F7DBFA10B930460AB0DE -:10C9400070BD1A49012200232846019100920893E4 -:10C95000F3F76CFD2478CDE90401CDE902017CB93F -:10C9600000220023CDE90623684601F053F888B180 -:10C97000089BA3B9DDE90601F3F7BEFF0AB070BD5D -:10C980000020002102460B46F3F7CEFE022CCDE933 -:10C990000601E9D101F046FA21230360E8E701F03E -:10C9A00041FA089B0360E5E79C0100200C15010893 -:10C9B000F8B520F00043B3F17E5F044610D008DCE8 -:10C9C000B3F17C5F11DAB3F10C5F00F384809D4812 -:10C9D000F8BD0146F3F7E4FF0146F4F79FF9F8BD0F -:10C9E000002840F3CD800020F8BD0028C0F2CA80A6 -:10C9F00001464FF07E50F3F7D3FF4FF07C51F4F730 -:10CA0000D9F8044600F040FB8F4906462046F4F76B -:10CA1000D1F88E49F3F7C6FF2146F4F7CBF88C49DD -:10CA2000F3F7BEFF2146F4F7C5F88A49F3F7BAFFDA -:10CA30002146F4F7BFF88849F3F7B2FF2146F4F72F -:10CA4000B9F88649F3F7AEFF2146F4F7B3F8844905 -:10CA500005462046F4F7AEF88249F3F7A1FF2146D8 -:10CA6000F4F7A8F88049F3F79DFF2146F4F7A2F800 -:10CA70007E49F3F795FF2146F4F79CF84FF07E517D -:10CA8000F3F790FF01462846F4F748F93146F4F7EA -:10CA900091F826F47F6525F00F05074629462846BC -:10CAA000F4F788F801462046F3F77AFF2946044652 -:10CAB0003046F3F777FF01462046F4F72FF9014699 -:10CAC0003846F3F76FFF01462846F3F76BFF014640 -:10CAD000F3F768FFF8BD0146F4F76CF85A490546CC -:10CAE000F4F768F85949F3F75DFF2946F4F762F85F -:10CAF0005749F3F755FF2946F4F75CF85549F3F722 -:10CB000051FF2946F4F756F85349F3F749FF2946F0 -:10CB1000F4F750F85149F3F745FF2946F4F74AF87E -:10CB20004F4906462846F4F745F84E49F3F738FFD3 -:10CB30002946F4F73FF84C49F3F734FF2946F4F758 -:10CB400039F84A49F3F72CFF2946F4F733F84FF048 -:10CB50007E51F3F727FF01463046F4F7DFF8014630 -:10CB60002046F4F727F801464148F3F719FF01463C -:10CB70002046F3F715FF01463E48F3F711FFF8BDD5 -:10CB80003D48F8BD4FF07E51F3F70CFF4FF07C515C -:10CB9000F4F710F82C490446F4F70CF82B49F3F796 -:10CBA00001FF2146F4F706F82949F3F7F9FE21467B -:10CBB000F4F700F82749F3F7F5FE2146F3F7FAFFFB -:10CBC0002549F3F7EDFE2146F3F7F4FF2349F3F788 -:10CBD000E9FE2146F3F7EEFF0646204600F054FA40 -:10CBE0001F4905462046F3F7E5FF1E49F3F7D8FE37 -:10CBF0002146F3F7DFFF1C49F3F7D4FE2146F3F794 -:10CC0000D9FF1A49F3F7CCFE2146F3F7D3FF4FF0D3 -:10CC10007E51F3F7C7FE01463046F4F77FF8294608 -:10CC2000F3F7C8FF1249F3F7BBFE01462846F3F7B6 -:10CC3000B9FE0146F3F7B6FE01461048F3F7B0FE21 -:10CC4000F8BD00BFDB0FC93F08EF1138047F4F3A32 -:10CC50004611243DA80A4E3E90B0A63EABAA2A3EFD -:10CC60002EC69D3D6133303F2D57014039D11940CB -:10CC70006821A233DA0FC93FDB0F4940DA0F494080 -:10CC800021F00042B2F1FF4FF8B5044614DC20F069 -:10CC90000045B5F1FF4F06460EDCB1F17E5F3AD09C -:10CCA0008F1707F0020747EAD07755B9022F2FD028 -:10CCB000032F2FD13148F8BD08462146F3F772FE05 -:10CCC000F8BDFAB1B2F1FF4F29D0B5F1FF4F19D03D -:10CCD000AA1AD2153C2A19DC002938DB2046F4F7C1 -:10CCE0001DF800F0B5FF00F09DFE012F2CD0022FA3 -:10CCF00022D0002F2FD02249F3F754FE2149F3F719 -:10CD00004FFEF8BD002E15DB1F48F8BD1E48ECE7AE -:10CD10001C48F8BDF8BDBDE8F84000F083BEB5F191 -:10CD2000FF4F19D0022FF3D0032FC3D0012F1BD0F8 -:10CD30000020F8BD1548F8BD1149F3F733FE014650 -:10CD40001048F3F72DFEF8BD00F10040F8BD3C326D -:10CD5000C4DA0020C9E7F8BD022F0CD0032F08D099 -:10CD6000012F04D00A48F8BD4FF00040F8BD094833 -:10CD7000F8BD0948F8BD0948F8BD00BFDB0F49C040 -:10CD80002EBDBB33DB0F4940DB0FC93FDB0FC9BFF3 -:10CD9000DB0F493FDB0F49BFE4CB16C0E4CB1640A5 -:10CDA0002DE9F04FAB4A20F00044944289B006468A -:10CDB0000D4664DDA84A94421CDC0028A74940F3D4 -:10CDC000EC80F3F7EDFDA64B24F00F049C420646E1 -:10CDD00064D0A449F3F7E4FD014628603046F3F738 -:10CDE000DFFDA049F3F7DCFD01236860184609B0B8 -:10CDF000BDE8F08F9C4A944262DDB4F1FF4F46DA01 -:10CE0000E715863FA4EBC7542046F4F799F8F3F7EB -:10CE10007DFE0346014620460593F3F7C1FD4FF022 -:10CE20008741F3F7C7FE8046F4F78AF8F3F76EFE02 -:10CE30000146044640460694F3F7B2FD4FF08741A1 -:10CE4000F3F7B8FE00210790F4F748F8002800F047 -:10CE5000C58020460021F4F741F8002814BF0123C3 -:10CE6000022382480221019000913A4605A82946F2 -:10CE700000F022FA002EC0F2A780034603E0002251 -:10CE8000286000234A60184609B0BDE8F08F0146CB -:10CE9000F3F786FD002368602860F4E77449F3F730 -:10CEA0007FFD74490446F3F77BFD01462860204668 -:10CEB000F3F776FD6F49F3F773FD01236860E2E74E -:10CEC00000F0C6FE6C490746F3F774FE4FF07C5144 -:10CED000F3F768FDF4F734F88246F3F717FE5F497D -:10CEE0008346F3F767FE01463846F3F759FD5D497F -:10CEF00080465846F3F75EFEBAF11F0F8146494659 -:10CF0000404618DC5D4B0AF1FF3253F8223024F022 -:10CF1000FF029A420FD0F3F743FD07462F603946D0 -:10CF20004046F3F73DFD4946F3F73AFD002E6860B1 -:10CF300056DB5346A7E7F3F733FDE315C0F3C752BB -:10CF40009A1A082A0746E9DD494958460393F3F738 -:10CF500031FE074639464046F3F722FD0446214696 -:10CF60004046F3F71DFD3946F3F71AFD41490746E0 -:10CF70005846F3F71FFE3946F3F712FD814649463E -:10CF80002046F3F70DFD039BC0F3C7529B1A192BE4 -:10CF9000074641DC2860A046C1E7F3F703FD304BAC -:10CFA00024F00F049C42064623D02E49F3F7FAFCE6 -:10CFB000014628603046F3F7F3FC2A49F3F7F2FC08 -:10CFC0004FF0FF3368605EE795E80C0003F1004125 -:10CFD00002F1004243422A60696054E7032340E7BC -:10CFE00007F1004700F100402F606860CAF10003BC -:10CFF00049E71F49F3F7D6FC1E490446F3F7D2FC74 -:10D00000014628602046F3F7CBFC1A49F3F7CAFC27 -:10D010004FF0FF33686036E719495846F3F7CAFD09 -:10D02000074639462046F3F7BBFC8046414620467A -:10D03000F3F7B6FC3946F3F7B3FC124904465846F9 -:10D04000F3F7B8FD2146F3F7ABFC8146494640466D -:10D0500061E700BFD80F493FE3CB1640800FC93FBF -:10D06000D00FC93F43443537800F49439415010819 -:10D070000044353708A3852E84F9223F1415010892 -:10D0800000A3852E32318D2420F00042B2F1FF4FF3 -:10D09000F8B5044603462DD25AB300283DDBB2F55D -:10D0A000000F4FEAE0502CD37F38C3F31603C207BA -:10D0B00043F4000348BF5B00002740105B003E467E -:10D0C00019244FF08072B5189D4202DC5B1BAE182C -:10D0D0001744013C4FEA43034FEA5202F3D113B124 -:10D0E00007F001031F447F1007F17C5707EBC05086 -:10D0F000F8BDF8BD0146F3F75DFD2146F3F752FC9C -:10D10000F8BD14F400020FD15B00190202F1010214 -:10D11000FAD5C2F101021044C6E70146F3F740FC1C -:10D120000146F3F7FBFDF8BD01221044BCE700BF48 -:10D130002DE9F84320F00046B6F1485F05460F465A -:10D1400049DAF3F7FDFE002800F09D8029462846C5 -:10D15000F3F730FD4E490446F3F72CFD4D49F3F744 -:10D1600021FC2146F3F726FD4B49F3F719FC214634 -:10D17000F3F720FD4949F3F715FC2146F3F71AFDB3 -:10D180004749F3F70DFC2146F3F714FD4549F3F742 -:10D1900009FC2146F3F70EFD804620464FF07C51F6 -:10D1A000F3F708FD414606462046F3F703FD3946EE -:10D1B00004462846F3F7FEFC01462046F3F7F0FB51 -:10D1C00001463046F3F7ECFB01464FF07E50F3F793 -:10D1D000E7FBBDE8F8830146F3F7ECFC2C49044675 -:10D1E000F3F7E8FC2B49F3F7DDFB2146F3F7E2FC0C -:10D1F0002949F3F7D5FB2146F3F7DCFC2749F3F780 -:10D20000D1FB2146F3F7D6FC2549F3F7C9FB2146AC -:10D21000F3F7D0FC2349F3F7C5FB2146F3F7CAFC2B -:10D22000214B80469E42B8DD204B9E4227DC06F112 -:10D230007F4631464FF07E50F3F7B2FB81462046E1 -:10D240004FF07C51F3F7B6FC3146F3F7A9FB4146AA -:10D2500006462046F3F7AEFC394604462846F3F767 -:10D26000A9FC01462046F3F79BFB01463046F3F745 -:10D2700097FB01464846F3F793FBBDE8F883DFF8D8 -:10D2800034900B4EDBE74FF07E50BDE8F88300BFD3 -:10D290004ED747ADF6740F317CF29334010DD03781 -:10D2A000610BB63AABAA2A3D9999993E0000483FD6 -:10D2B0000000903E0000383F2DE9F04FDFB00B93A7 -:10D2C000013B0293D31E48BF131DB84C0646689815 -:10D2D000DB1054F8204023EAE3730C93DB4302EBAA -:10D2E000C30308940693089C029B0C9A1D1909918C -:10D2F000C3EB02071DD4699C3D4404EB870901354B -:10D300004FF0000822AC0AE059F80800F3F7FEFBE2 -:10D310000137AF4244F8080008F1040809D0002F93 -:10D32000F2DA01370020AF4244F8080008F104089F -:10D33000F5D1089A002AC0F2DF82089A0B9B02F10D -:10D3400001089C0022AF4FEA880827440025029A72 -:10D35000002AC0F2F28105EB070B4FF000094FF0F5 -:10D36000000A56F809005BF8041DF3F723FC014698 -:10D370005046F3F717FB09F10409A1458246F0D1A5 -:10D380004AA840F805A004354545E0D1089A0EABFF -:10D3900003EB82030D9391464FEA89030793079AA3 -:10D3A0005EAB1344B9F1000F53F850AC23DD0DF11F -:10D3B00034084AAF174490440DAD4FF06E515046BB -:10D3C000F3F7F8FBF3F7BCFDF3F7A0FB4FF0874151 -:10D3D0008346F3F7EFFB01465046F3F7E1FAF3F724 -:10D3E000AFFD594645F8040F57F8040DF3F7DAFA84 -:10D3F00045458246E1D15046069900F08DFC4FF03C -:10D4000078510546F3F7D6FB00F026FC4FF0824139 -:10D41000F3F7D0FB01462846F3F7C2FA0546F3F7C7 -:10D420008FFD8246F3F772FB01462846F3F7B8FA00 -:10D43000069A8046002A40F3678109F1FF310EA861 -:10D4400050F82130C2F1080043FA00F202FA00F06D -:10D450001B1A06989244C0F1070743FA07F70EA873 -:10D4600040F82130002F32DDB9F1000F0AF1010A36 -:10D4700040F375810EAB079A19461144002507E069 -:10D48000C2F5807012B143F8040C01258B420BD019 -:10D4900053F8042B002DF3D0C2F1FF028B4243F866 -:10D4A000042C4FF00105F3D1069B002B0DDD012B61 -:10D4B00000F03281022B08D109F1FF330EA951F897 -:10D4C000232002F03F0241F82320022F70D0404673 -:10D4D0000021F3F703FD002800F08380089A09F18A -:10D4E000FF35AA420DDC079A0EAB0D9813440022BB -:10D4F00053F8041D834242EA0102F9D1002A40F0A8 -:10D50000E481089B0EA85A1E50F82230002B40F0F0 -:10D51000F18100EB8202012352F8041D013300293E -:10D52000FAD04B4499450A933DDADDF82CA022AAA3 -:10D53000CA44DDF8308002EB8A02C844C9EB030913 -:10D54000131D03920593699A079B4FEA89094AAF15 -:10D5500002EB8808CDF810901F44002558F8040FFE -:10D56000F3F7D4FA029B039A002B50514FF0000BB3 -:10D5700013DBDDF814A04FF00009AA4456F80900A7 -:10D580005AF8041DF3F716FB01465846F3F70AFA5A -:10D5900009F10409A1458346F0D1049A0435954266 -:10D5A00047F804BFDAD1DDF82890F5E6AC18010899 -:10D5B00041464FF07E50F3F7F3F98046002D86D0B8 -:10D5C00006994FF07E5000F0A7FB01464046F3F766 -:10D5D000E7F9804640460021F3F780FC00287FF4FD -:10D5E0007DAF069B40465942CDF808A000F094FB61 -:10D5F0004FF087410446F3F78FFC002800F07F814D -:10D600004FF06E512046F3F7D5FAF3F799FCF3F794 -:10D610007DFA4FF087410546F3F7CCFA01462046E4 -:10D62000F3F7BEF9F3F78CFC0EAB43F8290028465C -:10D63000F3F786FC069C09F1010508340EA906944F -:10D6400041F8250006994FF07E5000F065FB002D53 -:10D6500004464FDB6E1C4FEA8508C6EB867A0DF157 -:10D6600038094AABC1444FEA8A0A98444FF0000B8C -:10D6700059F80B00F3F74AFA2146F3F79BFA4FF0FB -:10D680006E5148F80B002046F3F794FAABF1040B07 -:10D69000D3450446ECD1DFF88C92DDF820A00024BD -:10D6A000B34603950497BAF1000FB8BF002515DB08 -:10D6B00000263746002501E0A7420FDC58F8061087 -:10D6C00059F80600F3F776FA01462846F3F76AF9A7 -:10D6D0000137BA45054606F10406EDDA5EA800EB0F -:10D6E00084030134A345A8F1040843F8A05CDAD10F -:10D6F000039D049F689C032C00F29880DFE814F0DF -:10D70000CB009C009C00310010D109F1FF330EA921 -:10D7100051F823703F12A5E609F1FF330EA850F827 -:10D72000232002F07F0240F82320CEE64FF07C5108 -:10D73000F3F7F2FB58B90746C9E64FF0000A4AA8CA -:10D7400040F805A0043545457FF401AE1EE6B9F169 -:10D75000000F4FF002070AF1010A3FF78BAE0025D8 -:10D76000A2E6002D40F3DC804FEA850B5EAB36AEBF -:10D7700005F1FF3A5B4406EB8A0A53F8A08C544645 -:10D780005B4635AABB462F4600E0C84654F804590C -:10D790004146284601920093F3F704F98146494631 -:10D7A0002846F3F7FDF84146F3F7FCF8019AC4F870 -:10D7B00004909442A060009BE7D13D46012D5F4656 -:10D7C0009B4640F3AD805EAB9B445BF8A04C00E011 -:10D7D00044465AF8049921464846F3F7E3F8804650 -:10D7E00041464846F3F7DCF82146F3F7DBF85645A7 -:10D7F000CAF80480CAF80800EAD16C1C06EB84045D -:10D800000020083654F8041DF3F7CCF8B442F9D1DF -:10D81000002F7ED0369A379B099C00F1004002F120 -:10D82000004203F10043A06022606360029A02F0AC -:10D8300007005FB0BDE8F08F002DB8BF00200ADB05 -:10D8400036AE6C1C002006EB840454F8041DF3F77C -:10D85000A9F8B442F9D1002F35D000F10043099C5A -:10D86000014623603698F3F79BF8002D08DD36ACAF -:10D8700004EB850554F8041FF3F794F8AC42F9D192 -:10D880000FB100F10040099A5060029A02F00700BF -:10D890005FB0BDE8F08F002D39DB6C1C36AE002088 -:10D8A00006EB840454F8041DF3F77CF8B442F9D174 -:10D8B0000FB100F10040099A1060029A02F00700CF -:10D8C0005FB0BDE8F08F0346C9E7069A0EAC54F886 -:10D8D0002530083ACDF808A00692002B7FF4B2AEAE -:10D8E00004EB850353F8041D013D083A0029F9D0E3 -:10D8F0000692A7E6012314E60B9B9C0046E5204612 -:10D90000F3F71EFB0EAA4D4642F829009AE60020C6 -:10D91000CEE7099C369A379BA0602260636085E75A -:10D92000002075E7B81801082DE9F84320F00043FE -:10D93000B3F1485F04460F46904603DAF3F700FB65 -:10D94000002857D021462046F3F734F921460546F2 -:10D95000F3F730F9294906462846F3F72BF9284909 -:10D96000F3F71EF82946F3F725F92649F3F71AF8D5 -:10D970002946F3F71FF92449F3F712F82946F3F77C -:10D9800019F92249F3F70EF88146B8F1000F22D0B9 -:10D9900038464FF07C51F3F70DF949468046304642 -:10D9A000F3F708F901464046F2F7FAFF2946F3F784 -:10D9B00001F93946F2F7F4FF154905463046F3F709 -:10D9C000F9F801462846F2F7EDFF01462046F2F746 -:10D9D000E7FFBDE8F88349462846F3F7EBF80C4922 -:10D9E000F2F7DEFF3146F3F7E5F82146F2F7DAFF0A -:10D9F000BDE8F8832046BDE8F88300BFD3C92E2FC9 -:10DA0000342FD7321BEF3836010D50398988083C46 -:10DA1000ABAA2A3E0020704700200149704700BF92 -:10DA20000000F87F2DE9F04120F00045B5F1A14F4D -:10DA30000446064608DBB5F1FF4F6FDC002840F3D3 -:10DA4000A0806F48BDE8F0816E4B9D4277DCB5F158 -:10DA5000445F68DB4FF0FF3721462046F3F7AAF812 -:10DA600001468046F3F7A6F867490546F3F7A2F8A2 -:10DA70006649F2F797FF2946F3F79CF86449F2F7F5 -:10DA800091FF2946F3F796F86249F2F78BFF294692 -:10DA9000F3F790F86049F2F785FF2946F3F78AF823 -:10DAA0005E49F2F77FFF4146F3F784F85C49804610 -:10DAB0002846F3F77FF85B49F2F772FF2946F3F740 -:10DAC00079F85949F2F76CFF2946F3F773F857498B -:10DAD000F2F766FF2946F3F76DF85549F2F760FF54 -:10DAE0002946F3F767F87B1C014640464CD0F2F715 -:10DAF00059FF2146F3F75EF84E4B4F4D53F8271070 -:10DB0000F2F74EFF2146F2F74BFF014655F827008A -:10DB1000F2F746FF002E30DBBDE8F0810146F2F758 -:10DB200041FFBDE8F0814549F2F73CFF4FF07E51DF -:10DB3000F3F7FCF900288DD02046BDE8F08100F015 -:10DB400087F83F4B04469D4229DCA3F5D0039D4254 -:10DB500044DC0146F2F726FF4FF07E51F2F720FF3A -:10DB60004FF0804105462046F2F71CFF014628464B -:10DB7000F3F7D4F8002704466EE700F10040BDE853 -:10DB8000F0813048BDE8F081F2F70CFF2146F3F751 -:10DB900011F801462046F2F703FFBDE8F0812A4B59 -:10DBA0009D4214DC4FF07F51F2F7FAFE4FF07F51A7 -:10DBB00005462046F2F7FEFF4FF07E51F2F7F2FEE7 -:10DBC00001462846F3F7AAF80227044644E701462F -:10DBD0001E48F3F7A3F8032704463DE74FF07E51B4 -:10DBE000F2F7DEFE4FF07E5105462046F2F7DAFEF0 -:10DBF00001462846F3F792F8012704462CE700BFB8 -:10DC0000DB0FC93FFFFFDF3ED769853C59DA4B3D4B -:10DC1000356B883D6E2EBA3D2549123EABAAAA3E11 -:10DC200021A215BD6BF16E3D95879D3D388EE33D7C -:10DC3000CDCC4C3EE4180108F4180108CAF2497131 -:10DC4000FFFF973FDB0FC9BFFFFF1B40000080BFF6 -:10DC500020F00040704700BF2DE9F04120F0004760 -:10DC6000FD0D7F3D162D064613DC002D80461BDB87 -:10DC7000194F2F41074214D01849F2F793FE0021A3 -:10DC8000F3F754F968B1002E1BDB28EA0700BDE862 -:10DC9000F081B7F1FF4F04D30146F2F783FEBDE8F0 -:10DCA000F0813046BDE8F0810C49F2F77BFE00219F -:10DCB000F3F73CF90028F4D0002E08DB0020BDE883 -:10DCC000F0814FF4000343FA05F5A844DDE7002F87 -:10DCD000E7D00348BDE8F081FFFF7F00CAF2497139 -:10DCE000000080BF30F0004001D102207047A0F555 -:10DCF0000003B3F1FE4F01D204207047054B421ED2 -:10DD00009A4201D803207047B0F1FF43584258416E -:10DD1000704700BFFEFF7F0038B530F00044024678 -:10DD200003460D4614D0B4F1FF4F0DD2B4F5000FE9 -:10DD30000FD3E40D2C44FE2C2EDC002C1DDD23F033 -:10DD4000FF4343EAC45038BD0146F2F72BFE38BD0D -:10DD500038BD4FF09841F2F72DFF194B02469D4216 -:10DD600007DBC0F3C7540346193CE3E7154800F04E -:10DD70002DF81449F2F71EFF38BD14F1160F13DA0F -:10DD80004CF250339D421146F0DD0F4800F01EF872 -:10DD90000D49F2F70FFF38BD11460B4800F016F899 -:10DDA0000949F2F707FF38BD04F1190023F0FF43DA -:10DDB00043EAC0504FF04C51F2F7FCFE38BD00BFB3 -:10DDC000B03CFFFF6042A20DCAF2497101F0004170 -:10DDD00020F000400843704700210A2200F0E8BF0D -:10DDE0002DE9F84FDDF828B0164681468A46984658 -:10DDF00092B18BB1002503E011D0651CAE420BD966 -:10DE00007419640808FB04A748463946D847002817 -:10DE1000F2DA2646AE42F3D80020BDE8F88F384645 -:10DE2000BDE8F88F014B1868704700BFD00500208F -:10DE300070B50F4E0F4D761BB61007D0043D002471 -:10DE4000013455F8043F9847A642F9D10A4E0B4DCC -:10DE500003F0DEFD761BB61008D0043D002401342B -:10DE600055F8043F9847A642F9D170BD70BD00BF78 -:10DE7000281A0108281A0108301A0108281A01086E -:10DE8000F0B4840743D0541E002A3ED0CDB20346DE -:10DE900003E0621E002C38D0144603F8015B9A0799 -:10DEA000F7D1032C2AD9CDB245EA05250F2C45EA36 -:10DEB000054515D9A4F110073F0903F1100606EB3B -:10DEC00007161A46156055609560D5601032B2424B -:10DED000F8D104F00F040137032C03EB07130DD91D -:10DEE0001E462246043A032A46F8045BFAD8221F4B -:10DEF00022F003020432134404F003042CB1C9B22B -:10DF00001C4403F8011BA342FBD1F0BC704714462C -:10DF10000346C6E72DE9F04F87B00092044602EBB6 -:10DF200042020098520005928008A20701911D4606 -:10DF3000029040F0838000998B077FD1019AB1F164 -:10DF4000040918BF4FF00109062A7CD9019A0098EC -:10DF50005308072A00FB034B40F00281059E26442C -:10DF6000B9F1000F40F01B812168DBF8002022602E -:10DF7000CBF80010009B009823444FF0000AD346D2 -:10DF800004931F460393C0F10008B246B74240F223 -:10DF900096805346DA469B46BAF1000F00F0D381D3 -:10DFA000039A9DE8090000FB0343B91AC4EB020C75 -:10DFB0008C45A8BF8C46BCF1000F019311DDB9F16F -:10DFC000020FCCEB070040F0448104EB0C0A224620 -:10DFD00090F800C0137802F801CB524500F8013BDD -:10DFE000F6D1019B0098CBEB0302C6EB0B06121A8D -:10DFF000B24228BF3246002A10DD0198B9F1020F63 -:10E00000C2EB000340F0428107EB020C18783A782B -:10E0100007F8010B674503F8012BF7D1009A8A42F4 -:10E02000C0F0CE80009CB44246D201980099841B77 -:10E03000A207B6FBF1F601963FF47DAF019A4FF0CF -:10E040000209062A82D8009B03FB024B9846A04493 -:10E05000D84531D25F42DDF800A02346CDF804B0A8 -:10E060004C469946C14523D2464608E03268DBF863 -:10E0700000303360CBF80020CB4519D95E4606EB63 -:10E08000070B58463146A847002811DD002CEDD07B -:10E09000012C00F0A18152465B4631781878013A94 -:10E0A000002A06F8010B03F8011BF6DCCB45E5D886 -:10E0B000019AD0449045D5D307B0BDE8F08F3846DB -:10E0C0002146A84700280DDC36E03268DAF8003037 -:10E0D0003360CAF80020C2444FF0010B4644B742F7 -:10E0E0003FF657AF30462146A8470028C0F290813E -:10E0F000F4D1B9F1000FE8D0B9F1010F0DD00099BA -:10E1000052463346187892F800C00139002903F8C6 -:10E1100001CB02F8010BF5DCDDE7029B50463146EE -:10E12000A4460C680268013B002B41F8042B40F820 -:10E13000044BF6DC6446CEE70FD1B9F1000F40F096 -:10E14000B280039B03981A683B6803603A60039AA5 -:10E15000009B4FF0010B1A4403920098074415E707 -:10E16000019A009B561E282A03FB064631D8B0466A -:10E17000274659463846A84700284146584679DB85 -:10E18000A84700283FF7ECAE38464146A84738EA92 -:10E19000200B28BFBB46B9F1000F3FF4E5AEB9F143 -:10E1A000010F00F09180009A5946234618780F78A5 -:10E1B000013A002A03F8017B01F8010BF6DCD9E6ED -:10E1C0002046009C2B46B1FBF4F12246FFF7A2FE4D -:10E1D00028E74FEAD20803FB08F804EB08074FEAE8 -:10E1E00048023946204692460392A847A244002896 -:10E1F00051463846C0F29B80A847002840F3008172 -:10E20000C8F100039A46DA44594650460493A84799 -:10E21000D8440028414658467EDBA847002840F3F2 -:10E22000E780039ADDF81080C2EB060AB04441464D -:10E230005046A84700283146404652DBA8470028F0 -:10E2400097DC50463146A84736EA200828BFD0461A -:10E250008FE74FEA9C0C22468846116803680CF150 -:10E26000FF3CBCF1000F42F8043B40F8041BF4DC17 -:10E270004146B6E6A8470028FFF672AE384641464A -:10E28000A84737EA200B28BFC34669E692088C46A8 -:10E2900039681868013A002A47F8040B43F8041B50 -:10E2A000F6DC6146BAE6B9F1010F26D00099039B6E -:10E2B0003A46187892F800C00139002903F801CBDA -:10E2C00002F8010BF5DC42E7029A5B4621460F6833 -:10E2D0001868013A002A41F8040B43F8047BF6DC85 -:10E2E00048E6A8470028FFF644AF50463146A84705 -:10E2F0003AEA200828BFB0463BE70399029B38461C -:10E30000A4460C680268013B002B41F8042B40F83E -:10E31000044BF6DC64461AE7A847002881DB504628 -:10E320004146A8473AEA200B28BFC34679E7A847E9 -:10E330000028FFF665AF20465146A84734EA20077B -:10E3400028BF57465CE7019A009B03FB0248049AEA -:10E350004245BFF4B1AE5F42DDF800B023469246BD -:10E360004C46CDF804809946D14522D2564608E065 -:10E370003268D8F800303360C8F80020C84518D992 -:10E38000464606EB070840463146A847002810DD00 -:10E39000002CEDD0012C13D05A4643463178187822 -:10E3A000013A002A06F8010B03F8011BF6DCC84508 -:10E3B000E6D8019BDA449A45D6D307B0BDE8F08F82 -:10E3C000029B414630680A68013B002B46F8042B4B -:10E3D00041F8040BF6DCD1E7029B594630680A6825 -:10E3E000013B002B46F8042B41F8040BF6DC43E616 -:10E3F00050464146A84738EA200B28BFD34610E7CD -:10E4000020465146A8473AEA200728BF2746F7E6A4 -:10E41000B7423FF6BEADB9F1000F09D13A68336893 -:10E420003B60326000994FF0010B0F44761AADE566 -:10E43000B9F1010F0DD0009932463B46187892F899 -:10E4400000C00139002903F801CB02F8010BF5DC0B -:10E45000E8E7029B30463946A4460C680268013B57 -:10E46000002B41F8042B40F8044BF6DC6446D9E756 -:10E47000830770B506461FD10368A3F1013222EA73 -:10E48000030313F0803F08BF031D15D1184653F84E -:10E49000044BA4F1013525EA040414F0803FF5D0C3 -:10E4A00003782BB1431C1C7818460133002CFAD199 -:10E4B00000F07EF8304670BD3046F1E7C9B2F0B4E6 -:10E4C000002947D085070FD00278002A3FD091421B -:10E4D0003ED0431C05E013F8012B002A37D09142AF -:10E4E00036D09A071846F6D1036841EA012747EA71 -:10E4F000074783EA0702A2F10135A3F1013425EAB7 -:10E50000020224EA0303134313F0803F11D1021DDA -:10E51000104652F8043B83EA0704A4F10136A3F144 -:10E52000013526EA040425EA0303234313F0803F60 -:10E53000EED00378002B39D0994209D0431C01E07A -:10E54000914205D0184613F8012B002AF8D1104645 -:10E55000F0BC704784070BD00378002BF8D0431C25 -:10E5600003E002780133002AF2D099071846F8D167 -:10E570000368A3F1013222EA030313F0803F0AD1BA -:10E58000031D184653F8042BA2F1013121EA0202BF -:10E5900012F0803FF5D00378002BD9D0431C1A78B5 -:10E5A00018460133002AFAD1F0BC70471846CFE76D -:10E5B00080EA0102844612F0030F4FD111F0030FDD -:10E5C00032D14DF8044D11F0040F51F8043B0BD03B -:10E5D000A3F101329A4312F0803F04BF4CF8043B90 -:10E5E00051F8043B16D100BF51F8044BA3F101329E -:10E5F0009A4312F0803FA4F101320BD14CF8043B56 -:10E60000A24312F0803F04BF51F8043B4CF8044B86 -:10E61000EAD023460CF8013B13F0FF0F4FEA3323F7 -:10E62000F8D15DF8044B704711F0010F06D011F8D6 -:10E63000012B0CF8012B002A08BF704711F0020FC4 -:10E64000BFD031F8022B12F0FF0F16BF2CF8022BAF -:10E650008CF8002012F47F4FB3D1704711F8012BD2 -:10E660000CF8012B002AF9D1704700BF20F00301FC -:10E6700010F00300C0F1000051F8043B00F1040C5D -:10E680004FEACC0C6FF000021CBF22FA0CF21343CD -:10E690004FF0010C4CEA0C2C4CEA0C4CA3EB0C0296 -:10E6A00022EA030212EACC1204BF51F8043B043000 -:10E6B000F4D013F0FF0F1FBF013013F47F4F013070 -:10E6C00013F47F0F18BF0130704700BFF0B4064647 -:10E6D000FAB1114B1F6804E0E81A18D1BBB1013A36 -:10E6E00017D016F8014B3B195B78254603F003035E -:10E6F000012B11F8013B08BF04F12005F818407800 -:10E7000000F003000128E7D12033E81AE7D0F0BC7D -:10E7100070471046F0BC7047A001002040EA01039A -:10E720009B0770B42AD1032A28D90C4603462146F8 -:10E7300054F8045BA5F1013626EA050616F0803F81 -:10E7400005D1043A032A43F8045B2146EFD89AB175 -:10E750000C78013A1C7001333CB16AB111F8014FD9 -:10E76000013A03F8014B002CF7D12AB11A440021D9 -:10E7700003F8011B9342FBD170BC70470346E6E7E8 -:10E780004FF0010C2DE9F003644600254FF0FF36F1 -:10E7900063198B4200EB06070DD23F5D10F8038032 -:10E7A000B8452ED21D460124C6EB030C63198B42DB -:10E7B00000EB0607F1D34FF00109C2F800C04C4648 -:10E7C00000254FF0FF376319994200EB070C0ED973 -:10E7D0001CF804C010F80380E04519D91D46012437 -:10E7E000C7EB03096319994200EB070CF0D8701CC2 -:10E7F0000137874224BF3846C2F80090BDE8F003D5 -:10E8000070470CD04FF0010C2E4664466544BFE7BC -:10E8100009D04FF001092F464C464D44D3E76445DB -:10E8200005D00134B4E74C4504D00134CBE71D4694 -:10E830000124ADE71D460124C5E700BF2DE9F04FD7 -:10E84000ADF21C4D164607460D461046194605AA60 -:10E850001C46FFF795FF05AB80460DF2144243F8C6 -:10E86000044F9342FBD15CB104F1FF3E002306A8A4 -:10E87000F25CC3EB0E010133A34240F82210F7D142 -:10E88000059930463144424600F010FB002879D10A -:10E8900008F1FF3C0346CDF808C0B4448246CDF8E9 -:10E8A00004802846CDF80CC01D46A04608E025B1DE -:10E8B000059A934238BFC2EB08039A4400252046CC -:10E8C0000AEB0804221A0021384400F0A5FA0028B7 -:10E8D00053D1002C51D03B1913F8012C06AB53F83F -:10E8E0002230002BE3D1019A08F1FF39954228BF6D -:10E8F0002A464A4511D207EB0A03985C16F802C073 -:10E90000B118844506D031E011F8010F13F802C0A8 -:10E9100084452BD101324A45F6D3019B02989D4292 -:10E9200028BF18461AD2DDF808C007EB0A0313F80F -:10E930000C20DDF80CC09CF8001091426ED16246AC -:10E9400006EB050B06E012F8019D13F801C0E14546 -:10E9500004D108465A4500F1FF31F4D10135854212 -:10E960005ED8059DAA44C5EB0805A8E701990025D6 -:10E97000C1F101039A449244A1E700200DF21C4D1D -:10E98000BDE8F08FC8EB0403434538BF434601336D -:10E99000284605934FF0000A06EB08094546A346B2 -:10E9A0000AEB0B04221A0021384400F035FA002843 -:10E9B000E3D1002CE1D03B1913F8012C06AB53F83E -:10E9C00022301BBB0BF1FF38454507EB0A0012D282 -:10E9D000435D99F800209A4218BF2B4619D14A4648 -:10E9E0002B4605E012F8011F10F803C08C4510D12A -:10E9F00001334345F6D36B1E1DB9BFE713F1FF3357 -:10EA0000BCD3F15CC25C9142F8D0059B9A4420468D -:10EA1000C6E7C5F1010292449A44F8E701989DE7E0 -:10EA200007EB0A00AAE700BF2DE9F04F037887B093 -:10EA300082460E46002B00F0EE800A789AB1074617 -:10EA40000131012502E011F8012B5AB1934214BFA4 -:10EA5000002505F0010517F8013F0C46002BF2D107 -:10EA6000237823B93DB1504607B0BDE8F08F0020B0 -:10EA700007B0BDE8F08F0AF101003178FFF71EFD05 -:10EA8000A41B80460028F2D0012CEDD0A2445045B2 -:10EA900094BFC0EB0A0501251F2C07D92946324631 -:10EAA0002346FFF7CBFE07B0BDE8F08F214605AA4D -:10EAB0003046FFF765FE05998146024631443046EF -:10EAC00000F0F4F900285BD1034609F1FF30029011 -:10EAD00030440390CDF804909A46284699460AEBB4 -:10EAE00004073A1A0021404400F096F90028BED1EC -:10EAF000002FBCD0019B994528BF4B469C4212D9A0 -:10EB000008EB030212F80A10F05CF21888422FD1C9 -:10EB100008EB0A0504E012F8011FE85C884227D1DF -:10EB200001339C42F7D8019B02994B4576D9039853 -:10EB300008EB0A0C1CF8013002789A426ED10346A9 -:10EB400006EB090B06E013F8015D1CF80200854294 -:10EB500004D111465B4501F1FF32F4D109F10109FD -:10EB600089455DD8059B9A44C3EB04093846B6E74E -:10EB700001994FF00009C1F1010292449A44F5E76E -:10EB8000C9EB04034B4538BF4B4601332846059378 -:10EB90004FF0000B06EB09074D460BEB0409C0EBE9 -:10EBA00009020021404400F037F900287FF45FAFEC -:10EBB000B9F1000F3FF45BAFAC4298BF08EB0B001C -:10EBC00014D908EB050313F80B303A789A421CD19C -:10EBD0003A462B4608EB0B0005E012F8011F10F82F -:10EBE00003C08C4512D101339C42F6D86B1E25B967 -:10EBF0003AE713F1FF33FFF437AFF15CC25C9142A7 -:10EC0000F7D0059B9B444846C7E72B46C5F1010258 -:10EC100093449B44F7E70C46012521E701999DE7C2 -:10EC200008EB0A0020E700BF024A012312685C32A9 -:10EC300000F002B8D0050020F0B420B3074617F862 -:10EC4000016B0D4601E0A64216D015F8014B002CD1 -:10EC5000F9D1EEB13E4616F8015B0C4600E073B107 -:10EC600014F8013BAB42FAD15DB100233B70166052 -:10EC700006463046F0BC704763B13846DEE737469B -:10EC8000E8E72E46F3E710680028D7D10646F0E7FC -:10EC90001660EEE7176006460370EAE72DE9F00F0D -:10ECA000424C82B0D4F800C001900E4600E02646E7 -:10ECB000344614F8015B0CEB0500407800F00800C6 -:10ECC00000F0FF0A0028F2D12D2D5BD02B2D04BFC0 -:10ECD0007578B41C33F010003CD09946BAF1000F9F -:10ECE0000CBF6FF0004B4FF0004BBBFBF9F8002757 -:10ECF00009FB18BB38460CE0303DAB4219DD7E1CE9 -:10ED000005D0404523D820D009FB0050012714F836 -:10ED1000015B0CEB0506767816F0040FECD116F0CB -:10ED2000030606D0012E14BF57263726AD1BAB4273 -:10ED3000E5DC7B1C15D0BAF1000F21D10AB1EFB987 -:10ED4000116002B0BDE8F00F70475D45DCDD4FF0AB -:10ED5000FF37DCE7302D1AD0002BBED10A239946AD -:10ED6000BCE70199BAF1000F4FF022030CBF6FF01E -:10ED700000404FF000400B60002AE2D0611EDFE748 -:10ED80004042DBE7B41C75784FF0010AA2E7207817 -:10ED900000F0DF00582803D0002B9ED108239CE709 -:10EDA000102365789946023498E700BFA00100203F -:10EDB00030B4044C0D46134601462A46206830BC48 -:10EDC000FFF76CBFD0050020024B13B1024800F0E2 -:10EDD00005B8704700000000E9ED0008014600207A -:10EDE0000246034600F096B838B5094D094C641B3D -:10EDF000A41018BF05EB840505D0013C55F8043D6F -:10EE00009847002CF9D1BDE8384002F007BE00BF9A -:10EE1000301A0108341A0108830770B4C9B240D00F -:10EE2000541E2AB303788B4223D0431C04E0FCB168 -:10EE3000057814468D421CD013F0030F184604F1D8 -:10EE4000FF3203F10103F2D1032C14D8651E54B331 -:10EE500003788B420DD0421C002302E004788C42E0 -:10EE600007D0AB42104603F1010302F10102F5D1D4 -:10EE7000002070BC704741EA0126034646EA064678 -:10EE80001A6818467240A2F1013525EA020212F012 -:10EE9000803F03F10403D9D1043C032C1846EFD87A -:10EEA000D4E71446D0E72046E3E700BF032A70B456 -:10EEB00028D940EA01039B0713D005780C78A542B6 -:10EEC00024D1013A002305E010F8015F11F8014F49 -:10EED000A5421BD1934203F10103F5D1002070BC80 -:10EEE00070470C46034625681E682146AE42184608 -:10EEF00004F1040403F1040304D1043A032A18467C -:10EF00002146F0D8002AD8D11046E8E7281B70BC6B -:10EF1000704700BFF0B5274C85B026680746D6F885 -:10EF20004841002C40D065681F2D1EDD224818B9CD -:10EF30004FF0FF3005B0F0BD4FF4C870039102925E -:10EF40000193AFF3008003990446029A019B0028C5 -:10EF5000EED0D6F848510020256060600546C6F81E -:10EF60004841C4F88801C4F88C013FB96B1C0020EB -:10EF70000235636044F8251005B0F0BD0126AE40AF -:10EF800004EB8500C0F88820D4F88821022F42EADB -:10EF90000602C4F88821C0F80831E7D1D4F88C31D2 -:10EFA0001E43C4F88C61E1E706F5A674C6F8484133 -:10EFB000B9E700BF0C1A0108000000001E1E6464BF -:10EFC0006464646400010103080409040A040B0476 -:10EFD0000C040D040404050406040704FFFF0001EB -:10EFE0000103080409040A050B050C050D050405B9 -:10EFF000050506050705FFFF08F00008C4EF000837 -:10F0000026F00008DEEF00080002010202020302FF -:10F010000402050206020702080409040A040B049C -:10F020000C040D04FFFF00020102020203020402AD -:10F03000050206020702080409040A050B050C056F -:10F040000D05FFFF7F230008372300085323000826 -:10F0500001250008F9220008F5220008752900089A -:10F06000B5270008D1270008A92700083527000880 -:10F07000AF27000800000040000801400100000028 -:10F08000001C0028000000400008014002000000B1 -:10F09000041C00280000004000080140040000009B -:10F0A000081C002800000040000801400800000083 -:10F0B0000C1C002800040040000801404000000033 -:10F0C000001D0028000400400008014080000000EE -:10F0D000041D002800040040000C01400100000055 -:10F0E000081D002800040040000C01400200000040 -:10F0F0000C1D0028002C0140000801400001000008 -:10F10000001B0128002C01400008014000080000FD -:10F110000C1B012800080040000C014040000000CA -:10F12000001E002800080040000C01408000000084 -:10F13000041E002800080040000C014000010000EF -:10F14000081E002800080040000C014000020000DA -:10F150000C1E0028002C014000000040000400406C -:10F16000000800400000040008000C00D007320036 -:10F17000320032003200320032003200C800640037 -:10F18000000041455452313233340030313233348F -:10F1900035363738394142434445464748494A4B5A -:10F1A0004C4D4E4F505152535455565758595A0082 -:10F1B000C940000825410008014100083D41000800 -:10F1C0006541000875410008D54000082D4200083F -:10F1D000E9400008F54000080000803FF704353F93 -:10F1E000F70435BF0000803F0000803FF70435BFC3 -:10F1F000F70435BF0000803F0000803FF70435BFB3 -:10F20000F704353F0000803F0000803FF704353FA2 -:10F21000F704353F0000803F0000803F0000000001 -:10F22000000080BF000080BF0000803F000080BF62 -:10F2300000000000000080BF0000803F00000000D0 -:10F240000000803F000080BF0000803F0000803F42 -:10F2500000000000000080BF0000803F0000803FF1 -:10F26000000000BF0000803F0000803F000000BFA2 -:10F27000000080BF0000803F0000803F000080BF92 -:10F280000000003F0000803F0000803F0000003F82 -:10F290000000803F0000803F0000803F0000003FF2 -:10F2A000000080BF000080BF0000803F000080BFE2 -:10F2B000000000BF000080BF0000803F000000BFD2 -:10F2C0000000803F000080BF0000803F0000803FC2 -:10F2D0000000003F000080BF0000803F000000BF32 -:10F2E000D0B35D3F0000803F0000803F000000BFC2 -:10F2F000D0B35DBF0000803F0000803F0000003FB2 -:10F30000D0B35D3F000080BF0000803F0000003FA1 -:10F31000D0B35DBF000080BF0000803F000080BF11 -:10F3200000000000000080BF0000803F0000803F20 -:10F33000000000000000803F0000803F000000004F -:10F340000000803F0000803F0000803F000080BF41 -:10F35000000080BF000000000000803F00000000AF -:10F360000000803F000080BF0000803F0000803F21 -:10F37000000080BF000000800000803F0000803F50 -:10F3800000000000000000000000803F000080BF7F -:10F3900000000000000000000000803F00000000AE -:10F3A00000000000000080BF0000803F000000005F -:10F3B000000000000000803F00000000000000008E -:10F3C00003010000D0F6000804000000F0F500087A -:10F3D0000400000050F500080201000078F3000866 -:10F3E00000010000000000000600000070F60008A8 -:10F3F0000600000090F50008010100000000000078 -:10F400000400000030F6000806000000D8F20008F2 -:10F4100008000000D0F4000808000000D8F100083F -:10F420000800000058F20008010100000000000080 -:10F4300000010000000000000001000000000000CA -:10F440000400000038F300080600000070F4000813 -:10F4500000010000000000000201000098F3000815 -:10F46000010100000000000000000000000000009A -:10F470000000803F000080BF0000803F000080BF90 -:10F480000000803F000080BF000080BF0000803F80 -:10F490000000803F0000803F0000803F0000803F70 -:10F4A0000000803F0000803F000080BF000080BF60 -:10F4B0000000803F0000000000000000000000008D -:10F4C0000000803F0000000000000000000000007D -:10F4D0000000803F000080BF0000803F000080BF30 -:10F4E0000000803F000080BF000080BF0000803F20 -:10F4F0000000803F0000803F0000803F0000803F10 -:10F500000000803F0000803F000080BF000080BFFF -:10F510000000803F000080BF0000803F0000803F6F -:10F520000000803F000080BF000080BF000080BF5F -:10F530000000803F0000803F0000803F000080BF4F -:10F540000000803F0000803F000080BF0000803F3F -:10F550000000803F000080BF0000803F000080BFAF -:10F560000000803F000080BF000080BF0000803F9F -:10F570000000803F0000803F0000803F0000803F8F -:10F580000000803F0000803F000080BF000080BF7F -:10F590000000803FD0B35DBF0000003F0000803F0F -:10F5A0000000803FD0B35DBF000000BF000080BFFF -:10F5B0000000803FD0B35D3F0000003F0000803F6F -:10F5C0000000803FD0B35D3F000000BF000080BF5F -:10F5D0000000803F00000000000080BF0000803F6E -:10F5E0000000803F000000000000803F000080BF5E -:10F5F0000000803F000000000000803F000080BF4E -:10F600000000803F000080BF000000000000803F3D -:10F610000000803F0000803F000000000000803FAD -:10F620000000803F00000000000080BF000080BF9D -:10F630000000803F000000000000803F000080BF0D -:10F640000000803F000080BF000080BF000000007D -:10F650000000803F000000000000803F0000803F6D -:10F660000000803F0000803F000080BF00000000DD -:10F670000000803F00000000A8AAAA3F0000803FD1 -:10F680000000803F000080BFB0AA2ABF000080BFFA -:10F690000000803F0000803FB0AA2ABF000080BF6A -:10F6A0000000803F00000000A8AAAA3F000080BF21 -:10F6B0000000803F000080BFB0AA2ABF0000803F4A -:10F6C0000000803F0000803FB0AA2ABF0000803FBA -:10F6D0000000803F00000000A8AAAA3F0000000030 -:10F6E0000000803F000080BFB0AA2ABF00000000D9 -:10F6F0000000803F0000803FB0AA2ABF0000000049 -:10F7000024505542582C34312C312C303030332C8D -:10F71000303030312C3131353230302C302A3145D7 -:10F720000D0A0024504D544B3235312C31313532D5 -:10F7300030302A31460D0A0024505542582C3431BD -:10F740002C312C303030332C303030312C353736B2 -:10F7500030302C302A32440D0A0024504D544B32A4 -:10F7600035312C35373630302A32430D0A002450DB -:10F770005542582C34312C312C303030332C303031 -:10F7800030312C33383430302C302A32360D0A00E8 -:10F7900024504D544B3235312C33383430302A32EA -:10F7A000370D0A0024505542582C34312C312C305E -:10F7B0003030332C303030312C31393230302C3045 -:10F7C0002A32330D0A0024504D544B3235312C313E -:10F7D000393230302A32320D0A00B5620601030098 -:10F7E000F00500FF19B56206010300F00300FD15E6 -:10F7F000B56206010300F00100FB11B562060103CA -:10F8000000F00000FA0FB56206010300F00200FCF0 -:10F8100013B56206010300F00400FE17B56206018D -:10F8200003000102010E47B5620601030001030156 -:10F830000F49B56206010300010601124FB56206C9 -:10F840000103000112011E67B562061608000307D6 -:10F8500003000000000031E5B56206080600C8009C -:10F8600001000100DE6A00000000000000C201008B -:10F8700000F7000823F700080100000000E1000085 -:10F8800038F700085AF70008020000000096000050 -:10F890006EF7000890F7000803000000004B00001E -:10F8A000A4F70008C6F70008040000008025000047 -:10F8B000630001086300010841455254313233347A -:10F8C00000002710080423022001000000000000AF -:10F8D0008025000000C201000200000001000000BD -:10F8E0008025000000C201000300000002000000AB -:10F8F00080250000004B0000050000000300000010 -:10F9000080250000004B0000050000000200000000 -:10F910008025000000C2010000000000100000006F -:10F920008025000000C2010001000000200000004E -:10F930008025000000C2010000000000010000005E -:10F940008025000000C20100000000000800000047 -:10F950008025000000C20100000300000400000038 -:10F9600080250000004B000000000000B9080108DD -:10F97000C0080108C5080108D6080108E008010808 -:10F98000EB080108F608010801090108AD080108A3 -:10F990000A090108A7080108130901081D0901083F -:10F9A000280901082E090108310901084109010847 -:10F9B0004809010800000000510901085509010823 -:10F9C0005B09010861090108640901086B09010864 -:10F9D0006E090108730901087F09010882090108FD -:10F9E000880901088F09010899090108A30901087C -:10F9F000AC090108BA090108C6090108CD090108C6 -:10FA0000D3090108E0090108EB090108F809010818 -:10FA100000000000C3060108C706010819A200087B -:10FA2000EE060108F3060108D99C00080707010843 -:10FA300010070108C19C00082D07010832070108C2 -:10FA40007DA200086107010863000108899C000885 -:10FA5000660701086E070108A19B000882070108DC -:10FA600091070108819B0008AB07010863000108AA -:10FA7000CD980008B0070108B4070108D99A00081A -:10FA800001070108D0070108299F0008E3070108C2 -:10FA9000E907010871A10008040801080C08010821 -:10FAA00025A100081B08010820080108B19A0008D8 -:10FAB00043FD000830080108C99F00085E080108DE -:10FAC00052080108F998000857020108630001086C -:10FAD000C198000863000108650801086D08010865 -:10FAE000750801087D080108840801088F080108CD -:10FAF00094080108000000004166726F3332204311 -:10FB00004C492076657273696F6E20322E32204D1B -:10FB100061792032362032303134202F2031333A8F -:10FB200033323A3035202D2028636C65616E666C67 -:10FB3000696768742900417661696C61626C65204F -:10FB4000636F6D6D616E64733A0D0A00257309254C -:10FB5000730D0A0053797374656D20557074696D67 -:10FB6000653A202564207365636F6E64732C20569C -:10FB70006F6C746167653A202564202A20302E312D -:10FB80005620282564532062617474657279290DAA -:10FB90000A004350552025644D487A2C2064657432 -:10FBA00065637465642073656E736F72733A2000C9 -:10FBB0002573200041434348573A202573002E25E2 -:10FBC00063004379636C652054696D653A20256450 -:10FBD0002C20493243204572726F72733A2025649B -:10FBE0002C20636F6E6669672073697A653A2025F9 -:10FBF000640D0A00202564202564000D0A52656208 -:10FC00006F6F74696E672E2E2E00536176696E6772 -:10FC10002E2E2E004D75737420626520616E792042 -:10FC20006F72646572206F662041455452313233E1 -:10FC3000340D0A0043757272656E742061737369C6 -:10FC4000676E6D656E743A20004572726F723A206D -:10FC5000456E61626C6520616E6420706C75672012 -:10FC6000696E204750532066697273740D0A00450F -:10FC70006E61626C65642066656174757265733A65 -:10FC80002000417661696C61626C65206665617413 -:10FC9000757265733A2000496E76616C69642066FE -:10FCA000656174757265206E616D652E2E2E0D0A6C -:10FCB0000044697361626C65642000456E61626C2A -:10FCC000656420000D0A4C656176696E6720434CBF -:10FCD00049206D6F64652E2E2E0D0A0052657365E6 -:10FCE0007474696E6720746F2064656661756C74E6 -:10FCF000732E2E2E004E4709004F4B09004375739B -:10FD0000746F6D206D697865723A200D0A4D6F74BD -:10FD10006F720954687209526F6C6C095069746390 -:10FD200068095961770D0A002325643A0900257393 -:10FD3000090053616E69747920636865636B3A09E1 -:10FD4000007265736574006C6F616400496E766162 -:10FD50006C6964206D6978657220747970652E2EE7 -:10FD60002E0D0A004C6F61646564202573206D6957 -:10FD7000782E2E2E0D0A0057726F6E67206E756DED -:10FD8000626572206F6620617267756D656E74734F -:10FD90002C206E6565647320696478207468722015 -:10FDA000726F6C6C207069746368207961770D0ADA -:10FDB000004D6F746F72206E756D626572206D7587 -:10FDC0007374206265206265747765656E203120EA -:10FDD000616E642025640D0A0043757272656E744D -:10FDE000206D697865723A2025730D0A00417661AD -:10FDF000696C61626C65206D69786572733A200088 -:10FE00004D697865722073657420746F2025730DB9 -:10FE10000A0043757272656E742073657474696E3E -:10FE200067733A200D0A0025732073657420746F80 -:10FE300020004552523A2056616C756520617373FB -:10FE400069676E6D656E74206F7574206F662072C1 -:10FE5000616E67650D0A004552523A20556E6B6E11 -:10FE60006F776E207661726961626C65206E616D7C -:10FE7000650D0A0043757272656E742070726F664C -:10FE8000696C653A2025640D0A0055736167653A0F -:10FE90000D0A6D6F746F7220696E646578205B76F1 -:10FEA000616C75655D202D2073686F77205B6F72C4 -:10FEB000207365745D206D6F746F722076616C7550 -:10FEC000650D0A004E6F2073756368206D6F746F47 -:10FED000722C207573652061206E756D62657220CD -:10FEE0005B302C2025645D0D0A004D6F746F72200D -:10FEF0002564206973207365742061742025640D66 -:10FF00000A00496E76616C6964206D6F746F7220AF -:10FF100076616C75652C20313030302E2E323030C9 -:10FF2000300D0A0053657474696E67206D6F746FCD -:10FF30007220256420746F2025640D0A0061757895 -:10FF40002025752025750D0A00496E76616C69645F -:10FF5000204665617475726520696E6465783A2023 -:10FF60006D757374206265203C2025750D0A004371 -:10FF7000757272656E7420436F6E6669673A2043CE -:10FF80006F70792065766572797468696E67206232 -:10FF9000656C6F7720686572652E2E2E0D0A006DD8 -:10FFA000697865722025730D0A00636D69782025D4 -:10FFB0006400636D69782025642030203020302073 -:10FFC000300D0A0066656174757265202D25730D0C -:10FFD0000A00666561747572652025730D0A006DEF -:10FFE00061702025730D0A00736574202573203D10 -:10FFF00020000D0A456E746572696E6720434C4996 +:1033700053204D210A464423E5E70E4B5B7C1BB1ED +:1033800053204D210246DDE70B4B1B7823B1322041 +:10339000BDE8F047FFF7FEBE084B1F70BDE8F087A1 +:1033A000712000204E0C0020540C0020580C0020EE +:1033B000520C00205F200020510C00204F0C0020F8 +:1033C000014B1870704700BF510C00200F4B1A784A +:1033D000462A17D1598840F24C42914212D11A79AB +:1033E000BE2A0FD193F849240020EF2A0CD113F8FC +:1033F000012B5040064A9342F9D1D0F1010038BF69 +:103400000020704700207047704700BF00F8010897 +:103410004CFC0108C8230380142383701E23C3704F +:10342000012303716423C3804FF49673038128231F +:103430004381704710B50446272006F0F1FA20704A +:10344000102006F0EDFA6070002006F0E9FAA07096 +:10345000002006F0E5FA4FF4E1336360A360E36017 +:1034600023615223E070237510BD000030B51C4C61 +:103470001C4D85B0204605F053F92946204605F03D +:1034800069F905F1240001F0F3FD05F1680005F08C +:10349000F1FD14F8500C02F095FD04F1A60003F0C4 +:1034A000ADFFA4F14C0004F06FFE04F19A0000F0AF +:1034B0009FFE05F1280001F0D5FD05F14B030093B7 +:1034C00005F13803019304F1A403029304F15A00B7 +:1034D000A91D2A4604F1A20303F02CFA05B030BD61 +:1034E000841E0020B81A002008B5054B4FF48272E4 +:1034F00002FB0030034900F59E70FDF767FD08BD33 +:10350000E8190020341E0020F8B5274B46221A7017 +:1035100040F24C425A80BE221A71EF2283F84924AD +:10352000002283F84A2411461F46BB5C01325940F1 +:1035300040F24C439A42F8D11B4B042683F84A14BC +:1035400009F034F90025013E16F0FF061ED03420A4 +:1035500009F040F9154CC4F3090363B13A1902F1BB +:103560007842A2F5FC322046116809F07DF9042862 +:10357000054607D0E7E7204609F058F90428054634 +:10358000ECD0E0E70A4B04349C42E4D109F01AF98C +:10359000042D02D1FFF71AFF20B90A20BDE8F84038 +:1035A00001F05EBFF8BD00BFE819002000F8010877 +:1035B0004CFC0108034B9B6818420CBF0020012003 +:1035C000704700BFE8190020024B9A6810439860CA +:1035D000704700BFE81900202DE9F04FB74AB84DF9 +:1035E00085B010685168B74C40F24C4702AB03C33A +:1035F0003A46002128460AF04DFF00214FF482721E +:1036000020460AF047FF46232B70022003236B71EC +:10361000FFF7DAFF4FF41673A5F8F030FA23A5F898 +:10362000F2302A23A5F8EE304FF4FA73A5F8F630FD +:10363000202385F8F4306E2385F804312B2385F898 +:103640000531212385F8063140F26C7300264FF0D6 +:10365000010840F2DC52A5F8163140F27E43A5F88D +:103660001221A5F8147185F84864A5F8FA60A5F848 +:10367000F860A5F8FC6085F8E26085F8E36085F8FD +:10368000E460A5F8E660A5F8E860A5F8EA6085F8CA +:10369000ED6085F8EC8085F8076185F8386185F87C +:1036A0003A6185F8396185F8106185F8186185F807 +:1036B000196185F81A6185F81B6185F81C81A5F8E8 +:1036C000D03040F23A73A5F8D2304FF47A73A5F8AF +:1036D000D43040F27E53A5F8D63040F2EA53A5F834 +:1036E000D83040F2B4534FF03209A5F8DA3005F57E +:1036F00090704FF4C873A5F8DE300192A5F8DC9005 +:10370000A5F8E09085F81E61FFF794FE40F6AC53F3 +:1037100008201E21AB81E07417230E20A1732376AD +:10372000E17363760B215523A0726420A37121728B +:103730002D231421E0777820DFF8B0A12374617283 +:1037400063772175607350215F48E3755F4B2827CD +:10375000A1774FF00A0B5A21E1726062AE732670B6 +:1037600027716771A67684F807906674E676A6746A +:10377000267784F815B0277384F82180C4F830A028 +:10378000E36323644FF08243E3624FF07C53A3630F +:103790004F4B84F8501063644E4B84F85460A3641C +:1037A0004D4B84F85560E364412384F8513084F82C +:1037B0005660019AA062C4F834A004F15C00A4F839 +:1037C000582084F8529084F8536002F0BBF8042328 +:1037D00084F86030152384F86430404BC4F868A046 +:1037E000E3663F4B3F48236705F58471A4F85A60B0 +:1037F00084F8617084F8627084F8748005F06CF964 +:103800004FF44873A4F8A630C82384F8EB304FF483 +:103810009663A4F8EC3040F2D933A4F8EE3040F6C9 +:103820004303A4F8F03084F8A26084F8A36084F81D +:10383000A47084F8A58084F8A86084F8EAB02346D0 +:103840004FF47F72A4F8AA204FF4FA62A4F8AC20D7 +:1038500002A940F2DC52A4F8AE208A5D013684F859 +:10386000B020082E4FF0FF0284F8B12004F10804C4 +:10387000E6D101221C4883F8F22083F8F32083F874 +:10388000F420FFF7C7FD0023EA1810330021C02BF6 +:103890001161F9D10024281900F59E7009494FF4EF +:1038A000827204F58274FDF791FBB4F5437FF2D187 +:1038B00005B0BDE8F04FFFF727BE00BFD0F5000808 +:1038C000E8190020341E0020000020408FC2753D02 +:1038D000CDCC4C3D0000A04000004040F6287C3F8D +:1038E0003D0A773F96F700082A1F00209A99193F52 +:1038F00008B5FFF76BFD18B9BDE80840FFF76CBECF +:1039000008BD0000024B9A6822EA000098607047E8 +:10391000E819002010B5314C48F20103A2681340A9 +:1039200033B92F4B13401BB94FF40040FFF74CFE47 +:10393000A36803F42033B3F5203F03D14FF40030E4 +:10394000FFF7E0FFA368D90311D51A0702D50820B5 +:10395000FFF7D8FFA3681B0403D54FF40040FFF71F +:10396000D1FFA368D80702D50120FFF7CBFFA368DA +:1039700019070BD51A0403D54FF40040FFF7C2FF17 +:10398000A368DB0702D50120FFF7BCFFA26848F25D +:103990000103134048F20102934203D14FF4004067 +:1039A000FFF7B0FFA26848F24003134048F240021C +:1039B000934202D14020FFF7A5FF0A4804F00EFF12 +:1039C000094806F0ABF9084806F026F920B9064880 +:1039D000BDE81040FFF72EBD10BD00BFE819002064 +:1039E00008000100F01A0020081B002007B5FFF7AF +:1039F000EDFC10B90A2001F033FD104B10491846B8 +:103A000040F24C42FDF7E2FA90F84824022A84BFC3 +:103A1000002280F8482490F848144FF4827202FB88 +:103A20000101084801F59E71FDF7D0FAFFF772FF1A +:103A300003B05DF804EBFFF719BD00BFE8190020E3 +:103A400000F80108341E002008B5FFF7CFFFBDE8DD +:103A500008400F201421012208F0B4B808B5054B26 +:103A600093F84804FFF740FDFFF74EFDBDE808401E +:103A7000FFF7EABFE8190020014B9868704700BFC4 +:103A8000E8190020884203DB9042A8BF1046704727 +:103A90000846704770B504460E461546FDF728FAED +:103AA00030B920462946FDF741FA18B1284670BDC5 +:103AB000304670BD204670BD0023036170472DE97C +:103AC000F041066904460136012E0D46066105D116 +:103AD0000023616021608360BDE8F081D0F8008040 +:103AE00008464146FCF75CFF07463046FDF70EF8F6 +:103AF00001463846FDF712F901464046FCF752FFF1 +:103B00000646606031462846FCF74AFF01463846C3 +:103B1000FDF750F8A168FCF745FF2660E060A06063 +:103B2000BDE8F08110B504460069012807DD0138C1 +:103B3000FCF7ECFF0146E068FDF7F0F810BD00204F +:103B400010BD08B5FFF7EEFFBDE8084009F0ECB97D +:103B500008B5FCF759FC04A3D3E90023FCF7BAFC31 +:103B6000FCF7CAFE08BD00BF399D52A246DF913F57 +:103B70002DE9F041069C002B06460F460CBF4FF086 +:103B800020084FF03008234613F8011B09B91546E9 +:103B900003E0002AFBDD013AF6E7002D04DD3046A4 +:103BA0004146B847013DF8E714F8011B11B1304612 +:103BB000B847F9E7BDE8F081014B186801F080BB18 +:103BC000680C00202DE9F04788B006460F460392A6 +:103BD0001C46039A531C03931178002900F08D8032 +:103BE000252901D0304686E00023911C04930391DF +:103BF0005578302D05D1D31C039395784FF00108EB +:103C000000E09846A5F13003DBB2092B06D8284620 +:103C100003A90A2204AB00F034F905466C2D05D146 +:103C2000039B5A1C03921D78012200E00022632DA1 +:103C30004FD006D8252D5CD0582D2AD0002D5CD031 +:103C4000C7E7732D4AD002D8642D14D0C1E7752D73 +:103C500002D0782D1DD0BCE704F1040905AD206821 +:103C60000A2122B100222B4600F090F80EE02B46EC +:103C700000F0BFF80AE005AD04F104092068294608 +:103C800012B100F0ABF801E000F0DBF84C46009513 +:103C900018E004F1040A0DF11409206810213AB16A +:103CA000B5F15804624262414B4600F06FF806E0FD +:103CB000B5F158035A425A414B4600F09AF854461F +:103CC000CDF8009030463946049A4346FFF750FF3E +:103CD0007FE730462178251DB84708E02368304645 +:103CE00000933946049A0023251DFFF741FF2C4617 +:103CF0006FE730462946B8476BE708B0BDE8F08764 +:103D00000FB407B50A4904AB08680A4953F8042BF5 +:103D100009680193FFF756FF074B186801F0EFFAA7 +:103D20000028F9D003B05DF804EB04B0704700BF81 +:103D3000640C0020600C0020680C0020034A044B37 +:103D40001A60044B00221A60704700BFB93B00089C +:103D5000600C0020640C0020014B1860704700BF0D +:103D6000680C002070B50646B6FBF2F4084615460E +:103D700014B12046FFF7F6FF05FB1464024B1B5DF0 +:103D800000F8013B70BD00BF9FF70008F0B50124AB +:103D9000B0FBF4F58D4201D34C43F9E70026DCB1CA +:103DA000B0FBF4F504FB1500B4FBF1F41EB9002DD3 +:103DB00001DC002CF3D1092D03F101075FFA85FC2A +:103DC00004DD002A0CBF5725372500E03025654467 +:103DD0001D7001363B46E2E71C70F0BD00280B4623 +:103DE00003DA2D2240420A704B1C0A210022FFF701 +:103DF000CDBFF0B50124B0FBF4F58D4201D34C43A7 +:103E0000F9E70026DCB1B0FBF4F504FB1500B4FBC8 +:103E1000F1F41EB9002D01DC002CF3D1092D03F1C2 +:103E200001075FFA85FC04DD002A0CBF5725372502 +:103E300000E0302565441D7001363B46E2E71C700A +:103E4000F0BD00280B4603DA2D2240420A704B1CBD +:103E50000A210022FFF7CDBFA0F13003DAB2092A10 +:103E600001D818467047A0F16103052B01D85738D7 +:103E70007047A0F14103052B94BF37384FF0FF3056 +:103E800070472DE9F8430D6804460F469046994661 +:103E900000262046FFF7E0FF002806DB404504DC53 +:103EA00008FB060615F8014BF3E73D602046C9F80C +:103EB0000060BDE8F883931E232B28BF0A22031E4F +:103EC00010B50C4603DA2D2001F8010B5842FFF71C +:103ED00049FF00230370204610BD000030B587B0B5 +:103EE00005460C4603A800210C220AF0D3FA284606 +:103EF0000021FDF71BF820B128462949FCF752FDA7 +:103F000003E028462649FCF74BFD2649FCF752FE04 +:103F1000FDF716F8054685EAE570A0EBE570694601 +:103F20000A22FFF7C8FF002DACBF20232D236846CF +:103F30008DF80C300AF0A4FE012807D130238DF84B +:103F40000D308DF80E308DF80F300CE0022805D1C1 +:103F500030238DF80D308DF80E3004E0032804BFB7 +:103F600030238DF80D30694603A80AF08BFD03A8B5 +:103F70000AF086FE0338C5B22A4603A920460AF095 +:103F8000D7FE00236355204607490AF07BFD03A9AD +:103F9000204629440AF076FD204607B030BD00BF18 +:103FA0006F12033A00007A44280201082DE9F0411B +:103FB00002780346202A00F10100F9D0092AF7D03F +:103FC0002D2A02D10346414D04E02B2A08BF0346A7 +:103FD0004FF07E551E460024334616F8012BA2F101 +:103FE0003007F9B209290DD839492046FCF7E2FD1E +:103FF00004463846FCF78AFD01462046FCF7D2FC11 +:104000000446E9E72E2A17D1314F334616F8010B43 +:104010003038C2B2092A0FD8FCF778FD3946FCF7D0 +:104020007DFE01462046FCF7BDFC29490446384682 +:10403000FCF7C0FD0746E8E71A7802F0DF02452AE0 +:1040400038D15A782D2A02D10233012604E02B2AD6 +:1040500014BF013302330026013B002713F8012F60 +:10406000303AD1B2092903D80A2101FB0727F5E725 +:10407000B7F59A7F28BF4FF49A77B8464FF07E5134 +:10408000B8F1070F07D908461249FCF793FDA8F1CC +:1040900008080146F4E707F0070737B108460C495E +:1040A000FCF788FD013F0146F7E72EB12046FCF7FB +:1040B00035FE04E04FF07E512046FCF77BFD0146C3 +:1040C0002846FCF777FDBDE8F08100BF000080BF07 +:1040D0000000204120BCBE4C014B00229A8070475A +:1040E000700C0020034BB3F90400D0F1010038BF7D +:1040F00000207047700C0020014B187A704700BFF9 +:10410000700C0020014B01221A727047700C0020C5 +:10411000064BB3F90400064B1B681B7803EB8303C3 +:104120009842D4BF00200120704700BF700C0020CF +:104130007C0C002010B50446FFF7EAFF002814BFEE +:104140002046002000F0010010BD0000074B1A6857 +:10415000074B1178B3F9040053780B4403EB830346 +:104160009842D4BF00200120704700BF7C0C002083 +:10417000700C0020024B9A8801329A80704700BF71 +:10418000700C002070B5FFF7C3FF30B3134C237AD7 +:104190000BB9A38070BD124EB578281C18BF012042 +:1041A000FFF7C8FF88B1012373700E4B1A680E4BDE +:1041B000518919805189598052899A800B4A126815 +:1041C0005288DA80E3880133E380FFF7BFFF00B94C +:1041D0001DB9BDE8704000F061BB70BD700C0020DF +:1041E0005F200020800C0020BA2000207C0C0020E2 +:1041F000024B00221860024B9A8070477C0C002012 +:10420000700C0020044B18600448054B0360002329 +:10421000C3800372704700BF800C0020700C002028 +:10422000C4F70008044B9A8811B21429CCBF143A81 +:1042300000229A80704700BF700C0020032810B540 +:104240000D4B0DD80D4A126894888C4208D2D28842 +:104250008A4205D9012202FA00F01A781043187038 +:104260001B780F2B06D1044B00221A70BDE81040BA +:10427000FFF7D8BF10BD00BF6C0C00207C0C0020E5 +:1042800070B5744C86B0FFF759FDFFF731FBFFF7AF +:10429000ADFBA07B003018BF012001F079F894F845 +:1042A000073133B103F0F702012A02D18DF8003053 +:1042B00004E000238DF8003084F807316846FDF7EC +:1042C0009DF80220FFF776F910B16348FEF7FEFD76 +:1042D0006248634DFEF724FE022004F0F5F96148C0 +:1042E000B4F8EE1094F8ED20B5F95A3000F080FFE4 +:1042F0002E4610B9032001F0B3F80A25192001F069 +:104300003CF8192001F039F86B1E13F0FF05F5D1C8 +:1043100001F0EAFE6079544902F070FBFEF778FD87 +:10432000524805F08DFD63790E2B01D0082B03D187 +:1043300001238DF80B3001E08DF80B5001214B4823 +:1043400005F0B0FC8DF807004020FFF733F98DF839 +:1043500008004FF40040FFF72DF98DF804004FF4EA +:104360000030FFF727F98DF806000120FFF722F94A +:104370008DF8050002F072FF96F8F4308DF8090010 +:10438000C3F380038DF80A30B4F8DE304FF4804078 +:10439000ADF80E30B4F8E030ADF810304FF47A7369 +:1043A000ADF81230FFF706F920B12A4BB3F8DA3036 +:1043B000ADF81230BDF80E30B3F5FA7F84BF00239C +:1043C000ADF81230B4F81231ADF8143094F807316A +:1043D000012B04D0092B01D1072300E0002301A801 +:1043E0008DF80C30FDF7AAFC2148FFF70BFF214D9B +:1043F0002860FEF74DFF1E48296804F029FA4FF4A3 +:104400008070FFF7D7F838B11B4A184894F81E118E +:10441000A2F1F20303F008FF4FF40060FFF7CAF8BF +:1044200008B104F0AFFE00F07DFF144B1860637913 +:10443000052B03D14FF4C87000F0FCFC4FF47A70E8 +:1044400000F01CFE0E4B01225A7300225A7006B077 +:1044500070BD00BFE8190020EC1A0020CE1A002021 +:10446000341E0020CA1A0020F8190020081B002062 +:10447000F01A0020381F00202A1F0020AC0C00205A +:104480005F20002008B5FFF7FBFE00F02DFAFCE7E7 +:1044900008B5034BB3F9D40002F0CCFBFEE700BF34 +:1044A000E819002038B51A4B1A4C5D7D637C15B3B2 +:1044B0006BBBA3789BB100F0EFFF174D08B92B78C9 +:1044C0001BB101F061F900232B70144810F8041C93 +:1044D00001F078F90123124A6374137038BD01F0BA +:1044E00021FAA0B105203221012207F06BFBBDE8C3 +:1044F000384001F049B913B101F0D2F96574A378DD +:104500002BB9074B1B7813B1034B01221A7038BD2E +:10451000712000205F2000209C0C0020381E00200D +:104520008A0C002008B500F08BFC28B100F0ACFD2F +:1045300080F00100C0B205E0022004F0BBF80028C2 +:10454000F4D0012000F0010008BD0000044B1A68FF +:1045500022B900F5F42000F590701860704700BF94 +:10456000A00C0020054A13683BB1C01A002804DBE8 +:1045700003F5F42303F5907313607047A00C00203B +:10458000B24B2DE9F04FB3F90600B14B85B0B3F84B +:10459000582090420FDBB0F5FA6F93F8564007DAD7 +:1045A000811A4C43A2F5FA6294FBF2F4643403E0FE +:1045B000C4F1640400E06424A64A93F85410B2F8ED +:1045C00012C192F9EC2093F8A25093F8A3605242E2 +:1045D00093F8553092B201910021029203930A465A +:1045E0009A4B40F2E637CB5E0093CCEB030303F229 +:1045F000F31EBE4503D8002BB8BF5B4201E04FF469 +:10460000FA73022ADFF858822CD025B1AB42CCBF16 +:10461000C5EB030300236427DFF874A293FBF7FEC6 +:104620006FF0630B3AF81E900BFB0E3B0EF1010E80 +:104630003AF91EA00FFA89FECEEB0A0E0EFB0BFE16 +:104640009EFBF7FECE4428F801E0DDF8048003FB72 +:1046500008FE814B9EFBF3F33B449BB2634393FB09 +:10466000F7F714E026B1B342CCBFC6EB0303002337 +:10467000DDF808E003FB0EF7A8F80470039F002B99 +:10468000B8BF5B427B43744F93FBF7F76437704BC3 +:10469000DFF8008202EB030E9EF80490642307FB10 +:1046A00009F999FBF3F902F808909EF80E909EF82C +:1046B00018E007FB09F907FB0EF7DFF8DC8199FB2F +:1046C000F3F902F80890DDF8008097FBF3F3634FED +:1046D000E045D355624F02DA7B5A5B427B5201328E +:1046E000032A01F102017FF47BAF5A4C4FF4FA62C6 +:1046F000B4F81411FFF7C6F9B4F814314FF47A7511 +:10470000C01A4543C3F5FA63B5FBF3F56421554878 +:1047100095FBF1F36FF0630630F8132006FB0355A9 +:10472000013330F9130013B2C31A5D4395FBF1F165 +:104730004D4D0A446B7A4A4CFA80002B38D04B4BD3 +:1047400018884B4B1B88C01A00B2FFF701FA0646C7 +:1047500008F0E6FA0746304608F056FB0646B4F97C +:104760000200FCF7D3F98046B4F90000FCF7CEF95B +:1047700039468146FCF71EFA314682464046FCF730 +:1047800019FA01465046FCF70BF9FCF7D9FB3946FC +:1047900020804046FCF70EFA314607464846FCF7B3 +:1047A00009FA01463846FCF7FDF8FCF7C9FB6080C2 +:1047B0000220FEF7FFFE2F4C88B12F4A13780133F9 +:1047C000DBB213700622B3FBF2F102FB113313F0DC +:1047D000FF0F04D1FEF742FBFEF762FB207020784A +:1047E000214C003018BF0120FEF758FDAB78C3B94B +:1047F000FFF798FE01232370637B03B923701F4BDF +:104800005B7D0BB100232B702B781D4C1BB11D4B16 +:1048100000221A6002E02068FFF798FE2068FFF788 +:10482000A1FE04F08FFC05F01BFB202003F042FFEB +:1048300018B1134B186803F0CFFE134B9B680BB1F4 +:104840001248984705B0BDE8F08F00BFBA2000209D +:10485000341E0020E81900200CFEFFFF771F002007 +:1048600088200020902000205F2000207E1F002054 +:10487000461F0020A70C0020880C0020712000207B +:10488000840C0020A00C00205C1F00203C1F002096 +:10489000A82000207A1F0020741F0020024B9A7865 +:1048A0000AB100229A7070475F2000200B4B1978E4 +:1048B0001A4651B1997879B9597831B901229A706B +:1048C000074B1A88074B1A807047937823B9022048 +:1048D000FF21012207F076B9704700BF5F2000205A +:1048E0007E1F0020461F00202DE9F84F8C4F03F05B +:1048F000F9FF386804F01EF88A4C002800F0DE81C9 +:10490000386804F0C7F84FF48040FEF753FE20B13A +:10491000854B1B780BB9FFF7C1FF04F0F1F84FF49A +:104920000070FEF747FE88B13B68804A804D934295 +:1049300008D92B681B681B6A984718B92B681B6835 +:104940005B6A98472B681B685B6998470022B4F83C +:104950001451B4F81661134676489B08115E023272 +:10496000A942C4BF63F07F03DBB2B142B8BF43F0DA +:104970004003082A8146EFD16F4EDFF8D8813278A4 +:104980009A4205D198F80020F92A04D8013200E0B3 +:10499000002288F800204FF480403370FEF70AFEB2 +:1049A00058B1B4F81211B4F8DC20B9F90630881AFD +:1049B000834202DD0A4493420ADB4FF48040FEF753 +:1049C000F9FDC8B9B9F90620B4F814319A4213DADE +:1049D00000F0BCFF00F0C2FF584BB3F876305BB17B +:1049E000514B1A78564B002A00F0DF811A78002AC2 +:1049F00000F0DB81FFF75AFF98F80030142B40F0ED +:104A0000BD804F4B4D4D93F802B09A46BBF1000F5D +:104A100018D0B5F8763023B933785F2B01D1FFF782 +:104A20003DFF94F81A31002B00F0A880B5F87630DD +:104A3000002B40F0A38033787D2B40F09F80FFF760 +:104A40002DFF9BE03378572B11D14FF47A7000F093 +:104A500015FB4FF48070FEF7ADFD08B102F036FD96 +:104A6000082003F027FEF0B9364B18801BE0042025 +:104A7000FEF7A0FDB8B1304B1B785A2B13D1324B47 +:104A80001A782AB183F800B0304B01221A700AE07C +:104A90002F4A137883F0010313700BB1022000E05A +:104AA0000320FEF78DFC33785D2B00F085815B2BB6 +:104AB00000F084815E2B00F08381B5F876302BB94D +:104AC00032786F2A02D1FFF7F1FE13E094F81A2131 +:104AD0001AB113B933787E2BF5D03378972B04D1E4 +:104AE0004FF4C87000F0A6F904E0A72B04BF01231F +:104AF0008AF80E303378BB2B03D1B5F85E30023321 +:104B000004E0B72B05D1B5F85E30023BA5F85E3066 +:104B100029E0BE2B20D1B5F85C30023321E000BF84 +:104B2000840C0020E819002071200020404B4C002C +:104B3000381F0020BA200020890C0020341E0020DD +:104B40005F2000207E1F0020940C0020A80C002075 +:104B50008C0C0020A60C0020BD2B0FD1B5F85C30CA +:104B6000023BA5F85C3094F84804FEF7BDFCFEF764 +:104B7000CBFCFEF769FF002388F800300420FEF725 +:104B800019FD48B3974A984B117871B197498978C4 +:104B900059B1B9F90600B4F81411884205DD197845 +:104BA00019B993483225058011705B7C53B1914B44 +:104BB0001A782AB9904A127812B98D4A3221118096 +:104BC000012208E08C4B1A7832B1884A92781AB9DF +:104BD0001A708A4B01221A7089480123002230F88A +:104BE000021F5E1EA1F21555B5F5C77F8CBF0025CB +:104BF00001259D4009B22A4340F21355A942CCBF7A +:104C000000250125B5402A4340F2A465A942D4BF3E +:104C1000002101215D1CA94003330A430D2B92B2F0 +:104C2000DDD100237749704E01EB4301B1F87610D6 +:104C30000A420CBF0021012199550133162BF1D1F5 +:104C400073786A4D23B1022003F034FD68B914E093 +:104C50004FF40070FEF7AEFC78B16B4B1B681B681D +:104C60009B6898470028EED107E0EB783BB900F04D +:104C70006DFE5E4B0122DA7001E00023EB70B37829 +:104C80004BB10023EB702B7933B900F05FFE574B2B +:104C900001221A7100E02B71202003F00BFD08B1F6 +:104CA00003F03EFC337B03B10123AB726379082B25 +:104CB00001D00E2B24D100236B7221E0534D2B68C1 +:104CC000042B1DD8DFE803F00305080B16000123B1 +:104CD0002B602B6801332B602B6801332B602B6812 +:104CE0004FF4807001332B60FEF764FC10B102F0CA +:104CF00013FC05E000234FF400502B60FEF75AFC34 +:104D000000F010FBA2893860414B1AB11968411AB2 +:104D100000293CDB1044186001F006FCFFF730FC72 +:104D200000F000FB3B4B3C491A683860821A18605F +:104D30000A80FFF7B7FB334B93F8A83053B12B4BE6 +:104D4000DA780AB91B792BB1344B354A1188DA88E5 +:104D50000A44DA80202003F0ADFC40B1234BDA791D +:104D60000AB91A7A1AB11B7B0BB103F037FB2D4835 +:104D70002D4B00F14C01B4F8F6201D6800F15803EA +:104D8000A84701F069FF01F0E5FE01F03FFF274B66 +:104D90001B78002B4CD14FF40060FEF70BFC002871 +:104DA00046D0BDE8F84F04F017BA9B78002B3FF4CB +:104DB00023AEFFF773FD1FE6012202E0022200E0AE +:104DC00003225FFA82FB0BF1FF3384F84834FEF7CD +:104DD0009BFBFEF70BFE022028215A4606F0F2FE4E +:104DE0006BE600BF8C0C0020712000205F200020AB +:104DF000A40C00208B0C0020940C0020A80C002098 +:104E0000C0200020341E0020381F0020900C0020FD +:104E1000980C0020AC0C00209E0C00208820002064 +:104E2000980E0020381E0020080000209814002052 +:104E3000BDE8F88F014B1880704700BFBC0C002004 +:104E4000034B1888D0F1010038BF0020704700BF25 +:104E5000BC0C0020204B00222DE9F041196880464F +:104E600013461E4C1E4E25881E4FB5F5C87F04BF45 +:104E70000025F550F05832F907C0194D844446F822 +:104E800003C0043300260C2BD6538E5202F10202CB +:104E9000E7D12388012B19D12B68404603F1C802C2 +:104EA0004FF4C87392FBF3F20A806A68C83292FB2F +:104EB000F3F24A80AA68C83292FBF3F30A4A1288D6 +:104EC0009B1A8B8000F03EFDFEF7C8FD2388013B56 +:104ED0002380BDE8F08100BFC00C0020BC0C002086 +:104EE000C40C0020981F0020040000202DE9F04190 +:104EF000354D04462B88322B0ED1344B1A68344B77 +:104F0000118819805188928859809A80314B028883 +:104F10001A8042885A8001E0002B34D02B490022AD +:104F2000D1F800C013460F46298832292A4904BF08 +:104F30000020C8502948CE5832F900804644CE504F +:104F4000043300210C2B11522CF8021002F1020242 +:104F5000EAD12B88012B13D1214A02201170214A5A +:104F60001370FEF72DFA1A4A3B6811881980518890 +:104F7000928859809A80174B1A885B8822806380B8 +:104F80002B88013B2B80184B1A78DAB1124900228A +:104F90001A700E4B08681B68322290FBF2F01880E2 +:104FA000486890FBF2F058808968204691FBF2F245 +:104FB0000E490988521A9A8000F0C4FCBDE8F041FD +:104FC000FEF74CBDBDE8F081A40C0020C00C002011 +:104FD000B00C0020B80C0020D00C0020981F00203E +:104FE0008B0C0020940C0020A80C00200400002052 +:104FF000064B028819888A1A1A80598842888A1AA8 +:105000005A80998882888A1A9A807047981F00204F +:105010000F4B10B55B6804460E4898470E4B0D4881 +:105020001A780146FEF712F80C4B1B8813B1204684 +:10503000FFF710FF0420FEF7BDFA10B12046FFF77E +:1050400055FFBDE81040064B1868FFF7D1BF00BF01 +:10505000481F0020981F0020B60C0020BC0C002028 +:10506000C00C0020014B1860704700BFC00C00202E +:10507000014B1860704700BFE80C0020014B1880FE +:10508000704700BFEC0C0020034B1888D0F10100E2 +:1050900038BF0020704700BFEC0C00203C4B2DE9CE +:1050A000F74F5B683B4898473B4B3A481A780146B4 +:1050B000FDF7CCFF394B374F1A889846DFF8E8A048 +:1050C000002A3CD0364B00251B68364E93F800B0C2 +:1050D0002C46B8F80030DFF8D490B3F57A7F05D1CC +:1050E0000023304649F80430FEF7E6FC785F59F8B3 +:1050F0000430034449F80430FBF708FD014630460C +:10510000FEF7DDFC00237B532AF80530B8F80030A9 +:10511000012B25D13046FEF714FD0346BBF1000FED +:105120000FD058460193FBF7F1FC019B014618464E +:10513000FBF7FCFE28B1194B4FF47A721A8000235A +:105140001BE059F804304FF47A7203F5FA7393FBBD +:10515000F2F30A200F2101222AF8053006F032FD71 +:1051600004340C2C05F1020506F11406B1D1B8F88F +:105170000030013BA8F80030E1E7F95A3AF8032083 +:105180008A1AFA520233062BF7D103B0BDE8F08F2A +:105190005C1F0020801F0020380D0020EC0C002038 +:1051A000E80C0020FC0C0020760E0020F00C002003 +:1051B000034B0146002203481A70FCF7DDB800BF1C +:1051C000380D00205C1F002003780BB1054A1370D6 +:1051D00043780BB1044A137083780BB1034A137000 +:1051E000704700BF380D0020B60C0020E40C0020F2 +:1051F0002DE9F8438046084614461E46FFF7D8FFBF +:10520000054600284AD0274B0022022C1A70264F50 +:1052100007D0072C01D054B903E0022003F05CFA58 +:1052200005E02248FCF758F808B102233B703B78B0 +:105230002BB90CB11C46E6E7022003F04DFA4046BC +:10524000FFF7C2FF022003F035FA10B1174B1B68BD +:105250009847174B174C1B689847082003F02AFA09 +:105260000746C8B14FF0640896FBF8F52846FBF7EF +:105270004DFC814608FB156000B2FBF747FC0E4968 +:10528000FBF798FC01464846FBF78CFB0B49FBF704 +:1052900091FC3D46206001E0002323602846BDE8E4 +:1052A000F88300BFB60C0020DC0C0020481F002053 +:1052B0005C1F00209C0E00208988883C0000204153 +:1052C00008B503681B68984708BD38B505460C4605 +:1052D00014F8011B19B12846FFF7F2FFF8E738BDB3 +:1052E00008B503685B68984708BD08B503689B6804 +:1052F000984708BD08B50368DB68984708BD08B53E +:1053000003681B69984708BD08B503685B6998473F +:1053100008BD7047024B1A6801321A60704700BF1F +:105320003C0D002010B5094A094913688C681268C1 +:105330009342F8D1074A106811684FF47A725043CB +:10534000001BB0FBF1F002FB030010BD3C0D002080 +:1053500010E000E0400D0020014B1868704700BFCE +:105360003C0D002038B50446FFF7DCFF0546FFF78B +:10537000D9FF401BA042FAD338BD10B504462CB16A +:105380004FF47A70FFF7EEFF013CF8E710BD000024 +:1053900030B587B006F08CFC2648012107F0F2FA00 +:1053A00044F61D20012107F0E1FA0120014607F033 +:1053B000D1FA002507F00AFB06AC4FF6FF736946E9 +:1053C0001D4824F8183D8DF80250FCF77DFC694615 +:1053D0001A48FCF779FC69461948FCF775FC194B2B +:1053E0005A6842F000725A60FFF793FF01A807F075 +:1053F00065FA019B144AF021B3FBF2F3134A1448F7 +:105400001360144B1A684FF47A73B2FBF3F2124B29 +:10541000013A5A60114A82F8231007229D601A60EF +:10542000FCF700FAFCF7D6FB6420FFF7A6FF07B0F5 +:1054300030BD00BF0700400000080140000C0140E3 +:10544000001001400000014040420F00400D0020CC +:10545000005800408801002010E000E000ED00E06E +:1054600040F2DB14604308B5841E2046FFF785FF39 +:105470001920FFF782FFF8E710B1034A034B1A60C7 +:10548000034A044BDA607047EFBEADDEF04F0020F8 +:105490000400FA0500ED00E0034B1878D0F101009C +:1054A00038BF0020704700BF5C0D00202DE9F04F91 +:1054B0009F4B87B01B780591013B012B00F2338194 +:1054C0009C4B1E78864240F02E819B4B1B78022B12 +:1054D00000F02981994D00232B80994B31F916005A +:1054E0009B5D0493049A974B1A70974A1278039223 +:1054F0002AB9964B40421A6802F100421A60FBF743 +:1055000005FB9349FBF70AFC91490446FBF752FB64 +:10551000FBF716FD8D4F80B2D7F800B08C49029092 +:1055200068805846FBF746FBFBF70AFD894AA880CE +:105530001368002118460193FBF7D0FCDFF80892AE +:10554000DFF810A24FF00008834F019B002855D0D0 +:105550003B68204619460193FBF7E8FC019B38B1F4 +:105560007E4B029AC3F800B0744B3C60DA80C0E016 +:1055700018464146FBF7DAFC002800F0BA80784F65 +:105580003B78002B32D120465946FBF709FA4FF001 +:105590007C51FBF7ADFC734C28B160687249FBF796 +:1055A00009FB60600FE060687049FBF703FBDFF800 +:1055B000D4B101905946FBF79BFC019B08B963608D +:1055C00001E0C4F804B001233B70694B049A1B68E6 +:1055D000CAF80080134400229A72039A82F00103F1 +:1055E00089F800305C4BC3F8008082E0594B1C60A6 +:1055F000FFF7B2FE5F4BFA3018607AE0204619469A +:10560000FBF776FC20B1029B4C4ACAF80040D380DD +:105610003868DAF80010FBF7C3F98346FFF79CFE01 +:10562000544B1B68C01A00280DDA58464FF07C51C5 +:10563000FBF77CFC00285CD0464B20461968FBF742 +:1056400075FC002855D0454B38681968FBF76EFC8F +:10565000444C48B10123206844492B80FBF7AAFA47 +:1056600041492060A06809E0022358464FF07E516E +:105670002B80FBF75BFC28B1A0683C49FBF79AFA4A +:10568000A06004E020683849FBF794FA2060384BAA +:105690002C4A1B682E49206892F800B00193FBF752 +:1056A00089FAFBF773FC019B03F80B00A0689B448D +:1056B000FBF76CFC99F800308BF8140083F00103C1 +:1056C00089F80030264BCAF800801A78C7F80080A5 +:1056D0000132D2B2032A01D01A700AE000221A70F5 +:1056E000204B25495868FBF765FAFBF74FFC8BF810 +:1056F0000A0016B92B8864332B8099F800300BB15F +:105700001E4B00E01E4B114A1360059B33F9160037 +:10571000FBF7FCF90E49FBF701FB0C4A0146106848 +:10572000FBF73EF900E0104607B0BDE8F08F00BF80 +:105730005C0D0020B80D0020650D00203E1F0020EC +:10574000ECF700085D0D0020C00D0020B40D002016 +:1057500000002041480D0020440D0020580D00207D +:10576000640D00204C0D00200AD7833FEC51783F98 +:10577000600D0020BC0D002000007A440000A04114 +:105780000000A0C16F12833A044B00221A60044B40 +:1057900000221A70034B01221A707047B40D0020CA +:1057A0005C0D00200600002001464C220148FBF75A +:1057B0000DBC00BF680D002001494C22FBF706BC60 +:1057C000680D0020254B264A1B7870B5032B044634 +:1057D0000E46137003D1BDE87040FFF7EDBF012BFB +:1057E000204D03D1FFF7E0FF002302E0022B01D19F +:1057F00001232B701C4A012313701C4A13701C4A8E +:10580000002313601B4A13601B4B1C4A1C601C4B7B +:105810001E702B781B4DD65C1B4B1C4A1E701C4BFC +:10582000A05D1A60FBF772F91A49FBF777FA344466 +:105830002860A07AFBF76AF91749FBF76FFA6860EE +:10584000207DFBF763F91549FBF7B4F9A860FBF776 +:105850009DFB00232075A37270BD00BF06000020D1 +:105860005C0D0020B80D0020C00D0020640D00204C +:10587000480D0020440D0020600D0020ECF70008CA +:10588000650D00204C0D00205D0D00200000A041A2 +:10589000B40D00200000204100007A445555553FCA +:1058A000F8B5194B194D1A78511E012921D8184BFA +:1058B000184F1C68184B194978681E78FBF77AF95D +:1058C000FBF764FB26441649B072B868FBF772F91F +:1058D000FBF75CFB30752078FBF718F90146FBF706 +:1058E00061F8FBF753FBA37AA0702373237DA375A4 +:1058F00005E0032A03D100221A70012301E02B786E +:1059000001332B70F8BD00BF5C0D002006000020A5 +:10591000600D00204C0D00205D0D002000007A4439 +:105920009A99993F064B10B5186800214FF0010471 +:10593000FBF7D4FA08B14FF0000404F0010010BDE9 +:10594000B40D00200023038043807047024B0022E7 +:105950001A605A60704700BF0C0E0020054B0022F1 +:105960001A605A609A60044B00221A605A609A606A +:10597000704700BF000E0020C40D0020044B987833 +:1059800018B1587C003018BF012000F001007047AA +:105990005F2000202DE9F04F87B00593884B0492DB +:1059A000B3F90220B3F90030002AB8BF5242002BED +:1059B000B8BF5B4200249A42B8BF1A4680460392A1 +:1059C0002546A14627460294019426467D4BDA7867 +:1059D00012B91B79002B54D0022E52D0784BDDF82F +:1059E00010C0E85E784BCCF10001EB5E624603EB41 +:1059F0004000FEF747F8DFF8F8A1DDF814C035F9EC +:105A00000AB03CF90530CBEB000000EB030BFFF7CD +:105A1000B5FFA0B16D4B5846F35C0093FBF776F8E9 +:105A20006B49FBF77BF9009B024651461846FFF78E +:105A30003DFD6749FBF7BEF8FBF782FA834698F80D +:105A4000070098F81B2000FB0BF064236FF00401A3 +:105A500090FBF3F0514302EB8202FEF713F8DFF8FC +:105A600094A1019054F80A005A49584442F2107225 +:105A7000FEF708F898F8113044F80A00584300136C +:105A80000290504BDA781AB11B790BB9022E33D140 +:105A90004B4B5020EF5EDFF844A1784318F80630F6 +:105AA00035F90A20DFF8509190FBF3F0042392FBC4 +:105AB000F3F3C01A54F809304FF47A5218444649A7 +:105AC000FDF7E0FF35F90A3049F80400002BB8BFB4 +:105AD0005B42B3F5206FC4BF002349F8043059F886 +:105AE00004207D2392FBF3F908EB06039B7A03FB6A +:105AF00009F9402399FBF3F9324B1A79D2B1022EFE +:105B000018D0DDF80CC04FF4FA710CFB07F2CCF59D +:105B1000FA73DDF804C003FB0C22DDF80CC092FB25 +:105B2000F1F20CFB09F0DDF808C003FB0C0393FB5A +:105B3000F1F308E0DB780BB1022E02D14B463A4676 +:105B400001E0029B019A2549DFF8B0B0695A0420B0 +:105B50000FFA81FC16F80BB09CFBF0FA0BFB0AFB6A +:105B60006FF04F0A9BFBFAFA02EB0A0B1C4A35F95D +:105B700002A0A952CAEB0C0C9CFBF0F0194ADFF80A +:105B800080C054F802A054F80C10A050164A51449A +:105B9000B25C01445143202291FBF2F15B1A13489D +:105BA00001369B44032E44F80CA025F800B004F104 +:105BB000040405F102057FF409AF07B0BDE8F08FDA +:105BC000882000205F2000206A110020EEF70008E6 +:105BD00000002041F0D8FFFF80C1FFFF700E0020C1 +:105BE000200E0020400E0020771F00206E1F002096 +:105BF000A00E00200C0E0020000E00207A1F0020B6 +:105C0000DC0D00202DE9F04F89B006936E4B8046E5 +:105C100018880591FAF776FF6C49FAF7CBFF002454 +:105C20000490474625462646022EDFF8E4910BD124 +:105C3000059AB9F9040053790A335843FAF766FF15 +:105C40006349FBF76BF844E0624B39F90500EB5E02 +:105C5000614918444FF4FA72FDF714FFDFF8B4A15C +:105C6000069B35F90A20595F801A0844FAF74EFF5F +:105C70005A49FBF753F88346FFF780FE30B1584A84 +:105C80005146905D5A46FFF711FC8346DFF888A124 +:105C90009AF80320C2B9059B39F905001A79143224 +:105CA0005043FAF733FF4A49FBF738F89AF80430C3 +:105CB00081467BB1D8F848105846FAF77BFF014679 +:105CC0004846FAF76FFE04E05846D8F84410FAF751 +:105CD00071FF8146434B0136585FFAF717FF424B7D +:105CE0000437D968FAF766FF824651464846FAF704 +:105CF00057FEF9698346FAF75DFFDFF820910499B2 +:105D000007905846FAF756FFB96AFAF753FF54F866 +:105D10000910FAF747FE354A3549FDF7BBFE44F84E +:105D20000900DFF8FC90834654F809105046FAF752 +:105D300037FE44F809A0024604994FF07E500192C4 +:105D4000FAF7ECFF019A01461046FAF733FF294BA8 +:105D5000294A54F803C0A158814660460192029333 +:105D6000CDF80CC0FAF71EFE4946FAF71BFEDDF827 +:105D70000CC0029B019A214944F8039044F802C0E8 +:105D8000FAF7CCFF796BFAF715FF1D4A1D49FDF7AD +:105D900081FE594681460798FAF704FE4946FAF70C +:105DA000FFFD06F0F3FF18494FF47A72FDF76AFE23 +:105DB000164B032E585304F1040405F102057FF439 +:105DC00033AF09B0BDE8F08F9E0C0020BD3786359B +:105DD000000048426A1100200CFEFFFF0000204135 +:105DE000EEF70008700E00205C1F002000007A43D0 +:105DF00000007AC3F40D0020D00D002000004040C8 +:105E000000009643000096C318FCFFFF6E1F0020A1 +:105E100088200020A00E00205F200020C40D00205C +:105E2000280E00202DE9F04F002485B007468A4651 +:105E30009346039306462546022DDFF87C814FEA00 +:105E4000450907D19AF80520B8F904301B325343AD +:105E50005B1144E04D4A38F9150032F91520CBF1B9 +:105E6000000102EB40005A46FDF70CFE484B33F9A7 +:105E70001520039B801A33F9151042180192FFF781 +:105E80007DFD019AB8B14349104615F801C0CDF81F +:105E900000C0FAF73BFE4049FAF740FFDDF800C0CA +:105EA00002463B496046FFF701FB3B49FAF782FE99 +:105EB000FBF746F802463949C87868B99AF80400F1 +:105EC00038F909301B30434309791B1139B1797C0A +:105ED0004A4303EB222302E0FB795A431311304A71 +:105EE000785D32F90980042298FBF2F8C8EB0308C8 +:105EF00000FB08F0DFF8C4C0C0110290BCF800003D +:105F0000284B00FB08F0E258B17AC01201FB0020D8 +:105F10002549E0504FF400120193CDF800C0FDF781 +:105F2000B1FD019BDDF800C0E050204B4FF6FF7241 +:105F3000E15844F80380BCF80030C1EB08011B09AC +:105F4000B2FBF3F35943DFF878C0194B891154F8C9 +:105F5000038054F80C20E150029B424403EB603074 +:105F6000337D0A445A430135124B00EB2222032DA4 +:105F700044F80C8023F8092006F1010604F104041A +:105F80007FF45AAF05B0BDE8F08F00BF6A11002062 +:105F9000A00E0020EEF70008000020415F20002046 +:105FA000700E0020000E00200000E0FF140E002004 +:105FB000E80D00206E1F0020882000209E0C00208D +:105FC000340E00200128054B03D0022803D0044AD8 +:105FD00002E0044A00E0044A1A607047080000200A +:105FE00095590008255E0008055C000800000000C7 +:105FF0002DE9F84F384E04463768384606F090FED3 +:106000000546384606F000FF76688046304606F0C2 +:1060100087FE8346304606F0F7FED4F80490064625 +:1060200029464846FAF7C6FDA768824641463846E3 +:10603000FAF7C0FD01465046FAF7B2FC21688246E5 +:106040005846FAF7B7FD414604464846FAF7B2FD0E +:106050003146FAF7AFFD01462046FAF7A3FC314678 +:1060600004463846FAF7A6FD2946FAF7A3FD01468D +:106070002046FAF797FC0146504606F053FF1749B1 +:10608000FAF798FDFAF7D2F911A3D3E90023FAF74A +:106090004BFB134B044618680D46FAF7C7F9024646 +:1060A0000B4620462946FAF763F800220D4BFAF713 +:1060B0003BFBFAF721FC06F069FE83B21A0444BFE9 +:1060C00000F5B4739BB218B2BDE8F88FAFF300804F +:1060D000182D4454FB210940680E00200000E144C3 +:1060E0009C0E00200000244010B5254C2088FAF7B3 +:1060F0000DFD2449FAF75EFD06F048FE224B18809C +:106100002088FAF703FD01462048FAF707FE2049E8 +:10611000FAF704FE1F4B18601F4BB3F8A600FAF7FE +:10612000F5FC01461D48FAF7F9FDFAF77FF90EA3D1 +:10613000D3E90023FAF7CEF9FAF7DEFB184B186023 +:10614000184BD868FAF772F909A3D3E90023FAF7D4 +:10615000C1F909A3D3E90023FAF7BCF9FAF7CCFB9C +:10616000114B186010BD00BF3B597E90A9E78140DC +:10617000399D52A246DF913F000000A0F7C6B03E15 +:1061800004000020C903683F600E00200AE81C419B +:1061900000401C46941F0020341E00200000614473 +:1061A000B01F00205C1F0020B41F0020AFF3008050 +:1061B0002DE9F041044600680D460146FAF7FAFC65 +:1061C000D4F80480064641464046FAF7F3FC0146FF +:1061D0003046FAF7E7FBA768064639463846FAF72D +:1061E000E9FC01463046FAF7DDFB06F09DFE002192 +:1061F0000646FAF773FE70B920683146FAF78EFD4D +:10620000314628606068FAF789FD31466860A06809 +:10621000FAF784FDA860BDE8F0812DE9F04F0C6825 +:10622000836889B0D0F800A0D0F8048006462046E4 +:1062300003938B4606F074FD0746204606F0E4FD06 +:10624000DBF804408146204606F06AFD05462046FC +:1062500006F0DAFDDBF8082004461046019206F04D +:106260005FFD019A8346104606F0CEFD3946029046 +:106270005846FAF79FFC394604900298FAF79AFCC0 +:10628000594605904846FAF795FC0299069048460B +:10629000FAF790FC294607905846FAF78BFC01461E +:1062A0005046FAF787FC214683460698FAF782FCA7 +:1062B00001460598FAF776FB01464046FAF77AFC64 +:1062C00001465846FAF76EFB214683460498FAF7D2 +:1062D00071FC01460798FAF763FB01460398FAF749 +:1062E00069FC01465846FAF75DFB3060029905F1FA +:1062F0000040FAF75FFC01465046FAF75BFC214686 +:1063000083460798FAF756FC01460498FAF748FBCB +:1063100001464046FAF74EFC01465846FAF742FB62 +:10632000214683460598FAF745FC01460698FAF798 +:1063300039FB01460398FAF73DFC01465846FAF747 +:1063400031FB214670605046FAF734FC294604467A +:1063500009F10040FAF72EFC01464046FAF72AFC04 +:1063600001462046FAF71EFB394604462846FAF74E +:1063700021FC01460398FAF71DFC01462046FAF776 +:1063800011FBB06009B0BDE8F08F80EAE073A3EBC9 +:10639000E0738B4206DB002801DD401A704702D013 +:1063A00008447047002070472DE9F041524B86B0F9 +:1063B0001A685B6802F1004203F1004301934F4BFE +:1063C0000646B3F900000092FAF7A0FB00F1004086 +:1063D000FAF72CF846A3D3E90023FAF77BF8FAF78B +:1063E0008BFA474C0290B4F90000FAF78FFB039048 +:1063F000B4F90200FAF78AFB0490B4F90400FAF742 +:1064000085FB404D0590694603A8FFF706FF95F808 +:106410007430012B15D13C4B3C4C9B7863B92368FD +:10642000402093FBF0F0181AFAF770FB0599FAF781 +:10643000B9FAFAF785FD20602068402390FBF3F05D +:1064400001E0334B1888FAF761FB01460598FAF72B +:10645000A7FA05903046FAF755FB2E490746FAF79A +:10646000A1FA01463846FAF759FCDFF8B88007462A +:10647000D8F8004005982146FAF792FA01463846C6 +:10648000FAF798FB01462046FAF78CFA224C0746A9 +:10649000C8F800000398D4F8008006F077FC95F85F +:1064A0006210FFF772FF404420600498D4F8048023 +:1064B00006F06CFC95F86210FFF767FF40446060DF +:1064C0003846D4F8088006F061FC95F86110FFF7B3 +:1064D0005CFF124B40441A68A06016441E60104BCB +:1064E0001A6801321A6006B0BDE8F081AFF300808F +:1064F000399D52A246DF913F680E00207E1F00208A +:10650000A81F0020341E00205F200020640E002001 +:10651000040000203661823C881F0020800E00208D +:10652000940E0020900E00202DE9F04F89B0FEF768 +:10653000B5FD022002F0BEF89B4D9C4F002800F0F4 +:10654000B2819B48FEF764FDFEF7ECFE994C0646CF +:106550002368C3EB00094846FAF7D4FA964B19684A +:10656000FAF728FB954A266092F8603000260390DF +:1065700002933446B246285FFAF7C8FA0399FAF74D +:1065800019FB029A0DF1140848F806005AB3104698 +:10659000FAF7BCFA01464FF07E50FAF7BFFBDFF87E +:1065A00050B2024611464FF07E500092FAF7F8F9C9 +:1065B00056F80B10FAF7FEFA8446385FCDF804C09F +:1065C000FAF7A4FA009A1146FAF7F4FADDF804C0D3 +:1065D00001466046FAF7E6F94BF80600FAF7B0FC18 +:1065E000774A105302E0395B754AA152744A043667 +:1065F000A15E0234062C01FB01AA9346BBD1714A6D +:106600006424128804FB0AF352436F48414693FB0B +:10661000F2F4FFF702FE082002F04CF820B16B48BC +:106620004146FFF7FAFD07E069484146FFF7F5FDEF +:1066300067480146FFF7BCFD493C664EA4B23B2CBF +:10664000B6F8F00006D90820B6F8F24002F032F8A9 +:1066500048BB53E0FAF756FA4FF07E518046FAF7FE +:10666000A1F901464FF07E50FAF758FB0024074687 +:10667000DFF854A140465AF81410FAF79BFA034683 +:106680003BF904000193FAF741FA019B01461846D1 +:10669000FAF788F93946FAF78DFA4AF81400023405 +:1066A000062CE5D1CFE74B4BB3F8F200FAF72AFA04 +:1066B00080462046FAF726FA4FF07E51FAF772F933 +:1066C00001464FF07E50FAF729FB002407463F4E63 +:1066D000404656F81410FAF76DFA3F4B8246185FA1 +:1066E000FAF714FA01465046FAF75CF93946FAF718 +:1066F00061FA46F814000234062CE8D1374B324CCC +:10670000B3F90000FAF702FAA668014630464FF0E6 +:106710000107FAF70BFC00B90746314B31466068B8 +:106720005F7306F0FFFB2F4ED4F808A0306020689E +:1067300000F1004760680146FAF73CFA514680468E +:106740005046FAF737FA01464046FAF72BF906F0B9 +:10675000EBFB0146384606F0E5FB70603068F9F760 +:1067600065FE0FA3D3E90023F9F7B4FEFAF7C4F8E6 +:1067700006F00CFB1C4F38807068F9F757FE08A331 +:10678000D3E90023F9F7A6FEFAF7B6F806F0FEFA09 +:106790007880082001F08EFF144E58B30B482AE091 +:1067A0003B597E90A9E78140801F0020981F002060 +:1067B000901E00205C0E0020B41F0020341E00201C +:1067C000A81F002004000020B81F0020500E002049 +:1067D0000C000020E8190020541F0020600E00204B +:1067E0005F200020680E0020A00E00207E1F0020E9 +:1067F000840E00204048FFF7FBFB30804846FFF73F +:10680000D3FD3E4A92F8A830002B4FD0206867682D +:106810000146FAF7CFF9394606463846FAF7CAF97B +:1068200001463046FAF7BEF8A468064621462046DF +:10683000FAF7C0F901463046FAF7B4F806F074FBEF +:1068400001462046FAF76AFA2D490646FAF75AFB3E +:106850002C4C10B10023238028E0304606F012FBB8 +:10686000294B1968FAF7A6F906F090FAB0F5617F9E +:10687000A8BF4FF46170F9F7C7FD1DA3D3E900234A +:10688000F9F752FFFAF738F806F0BEFA1B4B064646 +:1068900093F8A800FAF73AF93146FAF78BF906F0BF +:1068A00075FA208002E038807880B880174B5B79D9 +:1068B000012B174B06D02A881A806A885A80AA882A +:1068C0009A8010E0134AB5F90410B2F9000001EB08 +:1068D0004001032091FBF0F189B211802A88998050 +:1068E0001A806A885A8009B0BDE8F08FAFF3008043 +:1068F000A2EB0FE5DD1696400C000020341E0020B0 +:106900008FC2753C980E0020B01F0020E8190020AF +:10691000700E00204C0E002010B5054C0020218880 +:10692000FBF74EFB61880120BDE81040FBF748BB38 +:106930001800002010B5094C206009480160094981 +:106940000A60094A1360094A029B1360084A039BC4 +:106950001360084A049B136010BD00BFA40E002002 +:10696000800F0020840F0020B00E0020AC0E00200D +:10697000B80E00207C0F00200A4B1A6802EBC00200 +:10698000D379FF2B07D008490978994203D9074AE0 +:1069900032F8130004E00728D4BF908840F2DC509E +:1069A00000B27047A40E0020B6200020BA200020BC +:1069B000054B1B6803EBC00090F9063019420CBF71 +:1069C00001204FF0FF307047A40E002010B50024C6 +:1069D0004FF48040FCF7EEFD08B1054B00E0054B9D +:1069E0001B68054A9B88A3520234182CF0D110BDB5 +:1069F000800F0020840F0020DC1F00202DE9F041D3 +:106A00003B4BDFF80481C400187008EB04035B788B +:106A1000384E054620200F463360FCF7CBFD42463A +:106A200008B101233360162D1AD1002438590021F2 +:106A3000FAF754FA28B14FF48040FCF7BBFD48BB8D +:106A400024E02D4E3B1926440FCB86E80F002B4B3C +:106A500010341A78C02C02F101021A70E6D1EAE76C +:106A6000144412F83570254BD4F804E01F70BEF1C1 +:106A7000000FE0D00024BC42DDDA1F4E23011E448B +:106A800073440FCB013486E80F00F4E7082D1C4B4C +:106A900024D125E0194B1F78012FF7D9194C002676 +:106AA000BE4204F11004F1DA54F8100C4FF07C519E +:106AB000FAF780F84FF07C5144F8100C54F8140C9D +:106AC000FAF778F84FF07C5144F8140C54F80C0C99 +:106AD000FAF770F8013644F80C0CE1E70E2D01D1FD +:106AE000012200E000221A74BDE8F041FFF76EBFFA +:106AF000A80E0020880F0020BC0E0020B60E00203B +:106B00005F200020C40E0020D0F900082DE9F041DC +:106B10008C46461C002300224CF803201033C02B67 +:106B2000F9D10B4B03EBC602576898466FB10024AE +:106B300018F836309C4208DA23010CEB03053B447D +:106B40000FCB013485E80F00F2E7BDE8F08100BF0C +:106B5000D0F90008284B10B51B68002B4AD0274BF2 +:106B60001B78013B142B3DD8DFE803F00B3C3C24A1 +:106B7000403C3C1C3C3C3C3C3C2C3C3C3C3C3C2499 +:106B80002C001F4B1B685B7833B11E4B00205989CA +:106B9000BDE81040FBF714BA1B4B98780028F4D1DD +:106BA0000146F5E7174C0020E188FBF709FA0120C0 +:106BB0002189EDE7134C00202189FBF701FA012020 +:106BC0006189E5E70F4C0020E188FBF7F9F9012026 +:106BD0002189FBF7F5F902206189FBF7F1F9032020 +:106BE000A189D5E72020FCF7E5FC18B1BDE81040ED +:106BF000FFF792BE10BD00BF880F0020A80E002036 +:106C0000B00E0020180000205F20002010B50023E7 +:106C1000D8B25C1C054B1B78834206D9044B33F871 +:106C20001010FBF7C1F92346F2E710BDB60E0020A5 +:106C3000C41F0020064B1A780023D9B2914204D217 +:106C4000044921F813000133F7E7FFF7DFBF00BF66 +:106C5000B60E0020C41F00202DE9F74FA94E33784F +:106C6000032B0FD9A84BA94CB3F904206FF0630193 +:106C7000002AB8BF5242891AB4F904006432FCF702 +:106C800001FFA0803778012F1ED8A14AA14C1378AC +:106C90009046013B142B00F2D281DFE813F0910003 +:106CA000D001D00168009F00D001D0012901D0019E +:106CB000D001D001D001D001BD00D001D001D00160 +:106CC000D001D0019201A9018F4B9349B3F806A0DE +:106CD0008E4B0968B3F80280B3F80090B3F904B0A2 +:106CE0008E4C01910025BD4204F11004CDD20FFA63 +:106CF0008AF0F9F70BFF54F8101CF9F75BFF034615 +:106D00000FFA88F00093F9F701FF54F8081CF9F71F +:106D100051FF009B01461846F9F744FE03460FFA5F +:106D200089F00093F9F7F2FE54F80C1CF9F742FFD2 +:106D3000009B01461846F9F735FE019A034692F981 +:106D40000000009340420BFB00F0F9F7DFFE54F81F +:106D5000041CF9F72FFF009B01461846F9F722FEA5 +:106D6000FAF7EEF86E4B23F815000135BBE7022168 +:106D70000420FFF71DFE654D0121AF8878431FFAFF +:106D800080F90420FFF714FE6D8800FB05901FFAC0 +:106D900080F90420FFF7F0FD4844208102210520FE +:106DA000FFF706FE7843012187B20520FFF700FEBA +:106DB00000FB057087B20520FFF7DEFD38440BE0CD +:106DC00005200121FFF7F4FD504B9D88684385B2F3 +:106DD0000520FFF7D1FD2844608130E1514B0020B0 +:106DE0001D68FFF7C9FDDFF8549195F90630B9F930 +:106DF00002203227534393FBF7F3184420800120ED +:106E0000FFF7BAFD95F90E30B9F90020534393FB13 +:106E1000F7F73844608012E1434B9A789946434B28 +:106E20001B6812B99B88E38107E0374A1988B2F9D9 +:106E300006005A88FCF726FEE081394BE2893C4F78 +:106E40001A803B68374D1B7843B30220FFF794FD4F +:106E50002B68B3F91010B3F91220FCF713FE354B71 +:106E60001B685989344B081A1A8800B20FFA82FE3F +:106E7000864503DA38680078024403E003DD3868A9 +:106E80000078121A1A802A68B3F9003092F9162095 +:106E90005343642293FBF2F31944A18099F80A301A +:106EA00063B1194B1A88D5F800A0E28022819A8834 +:106EB000184F62815B880325A38101E0134BF1E742 +:106EC0000AEBC50393F90630B7F90690284609FB8B +:106ED00003F9642399FBF3F9A7F80690FFF74CFD3B +:106EE00001354844072DF88007F10207E8D1A6E0F4 +:106EF0000D4B9A781F460D4B1B680ABB9B88E3819C +:106F000026E000BFB60E0020882000206E1F002063 +:106F1000A80E002018000020B00E0020BC0E00209B +:106F2000C41F0020A40E00205F200020840F00203A +:106F3000AC0E0020B80E0020B40E0020A00E0020E1 +:106F4000B54A1988B2F906005A88FCF79BFDE08122 +:106F5000B24BE289B24D1A80BB7A032001211BB1EA +:106F6000FFF726FDAC4F02E0FFF722FDAD4FB7F86B +:106F70000290022100FB09F01FFA80FA0320FFF7BC +:106F800017FD3F88012100FB07A0E8800420FFF7E0 +:106F90000FFD00FB09F002211FFA80F90420FFF722 +:106FA00007FD00FB079028810320FFF7E5FCE3883D +:106FB0001844E0800420FFF7DFFC23891844208177 +:106FC0003DE001210420FFF7F3FC964D6F887843E4 +:106FD00087B204202781FFF7CFFC384420810121AC +:106FE0000520FFF7E5FC2D88684385B26581EFE653 +:106FF0008C4B0325B3F804A0994628460221FFF7DD +:10700000D7FC00FB0AF0012187B22846FFF7D0FC2D +:10701000C5F106035B0839F8133000FB037087B233 +:1070200024F815702846FFF7A7FC384424F815000B +:107030000135072DE1D1784BDA88784B1A80202072 +:10704000FCF7B8FA784F002849D00020FFF794FCED +:10705000208081460120FFF78FFC744B704D1B7A16 +:107060006080002B3BD0724B1B681B7813F0020F23 +:10707000704B1ED0D7F800E0B3F900109EF90E2037 +:107080009EF906E0B3F902304A43CEF1000E03FB4D +:107090000EF3322192FBF1F26FF0310E92B293FBBC +:1070A000FEFE9644F14493FBF1F1A5F800900A44EA +:1070B00013E03968B3F902E091F90620B3F9003022 +:1070C0000EFB02FE32229EFBF2FEF144A5F8009078 +:1070D00091F90E104B4393FBF2F2104468800025A7 +:1070E0003B68605F03EB850233F92510B2F902209B +:1070F000FCF7C8FC60530235102DF1D14C4B1B68D6 +:107100001B785B0704D4454D32782F8801231CE09F +:1071100098F800300E2B0AD0082B08D0464A02EB14 +:10712000C3035B78002B14BF0225002500E0042573 +:107130000024424B601903EB4403C0B219890134A7 +:10714000FAF73EFF042CF4D1DDE7934208D235F97B +:1071500013103FB2B942A8BF0F46BFB20133F4E7E4 +:107160000024A1463378994574D2DFF8E0803AB222 +:10717000D8F800305B889A4203DD2A5BDB1B13449E +:107180002B534FF48040FCF715FADFF8C4B02B4BBB +:10719000C0B1B3F90620DBF800305B899A42284B76 +:1071A00006DD1A68D8F800305188285F5A8805E053 +:1071B000D8F800201B689188285F1A88FCF762FCC9 +:1071C00028531FE0D8F80020285F118852880093C8 +:1071D000FCF758FC009B2853B3F90620DBF800307D +:1071E000DFF868A09B8905EB04089A420ADA1020B0 +:1071F000FCF7E0F9DAF8003008B91B8800E09B885A +:10720000A8F800300F4B9B7813B90F4BE35A2B5360 +:1072100009F101090234A5E788200020C41F0020DD +:10722000180000206E1F0020A40E002071200020F6 +:107230007C0F0020A00E0020D0F90008BA2000200A +:10724000800F00205F200020DC1F0020840F002022 +:10725000B80E002003B0BDE8F08F00BF024B1868E5 +:10726000003018BF01207047880F002044F250639F +:10727000984203DDA0F50C40A0387047034B9842BC +:10728000BCBF00F50C40A030704700BFB0B9FFFF95 +:1072900010B5044C002320702361FEF75DF8606197 +:1072A00010BD00BFC811002010B5F9F72FFC002158 +:1072B0000446F9F73BFE08B1204601E004F1004026 +:1072C0000549F9F72BFD0549F9F774FC05F028FD90 +:1072D000034B186010BD00BF8096184B35FA8E3CEA +:1072E00028000020F8B5101A0C461F46F9F70EFCCE +:1072F0000546381BF9F70AFC174B079E1968F9F782 +:1073000059FC294604462846F9F754FC214607460D +:107310002046F9F74FFC01463846F9F743FB05F0E4 +:1073200003FE0E49F9F746FCF9F730FE069B2146AD +:10733000186005F1004005F0F5FD0949F9F73AFC40 +:107340000849F9F72FFBF9F7FBFD0028BCBF00F552 +:107350000C40A0303060F8BD280000202C7D8E3F0E +:10736000A00CB34500A00C46F8B51D4614460E46C9 +:10737000F9F7CCFB6968F9F71DFC3146F9F71AFCFF +:107380002168F9F70FFB2060F9F7DAFDED68074691 +:1073900005F10040F9F7D4FD06462846F9F7D0FD7F +:1073A000314602463846FCF76DFBF9F7AFFB20602B +:1073B000F9F7C6FDF8BD000030B5002213460E49AE +:1073C000CC5C0D469CB12E2C04D1013378B11D4408 +:1073D00000242C540A246243C95CA1F13004092C16 +:1073E0009CBF303A52180E2B03D80133E7E7104602 +:1073F00030BD002030BD00BF6F110020014B186070 +:10740000704700BF3C110020F8B52B4B2B4C1B786C +:1074100013B1012B0AD04CE06278294B03EB021325 +:10742000284A59681068FDF765FF3FE0254D286838 +:10743000FDF765FF2E4600283BD02378012B1ED197 +:10744000FDF78AFF63690646C31A632B33D92369A4 +:10745000042B12D81A4F286807EB03135968FDF75D +:1074600049FF6378286807EB0317B968FDF72DFF1C +:1074700023696661013323611BE0022017E0236961 +:107480003BB962780E4B286803EB02135968FDF78D +:1074900031FF2369094D8B2B08D80B4A3068D15C2A +:1074A000FDF70EFF2B6901332B6102E00320FFF78C +:1074B000EFFE00236360F8BD69110020C8110020B1 +:1074C00080FE000834110020F2FD000810B50B4CBE +:1074D000E37A8BB10A4B1B78042B0DD9094A0A4B6E +:1074E0001068526818605A60FFF7DEFE074B1A8872 +:1074F000074B1A800123237310BD00BF5F200020BB +:107500004C20002034200020182000207E1F002066 +:1075100054110020000000002DE9F04F994B8BB072 +:107520001B68BBB9984C2378013B032B00F2CB8539 +:10753000DFE813F08F058F05A90592052068FDF798 +:10754000D4FE924B04461B78012B00F0DD8008D35B +:10755000022B06D08B4C2068FDF7C2FE0028EDD12F +:10756000E0E7242C07D18A4A00231370894A13705C +:10757000894A1370C4E02C2C02D02A2C40F083805E +:10758000844E864B3278824D002098542A78844964 +:10759000B2B90A701A78472A68D15A78502A65D148 +:1075A0009A78472A40F07E85DA78472A40F07A8533 +:1075B0001A79412A40F0768501220A7000F072BDE6 +:1075C000097801293AD1022A05D1184601F018F8A4 +:1075D000744B18604AE0032A07D11B78532B45D11E +:1075E000704B1A6852421A6040E0042A05D11846CE +:1075F00001F006F86B4B586038E0052A07D11B787C +:10760000572B33D1674B5A6852425A602EE0062AF4 +:1076100007D11A78644B302A94BF00220122DA7213 +:1076200024E0072A04D1FFF7C7FE604B18701DE065 +:10763000092A1BD1FFF7C0FE5D4B16E0022915D1C8 +:10764000072A0CD10120FFF7B7FE41F21843584337 +:107650004FF47A72B0FBF2F3564A138006E0082A20 +:1076600004D10120FFF7A8FE534B18802B782A2C59 +:1076700003F101032B704FF00003337037D14F4BF0 +:1076800001221A703CE00D2C4C4B01D00A2C24D165 +:107690001A78F2B1414908784978A0F13002D2B2A3 +:1076A000092A84BFA0F13702D2B202F00F02100102 +:1076B000A1F13002D2B2092A84BFA1F13702D2B2BD +:1076C000354902F00F0202440978D2B28C1A6242A4 +:1076D0006241002119707AB912E02E490A780E2A07 +:1076E00003D8501C08702D498C541B7843B92A4B81 +:1076F0001A7854401C7003E0294B1B78012B00D0F2 +:10770000002303F0010358E12D4B002219780829CA +:1077100000F25281DFE801F00A05111927607D9619 +:10772000A100622801D1022205E01A70B52C40F0B8 +:1077300043811A7801321A703EE103221A70214BFC +:107740001870214B1870214B0BE01F4904221A704E +:107750001E4B0A7818782244D2B20A7002441A707A +:107760001B4B1C7028E1184905221A70174B0A7828 +:1077700018782244D2B20A7002441A70154B1C8049 +:107780001AE100BF34110020C81100206911002047 +:10779000BC1100206E110020381100206F11002054 +:1077A00068110020342000205F2000204C200020A1 +:1077B000062000200A2000201C110020EC0F0020D1 +:1077C000B60F0020C41100203011002052110020FB +:1077D000B50F002050110020624906221A70624B3A +:1077E0000A7818782244D2B20A7002441A705F4BA9 +:1077F0001A8802EB0424A4B2B4F5007F01D81C80DF +:1078000003E000221A805A4B1A705A4A0023138050 +:10781000D3E05448544A017815782144C9B2017024 +:107820002944117053490A88C72A9CBF524884547E +:10783000013292B20A804D490988914240F0BC80E1 +:10784000072278E708221A70464B1B78834200F023 +:10785000B380474A00231370AFE01A70424B1B7885 +:10786000834240F0A980454B1B78062B39D004D8C1 +:10787000022B12D0032B24D09EE0122B44D0302BAD +:1078800040F09A803C4B1A793D4B102A88BF102259 +:107890001A701978384A002344E0374B394A59683E +:1078A0005160996811601A694FF47A7392FBF3F290 +:1078B000354B1A80354B1A78354BDA720122354B2D +:1078C00020E02D4A537913F0010303D01379D81E19 +:1078D000434243412D4A1370002B38D12C4AD372B6 +:1078E00035E0254BDA7A12F0010203D09A7AD11EE4 +:1078F0004A424A4125490A700AB92549CA7293F891 +:107900002F20254B1A7022E01B4B24495A690A800C +:107910009A6942F2107392FBF3F2214B1A80012212 +:10792000204BEFE78B4202F10C0210DA12F8044C04 +:107930001D481C5412F8034C1C481C5412F8014CEE +:107940001B481C5414781B481C540133EAE71149A6 +:107950000B788BB3134B1A7872B300221A700A702B +:1079600001232AE030110020521100205011002084 +:10797000B60F0020FE11002054100020B50F00208B +:107980004D2000203420002006200020E811002097 +:107990005F200020441100204C2000200A200020FD +:1079A0001C110020C5110020F41F002022200020FF +:1079B0003C2000204E2000200023002B3FF4CAADC5 +:1079C0008B4CA368E360FDF7C7FCA060202000F0AB +:1079D0007BFE884B884C1A78012A0CBF00220122BA +:1079E0001A70E37A002B3FF4B5AD844B1B78042B5F +:1079F0007FF6B0ADA37803B92373227B12B90BB124 +:107A0000FFF764FD7E4B4FF0050E1A787D4D013275 +:107A100092FBFEFE0EEB8E0ECEEB020E83F800E024 +:107A2000794B1B780593794B03EB8E0E0023784A34 +:107A300078499858DFF81C82774E585090FBF8F13F +:107A40009951764EDFF8109206FB010003EB830A92 +:107A50005EF80A6053F8097042F2107CBF1B90FB7D +:107A6000FCFC05264EF80A00384443F8090090FB58 +:107A7000F6F008FB01016A481FFA8CFC19500598C2 +:107A800003EB020B012825F802CF164606D1ACF114 +:107A9000020CBCF5797F98BFCBF800100433082B9B +:107AA000C5D1FDF759FC5F4F5F4D3B68C01AF9F730 +:107AB00029F85E49F9F732F92860FDF74DFC386086 +:107AC0002F684FF07E513846F9F712FA08B94FF097 +:107AD0007E5706AA2F60564B009207AA019296E89D +:107AE00003000CCBFFF7FEFB069A64235149B2FB5F +:107AF000F3F207980A80504A90FBF3F31380237B3C +:107B00000BB90B801380DFF854A14C4F9AF800306A +:107B1000002B36D029684FF07E50F9F7FFF83B680C +:107B200080463068C01AF8F7F1FF4146F9F742F88D +:107B3000F9F706FA7B681FFA80FB70680FFA8BFB77 +:107B4000C01AF8F7E3FF3E4B1968F9F733F84146DE +:107B5000F9F730F8F9F7F4F93A4B00B2B3F902202B +:107B60004FF0020E8118B3F9002037485A4491FBB8 +:107B7000FEF192FBFEF289B292B2418002805980FE +:107B80001A8001238AF8003071683068237A79609E +:107B9000386023B9184BDB79002B3FF4DBACDFF8FE +:107BA000C0B0DFF8C080294CCDF800B0CDF804801B +:107BB00094E80C00FFF796FB73686068244FC01AC6 +:107BC000F8F7A4FF1E4BBA461968F8F7F3FFF9F768 +:107BD000B7F9226833687860D31A3B600A4B93F98F +:107BE0000030012B40D0022B00F0D980B2E400BF5E +:107BF000C8110020EC1100205F2000204C20002044 +:107C0000FC1100207C110020B40F00208C0F0020FC +:107C100034200020E011002098110020806967FFC7 +:107C2000E40F00205C1100209411002000007A4431 +:107C300018200020142000202020002048110020BF +:107C400028000020A0110020A411002060110020B5 +:107C5000F411002080969800B0110020001200203E +:107C6000B8110020AC1100207D4D00245AF814609A +:107C7000DFF830923046F8F749FF7A4B7A4F1968AF +:107C8000F8F798FFF9F75CF934F809B0774BCBEBCC +:107C900000001FFA80FB24F803B00FFA8BFB584654 +:107CA000F8F734FF3968F8F785FFF9F749F9704AB2 +:107CB0001FFA80F811680BEB06002A463B46FFF7D7 +:107CC00053FB6C4EBF686A4B40445AF814B0A05343 +:107CD000686804971F68C0EB0B00F8F717FF394678 +:107CE000F9F71CF8644B28611B6884469878D5F82E +:107CF0000880CDF80CC0F8F705FFF8F797FB56A3FE +:107D0000D3E90023F8F7E6FB0B4602465B49002067 +:107D1000F8F70AFDF8F7F0FD3946F8F743FE01469B +:107D20003846F8F7FBFFDDF80CC0074641466046D1 +:107D3000F8F736FE01463846F8F73CFF0146404664 +:107D4000F8F730FEC5F804B001462861A860049831 +:107D5000F8F730FFF9F7F4F849494FF4FA62FBF706 +:107D600091FE34F80930474931339BB2622B335BC3 +:107D700098BF0020184480B2305340F6B83200B2A9 +:107D8000FBF780FE0A226243305355F8141B3E4B2A +:107D90000234042CD1507FF469AFFFF7DBBB364BC4 +:107DA000DBF800701B68394CB3F908607B089E4211 +:107DB00028BF1E46B4F80090B6B232B20FFA89F36B +:107DC0009A4208DD32492868F8F7F4FEF9F7B8F866 +:107DD000484486B226802F4BD8F800401B682E4DB1 +:107DE000C3EB04084046FFF741FA0028D8BF4042E1 +:107DF00041F293139842CCBF00200120002853D0B9 +:107E00004046F8F783FE2549F8F7D4FE04F0FCFF5E +:107E100080463846F8F776FE01464046F8F7CAFE37 +:107E2000F9F78EF81E4B80B21880164900B240F662 +:107E3000B832FBF727FE48F6A0432044984203DD02 +:107E4000A0F50C40A03804E00028BCBF00F50C40B1 +:107E5000A030286029E000BF182D4454FB211940B0 +:107E6000BC0F00202011002084110020A811002048 +:107E700094110020F00F00203C1100200000F03F82 +:107E800030F8FFFF48F4FFFF04100020EA11002043 +:107E90000000C842C011002058110020D302373919 +:107EA000EE0F0020A41100202C6028688A4DC0F538 +:107EB0000C502830F8F72AFE8849F8F77BFE044674 +:107EC00004F02EFF0990204604F09EFF0024089045 +:107ED00030B2F8F71BFE08AB53F81410F8F76AFE3F +:107EE0007F4B0746185FF8F711FE01463846F8F752 +:107EF00057FDF9F725F8DFF82C9280B24FF47A722B +:107F000024F80900774900B2FBF7BCFD80B20FFAF4 +:107F100080FA754F24F809005046F8F7F7FD3968E4 +:107F2000F8F748FEF9F70CF8DFF8FC8180B22A4632 +:107F30003B46D8F8001004905046FFF715FABF688A +:107F4000844634F909A068680597D8F80070C0EB3A +:107F50000A00CDF80CC0F8F7D9FD3946F8F7DEFE77 +:107F6000DFF8C8912861D9F8003083469878F8F78F +:107F7000C9FDF8F75BFA56A3D3E90023F8F7AAFA8C +:107F80000B46024659490020F8F7CEFBF8F7B4FC3F +:107F90003946F8F707FD01463846F8F7BFFED5F831 +:107FA0000880074641465846F8F7FAFC014638462D +:107FB000F8F700FE01464046F8F7F4FCDDF80CC087 +:107FC000049F01462861A860C5F804A0059867448D +:107FD000F8F7F0FDF8F7B4FF3844454F80B2E053AE +:107FE000444940F6B83200B2FBF74CFD0A22624326 +:107FF000385355F8141B404B0234042CD1507FF4F5 +:1080000067AFD9F800301A7932B13C4A116864225E +:1080100091FBF2F13A4A11803A4A1B8812689A425F +:108020000ED9394B1868394B1B68C01AFFF71EF977 +:1080300042F210730028B8BF404298427FF78AAAE4 +:10804000334B01221A70334B1A882D4B1A80FFF7DD +:1080500081BAFFF7D9F936E063680522013363601E +:1080600063780133DBB2B3FBF2F202EB82029B1ABC +:108070006370FDF771F9284A00231370274AA06046 +:10808000D37201200BE0FDF767F9A36840F6C41234 +:10809000C01A904217D9202000F01EFB0420FFF7E1 +:1080A000F7F810E09B781E4A522B7FF4DFAAD378B2 +:1080B0004D2B7FF4DBAA1379432B7FF4D7AA02233D +:1080C0000B70FFF7D3BA0BB0BDE8F08FAFF30080B1 +:1080D000182D4454FB21194004100020D3023739D5 +:1080E000A411002018FCFFFFF40F00200000F03F57 +:1080F000F00F002048F4FFFFBC0F002058110020B3 +:108100006C1F0020B8110020AC110020C01100200D +:10811000B40F0020541100204C2000205F200020CC +:108120006F110020A8110020941100203C110020A4 +:1081300010B500231A460E49002050520D490E4C2E +:1081400050520E495052002119511C446060A160E8 +:108150000B4C023219511C446060A160094C042A86 +:1081600019511C446060A16003F11403E3D110BDF8 +:108170006A110020401100202C100020F00F002078 +:10818000BC0F00200410002070B504460079F8F7F9 +:10819000B9FC1E49F8F7C2FD1D4D1E4E2860A07B9C +:1081A000F8F7B0FC1949F8F7B9FDEE60686060793E +:1081B000F8F7A8FC1849F8F7B1FD184D2860E07BE6 +:1081C000F8F7A0FC1149F8F7A9FD6860607EF8F7A0 +:1081D00099FC1349F8F7A2FDEE60A860A079F8F7C2 +:1081E00091FC0D49F8F79AFD0E4D2860207CF8F7B8 +:1081F00089FC0649F8F792FD6860A07EF8F782FCDA +:108200000749F8F78BFDEE60A86070BD0000C8421A +:10821000201100200000FA440000204184110020B9 +:1082200000007A44F40F00202DE9F7439946214BD2 +:10823000214C18600025C3686570204E06EB0510C0 +:108240004068B046984206D00135EDB2042DF4D90D +:108250000023637000E06570194B1A4E00203170E6 +:108260001A60FFF715F8FDF777F833780025AB4271 +:10827000A06048460CBF012703276560FFF784FF15 +:1082800066783B4608EB0616009510202946726872 +:1082900001F06EFD0C4B186030B94FF4807003B0E4 +:1082A000BDE8F043FBF72EBB012003B0BDE8F0436F +:1082B000FEF7EEBFF0110020C811002080FE00087C +:1082C0003C110020691100203411002073B51D4BB2 +:1082D0001D78032D31D1202001F01EFC1A4E0446DA +:1082E00038B101F0C7FD336820461969FDF702F87F +:1082F00009E03368009021461A6920202B4601F0DE +:1083000037FD0446D8B1114D2868FCF7E9FF30B1BC +:108310002868FCF7EAFF01462046FCF7D1FF20461B +:10832000FCF7DEFF0028EED020462D68FCF7DDFFCD +:1083300001462846FCF7C4FFE5E7022000E0284696 +:1083400002B070BDC8110020F011002034110020CF +:10835000F7B50368174C184D23600B68174E636020 +:108360000068FEF7A1FF95E80300154B0196009306 +:1083700094E80C00FEF7B6FF3668124B60681E608A +:108380006B68114FC01AF8F7C1FB104B1968F8F76A +:1083900011FCF8F7D5FD22682B687860D31A3B6092 +:1083A0000B4B1E600B4B1B68DA880B4B1A8003B01B +:1083B000F0BD00BF6011002034200020AC1100206F +:1083C000B811002058110020F411002028000020CE +:1083D000C01100203C110020EA1100202DE9F84FC7 +:1083E000484BDFF834A1B3F90000F8F78FFB46499A +:1083F000F8F7E0FB044604F007FD0746204604F0CA +:108400008FFCDAF80030064693F80390DFF80C8111 +:108410003E4DB9F1000F43D03D4CB8F90200B4F81D +:1084200002B00FFA8BF3C01AFEF720FFC9F100016A +:108430004A46FBF727FBB4F8009058446080B8F92F +:1084400000000FFA89F3C01AFEF710FFDAF80030C7 +:10845000DA785142FBF716FB48441FFA80F9A4F87A +:108460000090B4F90200F8F751FB80460FFA89F04A +:10847000F8F74CFB314604464046F8F79BFB39467B +:1084800081462046F8F796FB01464846F8F788FAF9 +:108490002049F8F743FCF8F753FD288040461DE0DB +:1084A000B8F90200F8F732FB8146B8F90000F8F796 +:1084B0002DFB314604464846F8F77CFB394680469A +:1084C0002046F8F777FB01464046F8F769FA11496C +:1084D000F8F724FCF8F734FD288048463946F8F7C9 +:1084E00069FB314607462046F8F764FB01463846EB +:1084F000F8F758FA0749F8F711FCF8F721FD6880FA +:10850000BDE8F88F7E1F002035FA8E3C6A110020EE +:1085100040110020000020413C110020F00F0020FD +:1085200038B5244CE37A2546002B3CD0224B1B78EF +:10853000042B38D9214B9A7A7AB1E379002B37D1C1 +:1085400001221F48E2711F4A011D13702372FFF7B9 +:10855000FFFE1D4B02221A7038BDDB7AE271BBB1FF +:108560001A4B1B68588900F0C5F888B1237AFBB90B +:10857000144A17481370174B01251A685B68011DD0 +:10858000436025720260FFF7E3FE0F4B1D7038BD9C +:1085900000232B720B4B1A7852B901221A70BDE8D6 +:1085A0003840FFF7C5BD084A0023EB712B721370EA +:1085B00038BD00BF5F2000204C200020712000202B +:1085C000182000202C000020B40F00203C110020B7 +:1085D0000C20002034200020074B1A68821A002A41 +:1085E00008DB064A1278042A04D900F5123000F597 +:1085F000F8701860704700BFB80F00204C200020B2 +:10860000294BF0B51D68024600F110071678144694 +:10861000AB195978013201F0040101F0FF0369B18F +:10862000BA42F3D10020F0BD1BB103EB83035B0022 +:10863000DBB210F8012B303A1344DBB2221A022AC3 +:10864000F2DC002184420AD919B101EB8101490011 +:10865000C9B210F8012B303A1144C9B2F2E72E2EFC +:1086600014D1013404200022267802EB8202AF19D3 +:108670007F7852007F0792B203D5303A32440134FA +:1086800092B2013810F0FF00EED100E0002207485E +:1086900006244143642000FB02120548B2FBF4F2B9 +:1086A00000FB0320F0BD00BFA401002040420F00EA +:1086B00080969800034B1B6818420CBF00200120D5 +:1086C000704700BF04120020024B1A681043186064 +:1086D000704700BF04120020024B1A6822EA000013 +:1086E0001860704704120020014B1868704700BFE3 +:1086F00004120020094BB3F90020002AB8BF5242EF +:10870000824209DAB3F90230002BB8BF5B428342E0 +:10871000ACBF002001207047002070478820002057 +:1087200010B544780078002303FB03F11939614345 +:1087300001F6C4115943414340F6C41291FBF2F1D2 +:10874000034A22F813100133072BEDD110BD00BFEF +:10875000A82000202DE9F0478278C6781E4BC2F190 +:10876000640802EB820C54425FFA88F84FEA4C0C22 +:10877000C6F16409A4B203F11807A5B228B2002813 +:1087800004DC002D14BF1546012500E0454600FB22 +:1087900000FA6D430AFB06FA9AFBF5F54D4468436F +:1087A0004FF00A0A90FBFAF0604480B258800D88BE +:1087B000B1F802A000B2C5EB0A0A00FB0AF04FF4C0 +:1087C0007A7A90FBFAF0054423F8025F0A34BB4240 +:1087D000A4B2D2D1BDE8F0878E200020014B1860F2 +:1087E000704700BF90120020074B1B681B7A032BB9 +:1087F00009D8DFE803F00202040600F0F3BB00F042 +:1088000037BA00F01BBB70479012002008B5037AFE +:10881000032B12D8DFE803F00202070C0A490B4AC7 +:1088200000F0E8FB08E00849084A00F029FA03E0F4 +:108830000549064A00F00AFB28B90820FBF762F850 +:10884000024B00221A6008BDB620002088120020CA +:10885000174B10B51860044600236089154A9852DA +:108860000233242BF9D1144B08201960FAF7A2FE29 +:1088700010B12046FFF7CAFF4FF48030FAF79AFE96 +:1088800020B120460D490E4A00F09AF90120FAF76E +:1088900091FE28B109480A49BDE8104000F09EB990 +:1088A0004FF40040FAF786FE0028F3D110BD00BF58 +:1088B00090120020BA20002084120020B620002050 +:1088C00088120020037A032B09D8DFE803F00202A4 +:1088D000040600F0C9BB00F001BA00F0D7BA0020CE +:1088E0007047000010B5104C002308202370FAF7E1 +:1088F00061FE20B10D4B1868FFF7E4FF20704FF4C4 +:108900008030FAF757FE10B100F050F9207023784C +:108910004BB14FF40070FAF74DFE20B1044B1B68C9 +:108920001B681B68984710BD8C1200209012002015 +:1089300084120020054B1B782BB9054B1B68C01A0D +:10894000C043C00F70470120704700BF8C12002049 +:10895000941200200E4A0F4B127802F0030202EB31 +:10896000800223F8121003EBC00233F83010538852 +:108970000B449188D2880B441344074A9BB222F8D7 +:1089800010301BB2042293FBF2F080B2704700BF9C +:1089900008120020221200200A1200202DE9F047C0 +:1089A00040F20120FAF706FE28B1F9F7E5FB82460E +:1089B000F9F7EEFB01E04FF0010A0026234BF4B279 +:1089C0001B78A34240D9224B224F1B68DFF88C80D2 +:1089D0002BB9D8F800305B8927F8143032E0D8F88A +:1089E0000020072C94BF12F80490A146174849466E +:1089F000984705464FF40070FAF7DCFD48B1BAF12C +:108A0000000F06D0144B48461B6829461B68DB69DB +:108A10009847A5F2EE2240F2DC5392B29A4288BF08 +:108A2000D8F8003048F2010088BF5D89FAF7C2FD2E +:108A300010B927F8145005E020462946FFF78AFFB1 +:108A400027F814000136B9E7BDE8F087B62000200A +:108A500088120020BA2000208412002090120020EA +:108A600010B5064C237843B1054B1B681B681B6887 +:108A70009847FFF793FF0023237010BD8C1200204E +:108A800084120020024B1A7801321A70FFF786BF59 +:108A90000812002008B500F59C400D4B20301860EE +:108AA0004FF40070FAF786FD20B10A4B1B681B6873 +:108AB0001B69984748F20100FAF77CFD18B9BDE838 +:108AC0000840FFF7CDBFBDE80840FFF7DBBF00BFA0 +:108AD0009412002084120020F8B505460F46441E6B +:108AE00014F8011F49B1054E304605F0F1FF00288A +:108AF000F6D0861B631BBB55F2E7F8BDD0FE00081D +:108B000010B51F4B1A681C46127C3AB123681B7CB7 +:108B10005BB11C4A013B32F813001BE04FF40030FC +:108B2000FAF748FD0028F1D110BD4FF40030FAF7F4 +:108B300041FD78B1F9F7F2FA114B80B21B685B7C0A +:108B4000012B07D103B2B3F57A7FC8BF002000F52F +:108B50007A7080B200B24FF47A720021A0F57A7078 +:108B6000FAF790FFF7F7D2FF0749F8F7D7F8074968 +:108B7000F8F720F8F8F70AFA054B188010BD00BF87 +:108B800090120020BA20002000007A4400C07F44E8 +:108B9000B8200020014B33F811007047BA200020A4 +:108BA000014B01221A70704798120020034B18786D +:108BB00010B100221A700120704700BF98120020E7 +:108BC00008230B700AB1024B13600120704700BFED +:108BD000958B00080846F9F787BB0000084B10B5D5 +:108BE0000B6004464FF40040FAF7E4FC08B1082398 +:108BF00023700120FAF7DEFC08B10C23237010BDAE +:108C0000D58B0008034B53F82100400800F577701E +:108C100080B27047A412002038B50446FCF782FBEE +:108C20000F4B40F6C4111A681860821A8A420D4A26 +:108C300084BF0021117013780BB90F2C0FD10A4893 +:108C4000002101704BB1094D182B1D4405F8014C52 +:108C500003D101231170037038BD0133137038BD87 +:108C60009C120020A0120020A1120020D41200208B +:108C7000024B43608360032343737047A086010067 +:108C8000F7B50025074605230E4614460E49009504 +:108C900008200E4A01F06CF879890D4BA1F5777127 +:108CA000186049002B460B4A99500433302BFAD1F7 +:108CB0000CB1094B236000304FF00C0318BF0120AA +:108CC000337003B0F0BD00BF198C0008A08601000E +:108CD000F0120020A4120020058C0008344B10B5BF +:108CE0001A780AB9002010BD00221A70314B9A7D03 +:108CF0001207F7D4587819782F4A00F0070441EA90 +:108D000004211160997801F03F04640144EAD00025 +:108D10005060D878800040EA9110197901F0010480 +:108D200040EA84209060587900F00F04E40144EA9E +:108D30005101D160997901F07F04240144EA1010B7 +:108D40001061D879400040EAD111187A00F003048C +:108D500041EA44215161597A01F01F04A40144EA17 +:108D600090009061987AC00040EA5111187BD1615F +:108D7000D97A00F0070441EA04211162597B01F01D +:108D80003F04640144EAD0005062987B800040EACE +:108D90009110D97B1B7C01F0010403F00F03DB0170 +:108DA00040EA842043EA51019062D162012010BD63 +:108DB000A1120020D4120020A4120020024B53F86C +:108DC0002100C0F3CF0070472413002010B50446E3 +:108DD000FCF7A8FA144B1A681860821AB2F57A6F79 +:108DE000124A84BF00211170137823B9A82C1AD11C +:108DF0000F490B7006E0022B02D10E490C7001E006 +:108E0000242B01D80C49CC540133DBB21370094A2E +:108E1000127852000532934205D1044B00221A7099 +:108E2000034B01221A7010BDF412002064130020BD +:108E30001E130020F8120020F91200204FF4E13335 +:108E400043608360012343737047000037B50023FC +:108E500000930D4601231446082009494FF4E132DE +:108E600000F086FF074B18600CB1074B2360003001 +:108E70004FF0100318BF01202B7003B030BD00BFAE +:108E8000CD8D000820130020BD8D0008134B10B5B8 +:108E90001A780AB9002010BD00221A70104B5B78B6 +:108EA000012BF7D10F4B1A78102A84BF10221A70A9 +:108EB0000D4A19780023D8B2884202F102020AD280 +:108EC00012F8010C12F8024C40EA0424074840F85A +:108ED00023400133EFE7012010BD00BF1E13002027 +:108EE000F9120020F8120020FC12002024130020A8 +:108EF000114B10B501221A700446FCF713FA0F4A01 +:108F0000014613681160C31A0D4841F2883293423A +:108F100003600C4B84BF00221A701B780A4AE4B22B +:108F20000F2BD45403D1094B01221A7010BD054AEE +:108F30000133137010BD00BFA0130020B813002030 +:108F4000681300206C130020A31300206613002078 +:108F50002DE9F0411C4B04781A781D46FAB11B4BE1 +:108F60001E781B4B1F7802231A4803F10108C25CCC +:108F7000324102F00F02A2420CD20B2A0AD810F89A +:108F800003C010F808000CEA070C00EB0C2C124888 +:108F900040F822C00233102BE6D100232B708C4204 +:108FA0000ED90E4B187860B10D4B1A780A4B53F856 +:108FB000210002B1400800F5777080B2BDE8F08171 +:108FC0000020BDE8F08100BF66130020651300207B +:108FD000A2130020A313002070130020A013002070 +:108FE000A11300204FF4E1334360836001234373F6 +:108FF0007047000013B5037A14465BB1012B13D1FF +:10900000134A03201070134A07201070124A13707D +:109010000C2308E00E4A022010700E4A0320107044 +:109020000D4A137007230B700023009308200123BF +:109030000A494FF4E13200F09BFE094B18600CB175 +:10904000084B2360003018BF012002B010BD00BFE4 +:1090500065130020A2130020A1130020F18E000848 +:10906000B4130020518F0008014B1878704700BFDF +:1090700066130020014B1860704700BFC01300202A +:10908000034B1B681878D0F1010038BF00207047EF +:10909000C0130020034B1B681878431E58425841E8 +:1090A000704700BFC0130020034B1B681878831E55 +:1090B00058425841704700BFC013002008B54FF414 +:1090C0000060FAF777FA20B10420BDE8084000F00C +:1090D00007BE08BD084B1B7863B1084B1B685B7863 +:1090E00013B1074B187D01E0064B9878003018BF8C +:1090F0000120704701207047BC130020C0130020DE +:10910000712000205F20002008B5FFF7B9FF18B1DB +:10911000BDE8084000F082BAFFF7BCFF18B1BDE817 +:10912000084000F04DBC08BD08B5FFF7A9FF08B125 +:1091300000F0B0F8FFF7AEFF18B1BDE8084000F04E +:1091400015BB08BD38B50D4B1B78B3B1FFF7C2FF97 +:109150000B4B04461A781D4682420ED050B1FFF7E1 +:109160008FFF08B100F0AEF8FFF794FF20B100F0D8 +:109170003DFB01E0FFF7D8FF2C7038BDC413002081 +:10918000BD13002008B50121042000F0B5FD0F4BF0 +:109190001870FFF793FF0E4B1870FFF771FF18B1AF +:1091A0000C4B186800F070F8FFF774FF18B1094B0A +:1091B000186800F0F3FAFFF777FF18B1054B18684D +:1091C00000F001FCBDE80840FFF7BCBFBC13002065 +:1091D000C4130020C013002008B50C4B1B789BB1B2 +:1091E000FFF778FF80B1FFF74BFF08B100F0ACF854 +:1091F000FFF750FF08B100F02BFBFFF755FF18B148 +:10920000BDE8084000F0E0BB08BD00BFC41300206B +:1092100038B5064C05465E212068FCF751F82068F9 +:109220002946BDE83840FCF74BB800BFDC130020EE +:10923000024B5E211868FCF743B800BFDC13002026 +:1092400010B50A4C5E280146206805D15D21FCF767 +:1092500037F820683E2105E05D2903D1FCF730F89E +:1092600020683D21BDE81040FCF72AB8DC1300203F +:1092700010B50446C0B2FFF7E3FFC4F30720BDE812 +:109280001040FFF7DDBF0000014B1860704700BFC2 +:10929000D413002010B5084B084C19782068FCF74F +:1092A00033F8074B20681968FCF724F8206804217C +:1092B000BDE8104000F05CBCD0130020DC1300209F +:1092C000C813002073B5042000F026FC144C01469E +:1092D0002060144E144D90B143794FF41651337001 +:1092E00083682B60FCF706F820680221FCF70CF875 +:1092F0002068042102B0BDE8704000F029BC0B4B8F +:109300004FF416521B6804209B780093022300F050 +:109310002FFD43792060337083682B6002B070BDED +:10932000DC130020D0130020C8130020D413002029 +:1093300008B5044B1868FBF7D3FFD0F1010038BF24 +:10934000002008BDDC1300202DE9F843FFF7F0FFF3 +:10935000002800F04481FBF7FFFFA24B1A68821A35 +:109360007C2A40F23C81A04E1860337800240133FF +:10937000337004F12400C0B2FFF74AFF9B4B33F96E +:109380001400F7F7C3FB9A4B05461888F7F7BEFBA6 +:1093900001462846F7F7C2FC9649F7F70BFCF7F7AA +:1093A000CFFD013400B2FFF763FF032CE1D1302081 +:1093B000FFF72EFF904BB3F90000FFF759FFFFF7BF +:1093C00037FF307810F0030729D18C4D1020FFF7BC +:1093D0001FFF2B68642493FBF4F000B2FFF748FFF3 +:1093E0002120FFF715FF2B6893FBF4F004FB1034EA +:1093F00084EAE470A0EBE47000B2FFF739FF1420B8 +:10940000FFF706FF7E4BB3F90000FFF731FF1C208A +:10941000FFF7FEFE3846FFF72BFFFFF709FF337813 +:109420005B0740F0B6800220FFF7F2FE754B0A257D +:10943000B3F9000090FBF5F0FFF71AFF0220FAF7EE +:10944000B9F800284CD0DFF8CC816F4F98F8003085 +:109450003A7840F63401B2FBF3F24A436B4C2A21CE +:10946000B2FBF1F22188062091FBF3F903FB1919F5 +:109470004FEA09191FFA89F949EA02291FFA89F9FD +:10948000C2F3032249EA0209FFF7C2FE0FFA89F08C +:10949000FFF7EEFE228898F80030013292B292FB7C +:1094A000F3F103FB112323803B786E245C431523E7 +:1094B00094FBF3F43A204FF06408FFF7A9FEB4FBE5 +:1094C000F8F708FB17443846A4B2FFF7D1FE05347D +:1094D0003B20FFF79DFE94FBF5F000B2FFF7C8FEBE +:1094E0002020FFF7E7F8002851D0494C1320FFF760 +:1094F0008FFE2368DFF82081002BB8BF5B4293FB0F +:10950000F8F000B2FFF7B4FE1B20FFF781FE2368DE +:109510000A27002BB8BF5B4293FBF7F342F21075AA +:1095200093FBF5F205FB123000B2FFF7A1FE2320FA +:10953000FFF76EFE2368002BACBF4E205320FFF7D1 +:1095400097FE1220FFF764FE6368002BB8BF5B42F2 +:1095500093FBF8F000B2FFF78BFE1A20FFF758FEDE +:109560006368002BB8BF5B4293FBF7F797FBF5F3FB +:1095700005FB137000B2FFF77BFE2220FFF748FEC9 +:109580006368002BACBF45205720FFF771FEFFF743 +:109590004FFE3378282B22D1134B00221A70FBF791 +:1095A000DBFE4FF47A763C24B0FBF6F61720FFF78B +:1095B0002FFEB6FBF4F5B5FBF4F004FB10500002EF +:1095C00000B2FFF755FE1820FFF722FE04FB1560DE +:1095D00000B2FFF74DFEBDE8F843FFF729BEBDE836 +:1095E000F88300BFD8130020CC130020A81F002050 +:1095F0000400002000007A447C0E0020E00C0020D3 +:109600007E1F00203C1F0020E4190020CE13002004 +:109610003420002001000020A08601004FF41650E5 +:109620007047000010B5054C2068FBF759FE18B1D3 +:109630002068FBF75AFEF6E710BD00BF2414002097 +:10964000DFF890C02DE9F043204E91FBFCF406FBBF +:1096500004180627C90F07FB08F8417292FBFCF1BA +:1096600006FB01261A4B04EB840498FBF3F903FB79 +:1096700019887E434FFA89F904EB840409EB8404CA +:10968000A4B28472240AC47296FBF3F403FB14633D +:1096900001EB810164B201EB8101642504EB8101DE +:1096A00098FBF5F893FBF5F389B280F80C80D20FA4 +:1096B0004FEA2828C1734374090A1B1280F80D80F1 +:1096C000827301748374BDE8F08300BF806967FF13 +:1096D00040420F008096980010B5174B174A1B7830 +:1096E000D27A0446837612B92D23C37610BD042B9B +:1096F0008CBF33233223C376114B93E80600FFF768 +:109700009FFF104B1A886423B2FBF3F303EBC303F0 +:109710009B009BB2E3711B0A23720B4B1B88E37403 +:109720001B0A2375094B1B8863751B0AA375084B1D +:109730001B88237710BD00BF4C2000205F20002035 +:10974000342000200A2000201420002006200020C1 +:1097500020200020044A002312788370037182774E +:10976000C377027543757047E419002010B5084BA4 +:10977000084C19782068FBF7C7FD074B206819686B +:10978000FBF7B8FD20680421BDE8104000F0F0B9F7 +:109790002A1400202414002014140020F8B5104CC2 +:1097A000104B2C271860002120463A4604F072FE28 +:1097B0008E2363707C26E0237D25E370267084F879 +:1097C0002B50094C002120463A4604F063FE8A23C0 +:1097D0006370A0232670E37084F82B50F8BD00BF9F +:1097E000E8130020301400203414002073B5042046 +:1097F00000F092F9134C01462060134E134D90B1C6 +:1098000043794FF49641337083682B60FBF772FD08 +:1098100020680121FBF778FD2068042102B0BDE833 +:10982000704000F095B900904FF496420123042057 +:1098300000F09EFA43792060337083682B6002B099 +:1098400070BD00BF241400202A140020141400202E +:109850002DE9F843FBF766FD4C4D4D4A2B68044655 +:10986000C31A934206D94B48FFF774FF4A48FFF7E3 +:1098700033FF2C60494E4A4F96F80090B9F1000F23 +:109880000ED1DFF82881D8F80000FBF729FD012868 +:1098900006D90228434D46D0FFF7C4FE01232B70A2 +:1098A0003D68DFF8FCC0002D6ED037783B4A3E4E55 +:1098B0003FB1336840F6B731E31A8B420BD8BDE8AD +:1098C000F88301231370394B02211868FBF71CFD44 +:1098D000374B1F7024E0374F34483B784BB9006852 +:1098E0000121CCF800301370FBF70EFDFFF79AFE54 +:1098F00016E0013BD9B239702D4A2F4B19B91178B6 +:109900004D1C157006E015F8011B1778CCF80050B7 +:109910000F4417701A78006801321A70FBF7D0FCF8 +:109920003460BDE8F8832A78244B1AB11C6085F8AE +:109930000090B5E71B68E31AB3F57A6FB0D3012343 +:10994000D8F800002B70FBF7D0FC0546D8F80000D3 +:10995000FBF7CBFC802DA3D18A2802D08E280AD019 +:109960009EE72020FEF7A6FE002899D03378002B32 +:1099700096D1094B03E03378002B91D1054B3B6026 +:109980000C4B2D221A708BE7BDE8F8831C140020C5 +:109990003F0D0300E81300203414002020140020A1 +:1099A000E41300202D0000201814002024140020AF +:1099B000E013002028140020291400202C1400207B +:1099C0004FF496407047704702F0E6B810B5002398 +:1099D0000C245C430549DAB2615C814203D0013357 +:1099E000042BF5D11A46104610BD00BF30000020F0 +:1099F000037A0022D0B2013213B1581E0340F9E7B6 +:109A00000A7AD9B2013312B1511E0A40F9E78842ED +:109A100094BF0020012070470048704724FF0008D1 +:109A200000230549DAB2595C814203D00133092B86 +:109A3000F7D11A4610467047D9FE00082DE9F74FB6 +:109A4000137C81460E461446032B40D80C225A4301 +:109A5000214903F1010A01EB020898F8080019EA0C +:109A6000000F31D08B5C43B1012B06D0022B04D008 +:109A7000032B14BF0425032500E01D46174B4FEAB6 +:109A8000051B402003EB0B070193F9F793FD019BA6 +:109A900020B913F80B30023B012B15D9737B13B19E +:109AA0003A7B134210D071687A6891420CD3B16846 +:109AB000BA68914208D82570A760C4F80480E660AF +:109AC00084F810A0204603E05FFA8AF3BCE7002088 +:109AD00003B0BDE8F08F00BF30000020E4FE0008B6 +:109AE00070B50A4C06460D4620460021142204F0AB +:109AF000D1FC074804210C22064B04F015FD30462A +:109B000029462246BDE87040FFF798BF6014002048 +:109B100030000020F19900080B4AA2F13003197AB5 +:109B200081420BD00C339342F9D1084B197A014092 +:109B300004D10C339342F9D1084670470BB15868F1 +:109B400070471846704700BF6000002030000020BA +:109B500010B50023054A1A445468844203D00C33DC +:109B6000302BF7D10022517210BD00BF3000002011 +:109B70000023064A1A445168814203D00C33302B2B +:109B8000F7D1002200235372704700BF300000203D +:109B900038B5002205461D491301585CA84204D07F +:109BA0000132062AF7D1002038BD194C0B44042D90 +:109BB0000FCB84E80F001BD007D8012D0FD0022D4A +:109BC00021D1144B1B689B6810E0102D15D0202D5F +:109BD00009D0082D17D12046FEF706FE11E00D4BE7 +:109BE0001B685B680CE00B4B1B681B69636007E03C +:109BF000FFF78AFA6060A06003E0064B1B68DB6831 +:109C0000A360204638BD024838BD00BF2CFF0008C5 +:109C10008814002084140020214B10B51860012006 +:109C2000FFF7B6FF01460120FFF75AFF08B90020F1 +:109C300010BD0220FFF7ACFF01460220FFF750FFE6 +:109C40000028F4D01020FFF7A3FF01461020FFF7F3 +:109C500047FF04464FF48070F9F7ACFC08B1002CC4 +:109C6000E5D00820FFF794FF01460820FFF738FFF2 +:109C700004460820F9F79EFC08B1002CD7D0042038 +:109C8000FFF786FF01460420FFF72AFF04464FF442 +:109C90000060F9F78FFC08B10CB9C8E7012010BDCE +:109CA0008414002070B50E4600240C4D0023605D26 +:109CB000E95CEA18814203D01033602BF8D100220E +:109CC0001146FFF70DFF83681B78B34204D01034B0 +:109CD000602CEAD1002070BD012070BD2CFF00086F +:109CE00010B50446FFF754FF01462046FFF7F8FE83 +:109CF000003018BF012010BD38B505460C46FFF7EF +:109D000047FF01462846FFF7EBFE28B143681B7A60 +:109D10001C420CBF0020012038BD0000F8B50546EC +:109D20000020FFF753FE104E0C272B780F4C07FB3B +:109D30000060E35C03720120FFF748FE6B7807FBCD +:109D40000060E35C03720220FFF740FEAB7807FB84 +:109D50000060E35C03720320FFF738FEEB7807FB3B +:109D60000060E35C0372F8BD30000020D9FE0008FB +:109D70002DE9F04F87B0984682460F4616469DF86B +:109D80004040FFF705FF0DF1080E0546034600F1C0 +:109D9000100C18685968724603C20833634596462A +:109DA000F7D12B7B0BB903960496504602A9FFF717 +:109DB00097FE054640B14368586830B1504602A945 +:109DC0002A46FFF73BFEF4E730E0AB6895F800B0B9 +:109DD00093F80090B9F1030F28D8DFE809F00205E5 +:109DE0000E100094134801E013480094394632469F +:109DF0004346F8F707FD04460BE0002000E0012091 +:109E0000394623463246F8F7EBFA41460446FBF75B +:109E10007BFA54B1094B84F8049043F82B406B68EB +:109E200020465C605146FFF793FE204607B0BDE830 +:109E3000F08F00BF0038014000440040741400203F +:109E400038B5064C05462060FFF768FF284601F04C +:109E500095FD2068BDE8384000F0E6BE841400207F +:109E6000034B1B780BB100F0E7BD01F021BE00BF32 +:109E70009814002010B504462046FBF740FA18B9A4 +:109E80000A20FBF77AFAF7E710BD0000232801D17A +:109E900000F0D2BD044B1B681B7D834202D1012020 +:109EA000FBF7EABA704700BF8414002010B5441EC7 +:109EB00014F8011F21B1034B1868FBF701FAF7E70B +:109EC00010BD00BFD01400200148FFF7EFBF00BF56 +:109ED0001801010810B50748FFF7E8FF0024064BFA +:109EE00006481A19E15852680C34F9F709FFC02CDA +:109EF000F5D110BD56010108340001086C010108BC +:109F000070B5FBF729FA244B4FF47A711A78234B7A +:109F1000B0FBF1F11B782248F9F7F2FEFEF7E4FB03 +:109F2000204B05461968204B2048B1FBF3F1F9F7A7 +:109F3000E7FE00241E4AE3B252F8231049B1012281 +:109F400002FA03F32B4202D01A48F9F7D9FE013482 +:109F5000F0E70220FEF7AEFB68B1174B17481A78FE +:109F6000174B53F82210F9F7CBFE164B197A11B1A3 +:109F70001548F9F7C5FE1548FFF798FF144B1C88E4 +:109F8000F7F7F8FD2146024640F24C431148BDE880 +:109F90007040F9F7B5BE00BFE419002001000020B1 +:109FA000740101088801002040420F00B20101083D +:109FB00020100108D0010108DC0C0020D4010108A8 +:109FC000F4000108481F0020DE01010844040108D4 +:109FD0009E0C0020E201010838B50C6805462046B9 +:109FE00004F04EFE214602462868BDE8384004F0E1 +:109FF00077BE000037B5037904460D46052B34D8EB +:10A00000DFE803F003060A0D1114836819782DE0C8 +:10A01000836893F9001029E08368198826E0836833 +:10A02000B3F9001022E0836819681FE0836869466D +:10A030001868F9F753FF01461248F9F761FEF5B1C8 +:10A04000E068F6F763FD6946F9F748FF01460E48F8 +:10A05000F9F756FE2069F6F759FD6946F9F73EFF14 +:10A0600001460948F9F74CFE09E000210748F9F7D5 +:10A0700047FE25B10648E1682269F9F741FE03B0C1 +:10A0800030BD00BFDB010108DA0101081802010838 +:10A090001402010808B50648FFF708FF054B1868C9 +:10A0A000FFF7E8FEBDE808400020FBF7E5B900BF78 +:10A0B0001B020108D014002008B50748FFF7F6FE80 +:10A0C000064B93F84804F9F70FFAF9F71DFABDE8C3 +:10A0D0000840FFF7DFBF00BF2A020108E81900208F +:10A0E0007FB5044604F0CCFD082825D100231F4984 +:10A0F000E25C09681144497801F00301022908BFB4 +:10A10000203AE2540133082BF1D10025665D18484E +:10A11000314604F0DDFC28B101356019314604F008 +:10A12000D7FC18B11348FFF7C1FE1DE0082DEDD193 +:10A1300020461149FEF7D0FC1048FFF7B7FE002378 +:10A140000F4A04A91A4492F808210A440849595CA4 +:10A150000133082B02F80C1CF2D10023094801A995 +:10A160008DF80C30F9F7CCFD04B070BDA4010020CF +:10A17000D0FE000834020108F01A00205402010841 +:10A18000E81900206F01010808B5FEF79FF80228C2 +:10A1900002D0032800D008BD0248BDE80840FFF700 +:10A1A00085BE00BF690201082DE9F041054604F0B3 +:10A1B00067FD0446F9F760FC06468CB92948FFF7AD +:10A1C00075FE294B53F8241041B10123A3403342BB +:10A1D00002D02648F9F794FD0134F2E7244821E043 +:10A1E00028462449224604F07BFD58B92248FFF74F +:10A1F0005DFE224C54F8041F0029EFD01B48F9F7EC +:10A200007FFDF7E72B7800262D2B03BF013504F1E6 +:10A21000FF344FF001084FF00008134B53F826703D +:10A2200027B91748BDE8F041FFF740BE2846394638 +:10A23000224604F055FD98B90120B040B8F1000F56 +:10A2400003D0F9F75FFB0F4802E0F9F7BDF90E48BC +:10A25000FFF72CFE39460D48BDE8F041F9F750BD37 +:10A260000136DAE78F0201088CFF0008D0010108EF +:10A2700044040108FE0D0108A202010888FF00083D +:10A28000B7020108D1020108DB0201086F010108D1 +:10A2900010B504460848FFF709FE084A002313706A +:10A2A000074A1360074A1370FCF790FB2046BDE88D +:10A2B0001040FFF701BF00BFE4020108991400201D +:10A2C000CC1400209814002008B50448FFF7EEFDD8 +:10A2D000F9F782F9BDE80840FFF7DCBEFC0201088F +:10A2E0002DE9F04389B0044604F0CAFCC6B2002E42 +:10A2F0006CD17B48FFF7DAFD7A4C20690021F6F734 +:10A30000EDFD40BB013678483146F9F7F9FC20698C +:10A3100004A9F9F7E3FD01467448F9F7F1FC606917 +:10A3200004A9F9F7DBFD01467048F9F7E9FCA069DB +:10A3300004A9F9F7D3FD01466C48F9F7E1FCE0699F +:10A3400004A9F9F7CBFD01466948F9F7D9FC0C2EB1 +:10A3500004F11004D1D10025664C2F462B464FF056 +:10A360000008B04504F1100415DA184654F8101C22 +:10A37000F6F718FB54F80C1C81462846F6F712FB3A +:10A3800054F8081C05463846F6F70CFB08F101089E +:10A390004B460746E5E75848019302950397FFF7B8 +:10A3A00085FD002401ABE058544920F00040F6F749 +:10A3B000BDFD534B534A0434002814BF10461846C1 +:10A3C000FFF774FD0C2CEDD14F4871E020464F494A +:10A3D000052204F085FC38B9424B002203441030BA +:10A3E000C0281A61F8D177E020464949042204F0D8 +:10A3F00077FC054620460DBB202104F069FB0028B0 +:10A400006AD0461C304604F03BFC2C460746414BC4 +:10A4100053F824500DB940484AE030462946FAB274 +:10A4200004F05EFC40B920463C49FCF76FFB3C4819 +:10A430002946F9F765FC47E00134E8E703F0D6FF69 +:10A44000461E0B2E074643DC2046202104F040FB2D +:10A45000054640B1451C2846F9F7A8FD214B3F01B0 +:10A46000D851012400E004462846202104F030FBA6 +:10A47000054640B1451C2846F9F798FD194B0134B3 +:10A4800003EB061358612846202104F021FB054602 +:10A4900040B1451C2846F9F789FD124B013403EB06 +:10A4A000061398612846202104F012FB18B91D48B4 +:10A4B000FFF7FCFC10E00130F9F778FD094B032CA5 +:10A4C00003EB0616F061F2D11748FFF709FF03E02E +:10A4D00016480C21F9F714FC09B0BDE8F08300BF61 +:10A4E0001D030108E8190020480301084E03010874 +:10A4F0006F010108FC190020520301080AD7233C10 +:10A500001903010815030108440401086103010847 +:10A5100067030108D8FF00086C030108F819002040 +:10A52000840301089703010883060108D103010889 +:10A53000F8B5074604F0A4FB044638B91A4B1B488B +:10A540005A791B4B013A53F8221028E03846194932 +:10A55000224604F0C5FB60B91748FFF7A7FC174C6B +:10A5600054F8041F19B11648F9F7CAFBF8E7154863 +:10A5700005E000250E4B53F8256026B91248BDE8CA +:10A58000F840FFF793BC38463146224604F0A8FB5A +:10A5900001350028EED1044B0C485D713146BDE811 +:10A5A000F840F9F7ADBB00BFE8190020F903010836 +:10A5B000D8FF0008FE0D01080D040108D4FF0008B3 +:10A5C000D0010108440401086C03010820040108BB +:10A5D0002DE9F047074604F053FB4D4D064620B1E8 +:10A5E000012818D13B782A2B15D14A48FFF75EFC89 +:10A5F000002429594848F9F783FB28193146FFF709 +:10A60000F9FC4648FFF752FC143440F6EC139C4228 +:10A61000EFD1BDE8F08738463D2104F059FA002813 +:10A620005BD0441C204603F0E1FE82462046F9F749 +:10A63000BDFC002406464FF0140909FB04F955F847 +:10A640000980404604F01CFB41460246384604F0AF +:10A6500047FB002839D12E4F4F44F868F6F756FAD9 +:10A6600001463046F6F758FC00282CD03869F6F73A +:10A670004DFA01463046F6F745FC20B33B79052BF1 +:10A680004FF0140303FB0454227918BF5646052AE1 +:10A690000FD8DFE802F003030606090CA268167063 +:10A6A00007E0A268168004E0A268166001E0A368D3 +:10A6B0001E6041461A48F9F723FB20460021BDE8F9 +:10A6C000F047FFF797BC174803E001347F2CB2D165 +:10A6D0001548BDE8F047FFF7E9BB04462E59394657 +:10A6E000304604F0ABFC58B10B483146F9F708FB93 +:10A6F000074800212044FFF77DFC0848F9F700FBDC +:10A70000143440F6EC139C42E8D1BDE8F08700BF5A +:10A7100040100108320401080C0601084404010835 +:10A7200047040108520401087704010810B50446E3 +:10A73000204604F0A5FA10F0FF0F07D10B4B0C4890 +:10A7400093F84814BDE81040F9F7DABA204603F050 +:10A750004DFE022808D8054B064C83F84804F8F74C +:10A76000D3FEF9F743F9E3E710BD00BFE819002075 +:10A77000940401088306010870B5044604F080FAC9 +:10A7800008B9204830E020461F4904F057FD002456 +:10A790002646254678B12CB1012C06D103F026FEC1 +:10A7A000064602E003F022FE054617490020013468 +:10A7B00004F044FDEEE70B2D05D9BDE870401348C9 +:10A7C0000C21F9F79DBA012C08DC114B294633F90D +:10A7D00015201048BDE87040F9F792BAA6F57A73D3 +:10A7E000B3F57A7F04D90C48BDE87040F9F788BA10 +:10A7F0000A4829463246F9F783FA054B23F81560D3 +:10A8000070BD00BFAA0401084D060108E404010858 +:10A81000DC1F00200A050108220501084405010883 +:10A8200038B5054604F02CFAC0B268B90446124B9C +:10A83000214603EB44031148B3F876200134F9F7BD +:10A840005FFA162CF3D138BD284603F0CFFD15284A +:10A8500004460BDC2021284604F03AF903F0C6FD3B +:10A86000054B03EB4404A4F8760038BD04481621D8 +:10A87000BDE83840F9F744BA341E00205D050108F0 +:10A88000690501082DE9FF47584C5948F9F738FA8E +:10A890005848FFF7C5FF6279574B013A53F8221029 +:10A8A0005648F9F72DFA20690021F6F717FB2746DD +:10A8B00000285AD10546266900213046F6F70EFBDE +:10A8C00000284ED101354E482946D4F814A0D4F8BA +:10A8D0001890D4F81C80F9F713FA30460021F6F7E7 +:10A8E00007FB10B14748F9F70BFA69463046F9F70C +:10A8F000F5FA01464448F9F703FA50460021F6F705 +:10A90000F7FA10B13F48F9F7FBF969465046F9F7F5 +:10A91000E5FA01463C48F9F7F3F948460021F6F715 +:10A92000E7FA10B13748F9F7EBF969464846F9F705 +:10A93000D5FA01463448F9F7E3F940460021F6F725 +:10A94000D7FA10B12F48F9F7DBF969464046F9F715 +:10A95000C5FA01462D48F9F7D3F90C2D04F110047E +:10A96000A9D12B48691CF9F7CBF9F9F785F8294CDF +:10A97000054654F8041F19B12748F9F7C1F9F8E75B +:10A980000C46264B53F8241041B10123A3402B421F +:10A9900002D02348F9F7B4F90134F2E7CB1993F860 +:10A9A000083104AA13441F4A8A5C0131082903F8BC +:10A9B000102CF3D100241C4869468DF80840F9F7A3 +:10A9C0009FF91A4D1A486159F9F79AF92819002187 +:10A9D000FFF710FB1748FFF769FA143440F6EC1341 +:10A9E0009C42EED104B0BDE8F08700BFE81900201A +:10A9F0008F05010883060108D8FF0008BF0501087C +:10AA0000CA0501084D060108DB0101086F010108B4 +:10AA1000D205010888FF0008E40501088CFF000842 +:10AA2000F2050108D0FE0008FF05010840100108EA +:10AA300008060108440401082DE9F0476C4B86B074 +:10AA40001A7899466B4F7AB901233868022189F840 +:10AA50000030FFF77DF83868F9F77EF96648FFF7B0 +:10AA600025FA6648FFF722FA3868FAF739FC002819 +:10AA700000F0BB805F4B624C1868FAF736FC09287F +:10AA8000014601D03F2852D14FF00008D4F800A071 +:10AA90005C4E4546BAF1000F05D05B48316852461E +:10AAA00004F01EF910B9B04605B93546574B0C36BF +:10AAB0009E42EFD3CDB1D5F800E0D8F800C05346A0 +:10AAC0001EF803601CF80300B04201D023600CE0C4 +:10AAD0005A1C4D4930B92D2B04D82026CE54226063 +:10AAE000885402E0CE541346EAE723681BB145457B +:10AAF00001D1554611E04648FFF7D8F9454508D839 +:10AB000055F80C0BFFF7D2F938680921FAF7D8FB92 +:10AB1000F4E73A48FFF7CAF9002523689D42A3D21B +:10AB2000394B3868595DFAF7CBFB0135F5E72368F7 +:10AB30002BB9042836D13448FFF7AAFB55E00C287E +:10AB400001D134488BE70A2901D00D2944D132487C +:10AB5000FFF7ACF92C4D22680023AB5404932F4B24 +:10AB600003A80093274910220C23039503F042FC0D +:10AB7000064638B1006804F083F80130B368284411 +:10AB8000984702E02648FFF791F91F48002130223C +:10AB900003F080FC0023236099F80030002B7FF441 +:10ABA00060AF22E00C28CCD07F2903D15CE72F2BAB +:10ABB0003FF65AAFA1F12002D2B25E2A3FF654AF5F +:10ABC00013B920293FF450AF5A1C22600E4A38684E +:10ABD000D154FAF775FB47E77F29E8D10A4A013BD0 +:10ABE00000212360D1540F483CE706B0BDE8F08750 +:10ABF00098140020D0140020120601084A0601080B +:10AC0000CC1400203400010899140020F40001083D +:10AC10004F0601085406010844040108D99F0008A2 +:10AC20005F0601088006010837B505460220FEF7D9 +:10AC300073FF064C0146206030B90090AA680220DC +:10AC40000323FFF795F8206003B030BDD014002037 +:10AC5000F8B5154E154C164D0746C1B23068217037 +:10AC6000FAF72EFB22782B78C7F307215340306880 +:10AC70002B702170FAF724FB22782B78C7F3074159 +:10AC8000534030682B702170FAF71AFB22782B782A +:10AC9000390E534030682B702170FAF711FB2B7876 +:10ACA000227853402B70F8BDE4140020E9140020F2 +:10ACB000D5140020F8B50C4E0C4D0D4CC1B2074612 +:10ACC00030682970FAF7FCFA2A782378C7F307214D +:10ACD0005340306823702970FAF7F2FA23782A7803 +:10ACE00053402370F8BD00BFE4140020001500207D +:10ACF000D5140020054B10B5044621461868FAF714 +:10AD0000DFFA034B1A7854401C7010BDE414002085 +:10AD1000D5140020034A1378591C1170024AD05CE4 +:10AD2000704700BFD61400200115002010B5FFF7B2 +:10AD3000F1FF0446FFF7EEFF04EB002080B210BDE8 +:10AD400010B5FFF7F3FF0446FFF7F0FF04EB0040F8 +:10AD500010BD000038B5044624200D46FFF7CAFF99 +:10AD60004D20FFF7C7FF002C0CBF3E202120FFF72E +:10AD7000C1FF064B284600221A70FFF7BBFF044BA9 +:10AD80001878BDE83840FFF7B5BF00BFD5140020E4 +:10AD9000E814002001460020FFF7DCBF0146012037 +:10ADA000FFF7D8BF014B1878FFF7A4BFD5140020D8 +:10ADB00070B5064608460D46FFF7ECFF0024E3B2E7 +:10ADC0009D4204D0305DFFF795FF0134F7E770BD79 +:10ADD00010B5441E14F8010F10B1FFF78BFFF9E70F +:10ADE00010BD00002DE9F047002701240025154B78 +:10ADF0001B789D421DDA144B144E15F803800C236A +:10AE000003FB0863586803F03BFFB24681460CB968 +:10AE1000264601E007440AE04E4508DA0C2303FB0E +:10AE200008A35B68985DFFF765FF0136F4E701351D +:10AE3000DDE724B1F8B2FFF7ADFF0024D6E7BDE8A7 +:10AE4000F08700BFD8140020EA1400206000002022 +:10AE5000F8B5D94B1B787B2B00F0498300F2C680F4 +:10AE60006E2B00F0BC8360D8682B00F05C8325D883 +:10AE7000652B00F04E8219D8642B40F066850720C0 +:10AE8000CE4CFFF787FFE620FFF734FF6079FFF72E +:10AE900031FF0020FFF72EFF94F81B01C84BC94A71 +:10AEA00000280CBF1046184600F02CBD662B00F0A1 +:10AEB000B382672B40F04985C34835E36B2B00F024 +:10AEC0006C8323D8692B00F055836A2B40F03D85B5 +:10AED0001020FFF75FFFBD4BBD4CD87AFFF70AFF8C +:10AEE000BC4B1878FFF706FF2068FFF7B1FE6068DB +:10AEF000FFF7AEFEB84BB3F90000FFF7DBFEB74B30 +:10AF0000B3F90000FFF7D6FEB54B65E36C2B00F0FC +:10AF100056836D2B40F019850620FFF73BFFB14BA0 +:10AF20001868FFF795FEB04B56E3732B00F02384AF +:10AF30003DD8702B00F08383C0F06283712B00F04A +:10AF4000F183722B40F001859C4C1620FFF722FF05 +:10AF50000020FFF7AFFEB4F9D000FFF7ABFEA34D22 +:10AF6000B4F9D200FFF7A6FEB4F9D400FFF7A2FEB1 +:10AF7000B5F9EC00FFF79EFE0020FFF79BFE0020D6 +:10AF8000FFF766FEB5F95A000A2390FBF3F0FFF7CE +:10AF900091FE94F80401FFF7ADFE94F80601FFF767 +:10AFA000A9FE94F80501FFF7A5FE00F013BC762B6F +:10AFB00000F0EC830DD8742B00F0CB83752B40F0A0 +:10AFC000C4842F20FFF7E6FE8948FFF701FF00F059 +:10AFD000BFBC772B00F0C083782B40F0B684834C45 +:10AFE0003820FFF7D7FE04F140054EE2D02B00F0E9 +:10AFF000248400F29B80CA2B00F0068139D8A42B50 +:10B0000000F0838411D8A02B40F09F840C20FFF720 +:10B01000C1FE784B1868FFF71BFE774B1868FFF7E7 +:10B0200017FE764B186800F06DBCC82B00F0B58099 +:10B03000C92B40F08A84FFF76DFE644B644CD872D4 +:10B04000FFF768FE634B1870FFF77AFE2060FFF78A +:10B0500077FE6060FFF76AFE5F4B1880FFF766FEC1 +:10B060005E4B1880664B1A7842F002021A7000F0AC +:10B0700030BCCD2B00F0E88324D8CB2B00F08B80A4 +:10B08000CC2B40F06284FFF745FE584C84F850000A +:10B09000FFF740FE84F85100FFF73CFE84F85400AF +:10B0A000FFF738FE84F85500FFF734FE84F85600A9 +:10B0B000FFF730FE84F85200FFF72CFE84F85300AF +:10B0C00000F007BCCE2B00F0C883CF2B40F03D84AE +:10B0D000FFF72CFEFFF72AFE384C444DA4F8D000B1 +:10B0E000FFF724FEA4F8D200FFF720FEA4F8D40056 +:10B0F000FFF71CFEA5F8EC00FFF718FEFFF720FE97 +:10B10000FFF714FE00EB80004000A5F85A00FFF79F +:10B1100001FE84F80401FFF7FDFD84F80601FFF746 +:10B12000F9FD84F80501FFF7F5FDD2E3D52B00F01A +:10B13000EC8111D8D22B00F0D880C0F04F83D32BF4 +:10B1400000F0E280D42B40F00084284C0020FFF770 +:10B1500021FE04F14005ACE1F02B00F0C6830FD8CE +:10B16000D62B00F0B980EF2B40F0EF83FFF7DEFD28 +:10B170001E4CA4F85E00FFF7D9FDA4F85C00A8E31C +:10B18000FA2B00F09983FE2B40F0DF830820FFF7B5 +:10B1900001FE0024A1E300248EE00024FFF7C6FD99 +:10B1A000184B18530234102CF8D10020FFF7F2FD91 +:10B1B000FDF7F6FCCCE300BFE8140020E8190020FE +:10B1C0001C00008014000080180000205F20002078 +:10B1D000342000204C200020062000200A200020DF +:10B1E0001C110020A01F00207C0E0020341E002017 +:10B1F0002C1A0108E8F7FF1FECF7FF1FF0F7FF1FFD +:10B20000EC110020BA200020C94B1A781C46022AF3 +:10B2100042D103F1200503F12C06FFF77BFDF5F782 +:10B2200071FCC449F5F77AFD45F8040FFFF772FD8C +:10B23000F5F768FCC049F5F771FDE860FFF76AFDB6 +:10B24000F5F760FCBD49F5F769FDB542A861E4D1A9 +:10B250000325072D12D1FFF75DFDF5F753FCB54926 +:10B26000F5F75CFDA064FFF755FDF5F74BFCB14920 +:10B27000F5F754FDE064FFF74DFD09E0FFF74AFDE7 +:10B2800066193071FFF746FDB073FFF743FD307666 +:10B2900001350A2DDDD11CE35C1E03F10905FFF722 +:10B2A00039FD01342071FFF735FDA073FFF732FD42 +:10B2B000AC422076F3D10CE3A14B1B789C4280F08A +:10B2C0000883A04BE55CFFF731FD994B013403EB9C +:10B2D0004505A5F87600EFE70024FFF727FD9A4B18 +:10B2E00018530234102CF8D1F3E2984B9C78002CC0 +:10B2F00040F0EF82FFF70EFD954B022894BF83F8D4 +:10B30000480483F84844E0E2FFF710FD914B1880B1 +:10B31000DFE20B20FFF73EFD8F4BB3F90000FFF794 +:10B32000C9FCF6F727FC00B2FFF7C4FC0220FDF7CA +:10B33000C1F905460420FDF7BDF904460820FDF7D4 +:10B34000B9F9800040EA44042020FDF7B3F92C430A +:10B35000A4B244EAC00084B21020FDF7ABF944EA7D +:10B36000001000B2FFF7A6FC784A00201479D378C9 +:10B37000A40044EA430493781C43937944EAC30449 +:10B38000537944EA4314537A44EA8314734BD979CA +:10B3900044EAC114197A44EA0124597A44EA41245E +:10B3A000D17944EA8124117A927A44EAC12444EAA8 +:10B3B00002345A7B44EA42349A7B44EA82341A7C4F +:10B3C00044EA02441A7944EA02145A7C44EA4244A8 +:10B3D0009A7C44EA8244DA7C44EAC2441A7D5B7D6A +:10B3E00044EA025444EA4354554B197803468B42CD +:10B3F0000CD2544A9D5C012202FA05F5254218BF81 +:10B400009A4003F1010318BF1043F0E7FFF720FC57 +:10B410004F4B93F84804DEE11220FFF7BBFC504B82 +:10B42000504C1B88B3F5806F22D90025605F08233C +:10B4300090FBF3F00235FFF73DFC062DF6D14A4CA8 +:10B44000B4F90000FFF736FCB4F90200FFF732FC54 +:10B45000B4F90400454CFFF72DFCB4F90000FFF7E8 +:10B4600029FCB4F90200FFF725FCB4F9040046E218 +:10B47000B4F90000FFF71EFCB4F90200FFF71AFC54 +:10B48000B4F90400FFF716FCD9E7B4F9AA00FFF7F6 +:10B4900011FCB4F9AC00FFF70DFCB4F9AE00FFF7F6 +:10B4A00009FC083494F8A800FFF724FCAC42ECD166 +:10B4B0004EE2FFF73BFCA4F8AA00FFF737FCA4F824 +:10B4C000AC00FFF733FCA0F57A7307289BB298BF56 +:10B4D00084F8B100B3F57A7F98BFA4F8AE00FFF707 +:10B4E00019FC083484F8A800AC42E2D130E208200C +:10B4F000FFF750FC00240E4B234493F8B1000834AE +:10B50000FFF7F8FB402CF6D122E20020FFF742FCC7 +:10B510000024FFF7FFFB064B23440834402C83F83C +:10B52000B100F6D114E212481021FFF741FC0FE2FE +:10B53000341E0020000020410000C84200007A4470 +:10B54000D8140020EA140020DC1F00205F20002017 +:10B55000E81900206C1F00209E0C002071200020A4 +:10B5600004000020A81F0020700E0020541F00209F +:10B57000C41F0020BC4D00242878400000F0FE00CD +:10B58000FFF708FC2B789C4280F0E281B74B33F93F +:10B590001400FFF78FFB0134F4E70520FFF7FAFBF7 +:10B5A000B34BB3F90000FFF785FBB24BB3F90000D2 +:10B5B000FFF780FBB04B187800F001000BE1AF4CB7 +:10B5C0000620FFF7E7FBB4F90000FFF773FBB4F9BF +:10B5D0000200FFF76FFBAA4BB3F900008FE10720D1 +:10B5E000FFF7D8FBA74B1878FFF784FB0020FFF785 +:10B5F00061FBA54BB3F90000FFF75CFB00207EE187 +:10B60000A24C0720FFF7C6FB94F85000FFF772FB2F +:10B6100094F85100FFF76EFB94F85400FFF76AFBB3 +:10B6200094F85500FFF766FB94F85600FFF762FBAD +:10B6300094F85200FFF75EFB94F85300CBE01E2015 +:10B64000FFF7A8FB914B1A781C46022A5AD103F146 +:10B65000200503F12C0655F8040F8D49F5F7AAFAD9 +:10B6600001F094FBFA220021F8F70CFAC0B2FFF7C0 +:10B6700041FB8849E868F5F79DFA01F087FBFA225B +:10B680000021F8F7FFF9C0B2FFF734FB8249A8693F +:10B69000F5F790FA01F07AFB00216422F8F7F2F94D +:10B6A000C0B2FFF727FBB542D5D10325072D1BD12B +:10B6B0007749A06CF5F77EFA01F068FBFA220021C9 +:10B6C000F8F7E0F9C0B2FFF715FB7149E06CF5F748 +:10B6D00071FA01F05BFB0021FA22F8F7D3F9C0B24E +:10B6E000FFF708FB002007E066193079FFF702FB3F +:10B6F000B07BFFF7FFFA307E0135FFF7FBFA0A2D2A +:10B70000D4D125E15C1E03F1090501342079FFF74E +:10B71000F1FAA07BFFF7EEFA207EFFF7EBFAAC42DE +:10B72000F3D115E15D4D00242878400000F0FE00C3 +:10B73000FFF730FB2B789C4280F00A81584BE25C8B +:10B74000524B013403EB4203B3F97600FFF7B2FA30 +:10B75000F0E7FFF747FBFBE0504D00242878FFF7A8 +:10B7600019FB2B789C4280F0F3804D4B185DFFF75E +:10B77000C1FA0134F5E70820FFF70CFB0124E0B221 +:10B780000134FFF7B7FA092CF9D1E1E0FFF7C2FA6B +:10B7900006461220FFF7FEFA0EB9424B02E0102EC9 +:10B7A00003D1414B1D685C6801E00024254630460A +:10B7B000FFF7A0FA2846FFF74BFA2046FFF748FAB2 +:10B7C0003A4B1868FFF744FA0020FFF773FA00209D +:10B7D000FFF770FA0020FFF78DFAB9E0FFF79AFA49 +:10B7E0000546FFF7ADFA0746FFF7AAFA0646FFF748 +:10B7F000A7FA0446FFF79AFAFFF798FAFFF78AFAD2 +:10B800005DB9284B01225E601F60294BDD711A7300 +:10B81000002C5ED0254B1C605BE0102D59D1224BD3 +:10B820001F605E600CB1214B1C601F48214B02223F +:10B83000011D1A70FCF78CFD4BE01D4B9B78002B13 +:10B8400047D1F7F7C9FE42E0194B9B78002B40D156 +:10B850004FF4C870F9F7EEFA3BE0154B9A78002ADE +:10B8600037D101229A7334E0B6200020BA2000209C +:10B870001420002020200020EC110020A00E002029 +:10B880007E1F0020E4190020B8200020341E002074 +:10B89000000020410000C84200007A44D814002073 +:10B8A000EA140020182000200C200020A41F0020F3 +:10B8B0005F200020B40F0020274B9B78002B44D141 +:10B8C000264B93F84804F7F70FFEF7F71DFEF8F73D +:10B8D0008DF80020FFF75EFA3AE0214B185F023442 +:10B8E000FFF7E8F9082CF8D132E01E4C0420FFF7EE +:10B8F00051FAB4F95E00FFF7DDF9B4F95C00FFF727 +:10B90000D9F925E0FFF7A4F922E0174D00242878A3 +:10B9100080000130C0B2FFF73DFA2878FFF7EAF95E +:10B920002B789C4214D2114B185DFFF7E3F9104BB2 +:10B93000185DFFF7DFF90F4B185DFFF7DBF90E4BD2 +:10B94000185DFFF7D7F90134EAE70020FFF726FA80 +:10B95000BDE8F840FFF726BA5F200020E819002074 +:10B960003E1F0020341E00204D200020F41F002028 +:10B97000222000203C2000204E2000202DE9F34111 +:10B98000474DFF2116220746284602F083FD00237B +:10B9900002202B70FCF78EFE012418B102236C707C +:10B9A000AB7003240420FCF785FE68B103234FF439 +:10B9B0000050661C2B55F7F7FDFD20B1384B0422D3 +:10B9C00002349A5500E034460220FCF773FE48B179 +:10B9D0002A19052306212B55A31C51700722EA546E +:10B9E000033404E00820FCF765FE0028F0D1202095 +:10B9F000F7F7E0FD10B108232B5501344FF48070A8 +:10BA0000F7F7D8FD28B10A222A55631C0B22EA5405 +:10BA10000234244A53799046082B01D00E2B02D1D0 +:10BA20000C232B5501340D230420661C2B55F7F7EE +:10BA3000C1FD18B11A4B11229A55A61C98F839016C +:10BA40001323003018BF0120741CAB55F7F7B2FD6B +:10BA500018B1134B14221A55B41C15232B55124B35 +:10BA600001341C70114B00221A601D467A680024B4 +:10BA70000021009101200323FEF77AF920B94CB987 +:10BA80004FF496420124F3E72A68002AEED1074BCF +:10BA90001860EBE702B0BDE8F041FDF7BDBF00BFA5 +:10BAA000EA140020E8190020D8140020E414002033 +:10BAB00010B5304C2068F9F713FC002858D02068E6 +:10BAC000F9F713FC2C4C034622786AB9B0F1240232 +:10BAD000534253412370002BEBD1284B9B78002B12 +:10BAE000E7D1FEF7D3F9E4E7012A04D14D2814BFCA +:10BAF000002302233AE0022A04D13C2814BF002389 +:10BB0000032333E0032A0FD140284FF0000201D96C +:10BB10002270CEE71A49042308701A490A701A499C +:10BB20000A701A4A107021E0042A08D1184A1070CD +:10BB3000164A117880EA01031370052316E0052ADE +:10BB4000B7D110480E4A017812788A420F4A07D9B5 +:10BB500014785C4014704A1C02700E4A5354A8E7D3 +:10BB600012789A4201D1FFF773F900232370A0E7FE +:10BB700010BD00BFE4140020D41400205F2000207A +:10BB8000D7140020E0140020D6140020D514002083 +:10BB9000E81400200115002010B5074C074A23685F +:10BBA000D25C074B1A70FFF753F923680133092B56 +:10BBB00088BF0023236010BDDC140020151B010882 +:10BBC000E81400202DE9F04106460F469046002576 +:10BBD000EBB243450DD20024E3B2B34204D238465F +:10BBE000F9F7CBFB0134F7E73C20F9F7C6FB013549 +:10BBF000EEE7BDE8F08100000F4B1A6842F0010249 +:10BC00001A6059680D4A0A405A601A6822F0847214 +:10BC100022F480321A601A6822F480221A605A686C +:10BC200022F4FE025A604FF41F029A60044B4FF058 +:10BC300000629A60704700BF001002400000FFF8E9 +:10BC400000ED00E0144A154B516801F00C01042985 +:10BC500003D0082904D0124914E01249096811E000 +:10BC600051685068C1F38341C00301F1020101D45E +:10BC70000D4806E0506810F4003F0A48006818BFFD +:10BC800040084143196052680849C2F30312895CB5 +:10BC90001A68CA401A6070470010024088010020EC +:10BCA00000127A008401002000093D007401002088 +:10BCB0001FB500230093019302934FF4E013039305 +:10BCC000504B1A6842F480321A609A6942F01002AE +:10BCD0009A611A6802F400320192009A01320092CD +:10BCE000019A1AB9009AB2F5A06FF2D11968454AC3 +:10BCF00011F4003101D0022215E0146844F001046F +:10BD0000146000911A6802F002020192009A013256 +:10BD10000092019A1AB9009AB2F5A06FF2D11A688E +:10BD2000920739D501220292374A384C116841F006 +:10BD300010011160116821F003011160116841F0D8 +:10BD4000020111605A685A605A685A605A6842F48F +:10BD500080625A602E4A1168043A21F070415160A5 +:10BD60002C490C605C6824F47C145C60546844F0DA +:10BD700000445460D46824F40044D46092681404ED +:10BD800049BF254A4FF4E0120A604FF48012039233 +:10BD9000029A012A01D117E0FEE7022A18D168B100 +:10BDA000039AB2F5801F02D14FF4A01205E0039A66 +:10BDB000B2F5E01F02D14FF4001203925968039AC2 +:10BDC0000A4342F4803202E05A6842F460125A6038 +:10BDD0001A6842F080721A6019680A4A8901FBD514 +:10BDE000516821F003015160516841F00201516036 +:10BDF0005A6802F00C02082AFAD1FFF723FF04B0B8 +:10BE000010BD00BF001002400020024000127A0066 +:10BE10000410014084010020001BB70008B5154B39 +:10BE200098420BD14FF48050012100F0B7FDBDE8DE +:10BE300008404FF48050002100F0B0BD0E4B9842F6 +:10BE400007D14FF48040012100F0B4FD4FF4804051 +:10BE500009E00A4B98420BD14FF40040012100F059 +:10BE6000A9FD4FF400400021BDE8084000F0A2BD4C +:10BE700008BD00BF0030014000380040003C0040D9 +:10BE80000B8810B54C88028823438C8802F44152F9 +:10BE90002343CC8823430C8923434C8923438C8937 +:10BEA0002343CC89234313439BB20380838B23F426 +:10BEB00000631B041B0C83830B8A038210BD038861 +:10BEC00019B19BB243F0400303E023F040031B048D +:10BED0001B0C0380704781817047808980B2704756 +:10BEE000038919420CBF00200120704743680A688B +:10BEF00023F4702323F4807313430A7910B543EAC3 +:10BF0000022343608A68CB6884681A43084B234045 +:10BF100013434A7943EA420383600B7CC26A013BC4 +:10BF200022F47002DBB242EA0353C36210BD00BFC9 +:10BF3000FDF7F1FF836811B143F0010301E023F045 +:10BF4000010383607047836811B143F4807301E09B +:10BF500023F4807383607047836843F00803836031 +:10BF600070478068C0F3C0007047836843F00403E3 +:10BF7000836070478068C0F380007047836811B1A8 +:10BF800043F4A00301E023F4A00383607047092970 +:10BF900070B50DD9A1F10A0404EB44040725A540AE +:10BFA000A340C66826EA050545EA0304C4600BE021 +:10BFB00001EB41040725A54003FA04F4066926EACB +:10BFC000050545EA04030361062A0CD8013A02EB91 +:10BFD00082021F23934001FA02F2446B24EA030316 +:10BFE0001A43426370BD0C2A0CD8073A02EB820256 +:10BFF0001F23934001FA02F2046B24EA03031A435D +:10C00000026370BD0D3A02EB82021F23934001FAD6 +:10C0100002F2C46A24EA03031A43C26270BD00003C +:10C0200040F0BF60024B40F40030D860704700BF62 +:10C0300000ED00E0C27810B50378FAB1154A4478F3 +:10C04000D26803F16043D243C2F30222C2F1040179 +:10C0500004FA01F10F2424FA02F2847803F5614313 +:10C0600022400A431201D2B283F80023037801224E +:10C07000590903F01F0302FA03F306E059090122EC +:10C0800003F01F0302FA03F32031034A42F8213080 +:10C0900010BD00BF00ED00E000E100E030B5048C11 +:10C0A00024F001042404240C0484058B048CADB218 +:10C0B00025F0F3052A4342EA03139DB2104BA4B2C4 +:10C0C000984215D003F50063984211D0B0F1804F2B +:10C0D0000ED0A3F5983398420AD003F580639842B6 +:10C0E00006D003F58063984218BF24F00A0401D1FA +:10C0F00024F0020444F0010421430583018430BD8F +:10C10000002C014030B5048C24F010042404240CCD +:10C110000484048B058C24F440742405240D44EA23 +:10C12000022242EA0333144AADB290429BB212D0CB +:10C1300002F5006290420ED0B0F1804F0BD0A2F514 +:10C140009832904207D002F58062904203D002F507 +:10C150008062904207D125F0200545F0100545EAA0 +:10C16000011189B204E025F0A00545F0100529432E +:10C170000383018430BD00BF002C0140224A0388A4 +:10C1800090429BB212D002F5006290420ED0B0F104 +:10C19000804F0BD0A2F59832904207D002F5806212 +:10C1A000904203D002F58062904203D14A8823F086 +:10C1B00070031343154A904208D002F58062904202 +:10C1C00004D023F44073CA889BB2134303808B8846 +:10C1D00083850B8803850C4B98420FD003F50063D1 +:10C1E00098420BD003F54063984207D003F5806373 +:10C1F000984203D003F58063984201D10B7A0386FD +:10C2000001238382704700BF002C014000100040D2 +:10C21000038C70B523F001031B041B0C0384038CF7 +:10C220008488028B0D8822F073021204120C2A43B8 +:10C230004E880D8923F002031B043543ADB21B0C5D +:10C240002B43144DA4B2A8420FD005F50065A842B7 +:10C250000BD005F54065A84207D005F58065A842DA +:10C2600003D005F58065A8420ED14D8923F008035F +:10C270002B438D8823F004032B43CE898D8924F42E +:10C2800040743543ADB22C4384800283CA888286D1 +:10C29000038470BD002C0140038C30B523F01003E3 +:10C2A0001B041B0C0384038C8288048B0D8824F4EC +:10C2B000E6442404240C23F0200344EA05241B0450 +:10C2C0000D891B0C43EA05134D8892B243EA05130E +:10C2D000124DA4B2A8429BB203D005F50065A84256 +:10C2E00015D14D8923F080039BB243EA05134FF625 +:10C2F000BF751D408B8822F4406245EA03138D8987 +:10C300009BB242EA8502CD8942EA850292B28280DE +:10C31000CA8804830287038430BD00BF002C01401B +:10C32000038C30B523F480731B041B0C0384038C33 +:10C330008288848B0D8824F073042404240C23F455 +:10C3400000732C431B040D891B0C43EA05234D8805 +:10C3500092B243EA0523124D9BB2A84203D005F5E1 +:10C360000065A84215D14D8923F400639BB243EACE +:10C3700005234FF6FF351D408B8822F4405245EAD5 +:10C3800003238D899BB242EA0512CD8942EA051248 +:10C3900092B28280CA8884838287038430BD00BFC2 +:10C3A000002C0140038C30B523F480531B041B0C7C +:10C3B0000384038C8488828B0D8822F4E642120465 +:10C3C000120C23F4005342EA05221B040D891B0CB6 +:10C3D00043EA05334D88A4B243EA05330A4D92B2CD +:10C3E000A8429BB203D005F50065A84205D18D890E +:10C3F00024F4804444EA8514A4B284808283CA88E9 +:10C40000A0F84020038430BD002C01404FF6FF739C +:10C41000838000230380C38043800372704700231E +:10C42000038043808380C380038143818381C381F0 +:10C43000704700230122038043808280C3800381F0 +:10C440007047038819B19BB243F0010303E023F066 +:10C4500001031B041B0C03807047B0F8443029B162 +:10C460006FEA43436FEA53439BB201E0C3F30E0309 +:10C47000A0F84430704783899BB20AB1194301E0A8 +:10C4800023EA010181817047038B23F008031B0419 +:10C490001B0C194301837047038B23F400631B04B7 +:10C4A0001B0C43EA01218BB203837047838B23F07B +:10C4B00008031B041B0C194381837047838B23F4EF +:10C4C00000631B041B0C43EA01218BB2838370477A +:10C4D00081847047038B23F00C031B041B0C038324 +:10C4E000038B9BB2194301837047038B23F4406392 +:10C4F0001B041B0C0383038B9BB243EA01218BB209 +:10C5000003837047838B23F00C031B041B0C838372 +:10C51000838B9BB2194381837047838B23F44063E1 +:10C520001B041B0C8383838B9BB243EA01218BB2D8 +:10C530008383704770B50E880D4604464988AA88E3 +:10C540002B893EB9FFF7AAFD2046E988BDE8704077 +:10C55000FFF7C0BF042E07D1FFF7D4FD2046E988BE +:10C56000BDE87040FFF7C1BF082EEE88058C39D1B9 +:10C5700025F480752D042D0C0584808B258C80B2CC +:10C5800020F0F30040EA03139BB21A43344BADB2E0 +:10C590009C4212D003F500639C420ED0B4F1804F50 +:10C5A0000BD0A3F598339C4207D003F580639C42DF +:10C5B00003D003F580639C4207D125F4007545EA5A +:10C5C000012189B241F4807104E025F4206541F431 +:10C5D00080712943A283204621843146BDE8704002 +:10C5E000FFF790BF25F480552D042D0C0584808B1A +:10C5F000258C20F440700005000D40EA0220184A06 +:10C6000040EA03339442ADB29BB212D002F500620D +:10C6100094420ED0B4F1804F0BD0A2F598329442E0 +:10C6200007D002F58062944203D002F58062944202 +:10C6300007D125F4005242EA013292B242F480520C +:10C6400005E047F6FF522A4041F480510A43A38394 +:10C65000204622843146BDE87040FFF75EBF00BF30 +:10C66000002C0140808E80B27047008F80B27047EE +:10C67000808F80B27047B0F8400080B27047038A64 +:10C68000828911EA030092B203D011420CBF00204C +:10C6900001207047C94389B201827047038ACA8862 +:10C6A0009BB223F44053134330B503820D46828975 +:10C6B0000989AB8892B20B43698922F4B0520B43CB +:10C6C00022F00C0213439BB28381838AAA899BB216 +:10C6D00023F4407387B013430446838201A800F01B +:10C6E000EDF81749049A039B8C4208BF1346A289B0 +:10C6F000192112B25943002A2A684FF06403B4BFCB +:10C7000052009200B1FBF2F1B1FBF3F212011009F9 +:10C7100003FB1011A08900B2002806DAC9003231EB +:10C72000B1FBF3F303F0070305E009013231B1FB7C +:10C73000F3F303F00F031A4392B2228107B030BD26 +:10C7400000380140838919B19BB243F4005303E0E0 +:10C7500023F400531B041B0C83817047C1F3421365 +:10C7600010B5012401F01F01A34204FA01F101D127 +:10C770000C3003E0022B0CBF1030143003680AB1F8 +:10C78000194301E023EA0101016010BD838A9BB2D5 +:10C790000AB1194301E023EA010181827047090AC5 +:10C7A00001238B40DB439BB203807047034B044A59 +:10C7B0005A6002F188325A60704700BF0020024080 +:10C7C00023016745024B1A6942F080021A617047E3 +:10C7D00000200240014BD860704700BF002002409B +:10C7E000084BDA68D10709D4DA68520708D4DB6845 +:10C7F00013F0100F0CBF0420032070470120704776 +:10C80000022070470020024010B50446FFF7E8FF01 +:10C81000012806D11CB1FFF7E3FF013CF8E7052032 +:10C8200010BD002C08BF052010BD000038B505461E +:10C830004FF43020FFF7E8FF042812D1094C4FF4E1 +:10C840003020236943F0020323616561236943F0CB +:10C8500040032361FFF7D8FF226941F6FD731340BF +:10C86000236138BD0020024073B5002306464FF413 +:10C8700000500D460193FFF7C7FF04281AD10E4C54 +:10C880004FF40050236943F001032361ABB23380BE +:10C89000FFF7BAFF042808D102360196019B2D0C40 +:10C8A0001D804FF40050FFF7AFFF226941F6FE7381 +:10C8B0001340236102B070BD002002401F4B10B531 +:10C8C0005A6802F00C02042A03D0082A04D01C4A39 +:10C8D00014E01C4A126811E05A685968C2F3834296 +:10C8E000C90302F1020201D4174906E0596811F4A4 +:10C8F000003F1449096818BF49084A4302605A6852 +:10C900001249C2F303128C5C0268E24042605C6828 +:10C91000C4F302240C5D22FA04F484605C68C4F35E +:10C92000C224095DCA40C2605B680949C3F3813310 +:10C93000CB5CB2FBF3F2026110BD00BF00100240FD +:10C9400000127A008401002000093D0090010020BF +:10C950008C010020044B5A6909B1104301E022EA1E +:10C9600000005861704700BF00100240044B9A69F4 +:10C9700009B1104301E022EA00009861704700BF4E +:10C9800000100240044BDA6909B1104301E022EAC9 +:10C990000000D861704700BF00100240044BDA6805 +:10C9A00009B1104301E022EA0000D860704700BFDF +:10C9B00000100240044B1A6909B1104301E022EA59 +:10C9C00000001861704700BF00100240024B5A6A15 +:10C9D00042F080725A6270470010024008B50B4B5B +:10C9E000984207D14FF400100121FFF7E3FF4FF405 +:10C9F000001006E04FF480000121FFF7DBFF4FF449 +:10CA000080000021BDE80840FFF7D4BF005400407B +:10CA1000F0B587B00446868801A80D46314FFFF770 +:10CA20004DFF039826F03F063604B0FBF7F7360CAF +:10CA30001FFA87FC4CEA0606A68021882A6821F0A6 +:10CA40000101294B0904090C9A4221800DD8530099 +:10CA5000B0FBF3F39BB20CF1010C032B1FFA8CFC1F +:10CA600098BF0423A4F820C022E0E9884BF6FF73A6 +:10CA7000994205D102EB4202B0FBF2F39BB206E011 +:10CA800019235343B0FBF3F39BB243F48043C3F346 +:10CA90000B020AB943F001034FF4967257434FF467 +:10CAA0007A7297FBF2F70137BFB243F40043278451 +:10CAB000A383238869899BB243F0010323802388E1 +:10CAC000AA8823F4816323F002031B040A431B0C8E +:10CAD00013439BB223802A89AB8913439BB22381E2 +:10CAE00007B0F0BD40420F00A086010041F288333C +:10CAF0000360002383804BF6FF72038143814FF470 +:10CB00008043C28083817047038819B19BB243F090 +:10CB1000010303E023F001031B041B0C0380704797 +:10CB2000038819B19BB243F4807303E023F480734C +:10CB30001B041B0C03807047038819B19BB243F49C +:10CB4000007303E023F400731B041B0C0380704785 +:10CB5000038819B19BB243F4806303E023F480633C +:10CB60001B041B0C0380704783889BB20AB11943D6 +:10CB700001E023EA01018180704701827047008A49 +:10CB8000C0B2704712B141F0010101E001F0FE01B5 +:10CB90000182704702684FF6FE7313400360002362 +:10CBA000036043608360C3602A4B984222D02A4BC3 +:10CBB000984229D0294B984230D0294B984237D0FF +:10CBC000284B98423ED0284B984206D153F8682C07 +:10CBD00042F4700243F8682C7047244B984206D107 +:10CBE00053F87C2C42F0706243F87C2C7047204B49 +:10CBF000984206D153F8042C42F00F0243F8042C5B +:10CC000070471C4B984206D153F8182C42F0F002A2 +:10CC100043F8182C7047184B984206D153F82C2C27 +:10CC200042F4706243F82C2C7047144B984206D1A2 +:10CC300053F8402C42F4704243F8402C7047104B9C +:10CC4000984205D153F8542C42F4702243F8542CE6 +:10CC5000704700BF080002401C0002403000024044 +:10CC600044000240580002406C0002408000024034 +:10CC7000080402401C040240300402404404024004 +:10CC8000580402408A6810B50C6A036814430A69A4 +:10CC900023F4FF4314434A6923F0700314438A6961 +:10CCA0001443CA6914434A6A14438A6A22431343E9 +:10CCB0000360CB6843600B6883604B68C36010BD42 +:10CCC0000023036043608360C36003614361836149 +:10CCD000C361036243628362704719B1036843F022 +:10CCE000010303E002684FF6FE73134003607047D0 +:10CCF00003680AB1194301E023EA010101607047AA +:10CD000041607047406880B270470000C3004CBF6C +:10CD1000014B024B58607047000402400000024083 +:10CD200000B5194A20F00043934283B0014617DD55 +:10CD3000B3F1FF4F04DBF3F733FE03B05DF804FB00 +:10CD4000694600F037FB00F00302012A00980199C0 +:10CD500011D0022A0AD09AB1012201F0EFF8ECE7D3 +:10CD6000002100F0EFFC03B05DF804FB00F0EAFCEA +:10CD700000F10040E1E701F0E1F800F10040DCE7FC +:10CD800000F0E0FCD9E700BFD80F493F30B5C0F351 +:10CD9000C754A4F17F031E2B83B0014620DC581C2E +:10CDA0001BDB162B4FEAD17509DDC1F3160040F4E9 +:10CDB0000000963CA04005B1404203B030BD114B8D +:10CDC00053F825402046F3F7EDFD019001982146E8 +:10CDD000F3F7E6FD20F0004333B9002003B030BD87 +:10CDE000F4F7AEF803B030BDC0F31604C0F3C7507B +:10CDF00044F40004C0F1960024FA00F0002DDCD0C9 +:10CE0000DAE700BF201B010800B51D4A20F00043EF +:10CE1000934283B0014618DDB3F1FF4F04DBF3F713 +:10CE2000BFFD03B05DF804FB694600F0C3FA00F0F3 +:10CE30000300012818D002280ED0D0B10098019923 +:10CE400000F080FC00F10040EBE70021002201F03F +:10CE500075F803B05DF804FB00980199012201F018 +:10CE60006DF800F10040DCE70098019900F06AFCE1 +:10CE7000D7E700980199012201F060F8D1E700BFDF +:10CE8000D80F493F70B58AB0054600F09BF8224C98 +:10CE9000064694F90030013303D0284601F02CFAFD +:10CEA00010B930460AB070BD284601F0DBF94FF0EA +:10CEB0007E51F4F73BF80028F3D0184901220023F3 +:10CEC0002846009208930191F3F7B0FA02460B4608 +:10CED0001348CDE90423CDE9022301F0A7F894F922 +:10CEE0000030CDE90601022B0BD0684601F09CF81A +:10CEF00038B1089B53B9DDE90601F3F7FDFC0AB030 +:10CF000070BD01F099FA21230360F2E701F094FA71 +:10CF1000089B0360EFE700BFA0010020281B010869 +:10CF2000301B010800F0B6B970B58AB0054600F0B4 +:10CF3000B5FB224C064694F90030013308D0284650 +:10CF400001F0DAF920B128460021F3F7D1FF10B93A +:10CF500030460AB070BD1A490122002328460191CB +:10CF600000920893F3F762FA2478CDE90401CDE941 +:10CF700002017CB900220023CDE90623684601F0B6 +:10CF800053F888B1089BA3B9DDE90601F3F7B4FCB7 +:10CF90000AB070BD0020002102460B46F3F7C4FB27 +:10CFA000022CCDE90601E9D101F046FA2123036004 +:10CFB000E8E701F041FA089B0360E5E7A0010020E3 +:10CFC000341B0108F8B520F00043B3F17E5F04463E +:10CFD00010D008DCB3F17C5F11DAB3F10C5F00F321 +:10CFE00084809D48F8BD0146F3F7DAFC0146F3F76B +:10CFF00095FEF8BD002840F3CD800020F8BD002844 +:10D00000C0F2CA8001464FF07E50F3F7C9FC4FF0E2 +:10D010007C51F3F7CFFD044600F040FB8F490646F4 +:10D020002046F3F7C7FD8E49F3F7BCFC2146F3F722 +:10D03000C1FD8C49F3F7B4FC2146F3F7BBFD8A49E7 +:10D04000F3F7B0FC2146F3F7B5FD8849F3F7A8FCE8 +:10D050002146F3F7AFFD8649F3F7A4FC2146F3F729 +:10D06000A9FD844905462046F3F7A4FD8249F3F75C +:10D0700097FC2146F3F79EFD8049F3F793FC214688 +:10D08000F3F798FD7E49F3F78BFC2146F3F792FD09 +:10D090004FF07E51F3F786FC01462846F3F73EFE3B +:10D0A0003146F3F787FD26F47F6525F00F05074627 +:10D0B00029462846F3F77EFD01462046F3F770FC2B +:10D0C000294604463046F3F76DFC01462046F3F747 +:10D0D00025FE01463846F3F765FC01462846F3F77E +:10D0E00061FC0146F3F75EFCF8BD0146F3F762FD13 +:10D0F0005A490546F3F75EFD5949F3F753FC2946B3 +:10D10000F3F758FD5749F3F74BFC2946F3F752FD67 +:10D110005549F3F747FC2946F3F74CFD5349F3F71C +:10D120003FFC2946F3F746FD5149F3F73BFC2946FE +:10D13000F3F740FD4F4906462846F3F73BFD4E49BD +:10D14000F3F72EFC2946F3F735FD4C49F3F72AFC9B +:10D150002946F3F72FFD4A49F3F722FC2946F3F756 +:10D1600029FD4FF07E51F3F71DFC01463046F3F7E1 +:10D17000D5FD01462046F3F71DFD01464148F3F772 +:10D180000FFC01462046F3F70BFC01463E48F3F73F +:10D1900007FCF8BD3D48F8BD4FF07E51F3F702FCA7 +:10D1A0004FF07C51F3F706FD2C490446F3F702FDDE +:10D1B0002B49F3F7F7FB2146F3F7FCFC2949F3F77A +:10D1C000EFFB2146F3F7F6FC2749F3F7EBFB21468B +:10D1D000F3F7F0FC2549F3F7E3FB2146F3F7EAFC0C +:10D1E0002349F3F7DFFB2146F3F7E4FC064620462C +:10D1F00000F054FA1F4905462046F3F7DBFC1E49B0 +:10D20000F3F7CEFB2146F3F7D5FC1C49F3F7CAFB35 +:10D210002146F3F7CFFC1A49F3F7C2FB2146F3F797 +:10D22000C9FC4FF07E51F3F7BDFB01463046F3F7E2 +:10D2300075FD2946F3F7BEFC1249F3F7B1FB014631 +:10D240002846F3F7AFFB0146F3F7ACFB0146104865 +:10D25000F3F7A6FBF8BD00BFDB0FC93F08EF11389D +:10D26000047F4F3A4611243DA80A4E3E90B0A63E98 +:10D27000ABAA2A3E2EC69D3D6133303F2D5701405B +:10D2800039D119406821A233DA0FC93FDB0F494079 +:10D29000DA0F494021F00042B2F1FF4FF8B50446E1 +:10D2A00014DC20F00045B5F1FF4F06460EDCB1F16D +:10D2B0007E5F3AD08F1707F0020747EAD07755B95B +:10D2C000022F2FD0032F2FD13148F8BD0846214619 +:10D2D000F3F768FBF8BDFAB1B2F1FF4F29D0B5F111 +:10D2E000FF4F19D0AA1AD2153C2A19DC002938DBC5 +:10D2F0002046F3F713FD00F0B5FF00F09DFE012F6F +:10D300002CD0022F22D0002F2FD02249F3F74AFB36 +:10D310002149F3F745FBF8BD002E15DB1F48F8BD8A +:10D320001E48ECE71C48F8BDF8BDBDE8F84000F029 +:10D3300083BEB5F1FF4F19D0022FF3D0032FC3D016 +:10D34000012F1BD00020F8BD1548F8BD1149F3F797 +:10D3500029FB01461048F3F723FBF8BD00F100401C +:10D36000F8BD3C32C4DA0020C9E7F8BD022F0CD06A +:10D37000032F08D0012F04D00A48F8BD4FF0004019 +:10D38000F8BD0948F8BD0948F8BD0948F8BD00BF17 +:10D39000DB0F49C02EBDBB33DB0F4940DB0FC93F5C +:10D3A000DB0FC9BFDB0F493FDB0F49BFE4CB16C022 +:10D3B000E4CB16402DE9F04FAB4A20F000449442F4 +:10D3C00089B006460D4664DDA84A94421CDC00285C +:10D3D000A74940F3EC80F3F7E3FAA64B24F00F04DF +:10D3E0009C42064664D0A449F3F7DAFA0146286065 +:10D3F0003046F3F7D5FAA049F3F7D2FA0123686073 +:10D40000184609B0BDE8F08F9C4A944262DDB4F141 +:10D41000FF4F46DAE715863FA4EBC7542046F3F7E3 +:10D420008FFDF3F773FB0346014620460593F3F7A0 +:10D43000B7FA4FF08741F3F7BDFB8046F3F780FD65 +:10D44000F3F764FB0146044640460694F3F7A8FA56 +:10D450004FF08741F3F7AEFB00210790F3F73EFD55 +:10D46000002800F0C58020460021F3F737FD002892 +:10D4700014BF0123022382480221019000913A4601 +:10D4800005A8294600F022FA002EC0F2A780034624 +:10D4900003E00022286000234A60184609B0BDE876 +:10D4A000F08F0146F3F77CFA002368602860F4E708 +:10D4B0007449F3F775FA74490446F3F771FA0146B3 +:10D4C00028602046F3F76CFA6F49F3F769FA0123F5 +:10D4D0006860E2E700F0C6FE6C490746F3F76AFBB6 +:10D4E0004FF07C51F3F75EFAF3F72AFD8246F3F72B +:10D4F0000DFB5F498346F3F75DFB01463846F3F7C2 +:10D500004FFA5D4980465846F3F754FBBAF11F0FB6 +:10D5100081464946404618DC5D4B0AF1FF3253F81C +:10D52000223024F0FF029A420FD0F3F739FA07466F +:10D530002F6039464046F3F733FA4946F3F730FA9D +:10D54000002E686056DB5346A7E7F3F729FAE31588 +:10D55000C0F3C7529A1A082A0746E9DD49495846D6 +:10D560000393F3F727FB074639464046F3F718FACB +:10D57000044621464046F3F713FA3946F3F710FA0A +:10D58000414907465846F3F715FB3946F3F708FAC1 +:10D59000814649462046F3F703FA039BC0F3C7527E +:10D5A0009B1A192B074641DC2860A046C1E7F3F718 +:10D5B000F9F9304B24F00F049C42064623D02E4943 +:10D5C000F3F7F0F9014628603046F3F7E9F92A4904 +:10D5D000F3F7E8F94FF0FF3368605EE795E80C0079 +:10D5E00003F1004102F1004243422A60696054E7BE +:10D5F000032340E707F1004700F100402F60686017 +:10D60000CAF1000349E71F49F3F7CCF91E49044664 +:10D61000F3F7C8F9014628602046F3F7C1F91A4923 +:10D62000F3F7C0F94FF0FF33686036E71949584601 +:10D63000F3F7C0FA074639462046F3F7B1F98046BA +:10D6400041462046F3F7ACF93946F3F7A9F91249F8 +:10D6500004465846F3F7AEFA2146F3F7A1F981469E +:10D660004946404661E700BFD80F493FE3CB16402B +:10D67000800FC93FD00FC93F43443537800F49431E +:10D68000BC1B01080044353708A3852E84F9223FCE +:10D690003C1B010800A3852E32318D2420F000426E +:10D6A000B2F1FF4FF8B5044603462DD25AB3002815 +:10D6B0003DDBB2F5000F4FEAE0502CD37F38C3F3C7 +:10D6C0001603C20743F4000348BF5B000027401065 +:10D6D0005B003E4619244FF08072B5189D4202DC73 +:10D6E0005B1BAE181744013C4FEA43034FEA52025A +:10D6F000F3D113B107F001031F447F1007F17C57EA +:10D7000007EBC050F8BDF8BD0146F3F753FA2146C8 +:10D71000F3F748F9F8BD14F400020FD15B001902C9 +:10D7200002F10102FAD5C2F101021044C6E7014636 +:10D73000F3F736F90146F3F7F1FAF8BD0122104488 +:10D74000BCE700BF2DE9F84320F00046B6F1485F82 +:10D7500005460F4649DAF3F7F3FB002800F09D80F9 +:10D7600029462846F3F726FA4E490446F3F722FAEB +:10D770004D49F3F717F92146F3F71CFA4B49F3F734 +:10D780000FF92146F3F716FA4949F3F70BF9214649 +:10D79000F3F710FA4749F3F703F92146F3F70AFACA +:10D7A0004549F3F7FFF82146F3F704FA804620468F +:10D7B0004FF07C51F3F7FEF9414606462046F3F759 +:10D7C000F9F9394604462846F3F7F4F901462046AC +:10D7D000F3F7E6F801463046F3F7E2F801464FF07A +:10D7E0007E50F3F7DDF8BDE8F8830146F3F7E2F980 +:10D7F0002C490446F3F7DEF92B49F3F7D3F8214619 +:10D80000F3F7D8F92949F3F7CBF82146F3F7D2F922 +:10D810002749F3F7C7F82146F3F7CCF92549F3F781 +:10D82000BFF82146F3F7C6F92349F3F7BBF82146C1 +:10D83000F3F7C0F9214B80469E42B8DD204B9E4253 +:10D8400027DC06F17F4631464FF07E50F3F7A8F80B +:10D85000814620464FF07C51F3F7ACF93146F3F79F +:10D860009FF8414606462046F3F7A4F93946044698 +:10D870002846F3F79FF901462046F3F791F8014651 +:10D880003046F3F78DF801464846F3F789F8BDE8CE +:10D89000F883DFF834900B4EDBE74FF07E50BDE8A5 +:10D8A000F88300BF4ED747ADF6740F317CF2933446 +:10D8B000010DD037610BB63AABAA2A3D9999993E32 +:10D8C0000000483F0000903E0000383F2DE9F04F37 +:10D8D000DFB00B93013B0293D31E48BF131DB84C1E +:10D8E00006466898DB1054F8204023EAE3730C9353 +:10D8F000DB4302EBC30308940693089C029B0C9A3B +:10D900001D190991C3EB02071DD4699C3D4404EB2A +:10D91000870901354FF0000822AC0AE059F80800E9 +:10D92000F3F7F4F80137AF4244F8080008F10408AF +:10D9300009D0002FF2DA01370020AF4244F8080086 +:10D9400008F10408F5D1089A002AC0F2DF82089A8B +:10D950000B9B02F101089C0022AF4FEA8808274484 +:10D960000025029A002AC0F2F28105EB070B4FF066 +:10D9700000094FF0000A56F809005BF8041DF3F7A0 +:10D9800019F901465046F3F70DF809F10409A145CC +:10D990008246F0D14AA840F805A004354545E0D1BB +:10D9A000089A0EAB03EB82030D9391464FEA89036D +:10D9B0000793079A5EAB1344B9F1000F53F850ACCC +:10D9C00023DD0DF134084AAF174490440DAD4FF0FC +:10D9D0006E515046F3F7EEF8F3F7B2FAF3F796F814 +:10D9E0004FF087418346F3F7E5F801465046F2F7DA +:10D9F000D7FFF3F7A5FA594645F8040F57F8040D79 +:10DA0000F2F7D0FF45458246E1D15046069900F035 +:10DA10008DFC4FF078510546F3F7CCF800F026FC6A +:10DA20004FF08241F3F7C6F801462846F2F7B8FFF7 +:10DA30000546F3F785FA8246F3F768F8014628466B +:10DA4000F2F7AEFF069A8046002A40F3678109F19B +:10DA5000FF310EA850F82130C2F1080043FA00F25D +:10DA600002FA00F01B1A06989244C0F1070743FA25 +:10DA700007F70EA840F82130002F32DDB9F1000F72 +:10DA80000AF1010A40F375810EAB079A1946114459 +:10DA9000002507E0C2F5807012B143F8040C01259F +:10DAA0008B420BD053F8042B002DF3D0C2F1FF02B0 +:10DAB0008B4243F8042C4FF00105F3D1069B002B59 +:10DAC0000DDD012B00F03281022B08D109F1FF336B +:10DAD0000EA951F8232002F03F0241F82320022F23 +:10DAE00070D040460021F3F7F9F9002800F0838058 +:10DAF000089A09F1FF35AA420DDC079A0EAB0D9882 +:10DB00001344002253F8041D834242EA0102F9D172 +:10DB1000002A40F0E481089B0EA85A1E50F82230DB +:10DB2000002B40F0F18100EB8202012352F8041D2A +:10DB300001330029FAD04B4499450A933DDADDF8C8 +:10DB40002CA022AACA44DDF8308002EB8A02C84425 +:10DB5000C9EB0309131D03920593699A079B4FEACA +:10DB600089094AAF02EB8808CDF810901F440025C0 +:10DB700058F8040FF2F7CAFF029B039A002B50518A +:10DB80004FF0000B13DBDDF814A04FF00009AA449E +:10DB900056F809005AF8041DF3F70CF801465846E8 +:10DBA000F2F700FF09F10409A1458346F0D1049A78 +:10DBB0000435954247F804BFDAD1DDF82890F5E640 +:10DBC000D41E010841464FF07E50F2F7E9FE804630 +:10DBD000002D86D006994FF07E5000F0A7FB01463D +:10DBE0004046F2F7DDFE804640460021F3F776F925 +:10DBF00000287FF47DAF069B40465942CDF808A02F +:10DC000000F094FB4FF087410446F3F785F90028B4 +:10DC100000F07F814FF06E512046F2F7CBFFF3F713 +:10DC20008FF9F2F773FF4FF087410546F2F7C2FF15 +:10DC300001462046F2F7B4FEF3F782F90EAB43F843 +:10DC400029002846F3F77CF9069C09F10105083400 +:10DC50000EA9069441F8250006994FF07E5000F079 +:10DC600065FB002D04464FDB6E1C4FEA8508C6EBB2 +:10DC7000867A0DF138094AABC1444FEA8A0A9844C2 +:10DC80004FF0000B59F80B00F2F740FF2146F2F776 +:10DC900091FF4FF06E5148F80B002046F2F78AFFD3 +:10DCA000ABF1040BD3450446ECD1DFF88C92DDF8E0 +:10DCB00020A00024B34603950497BAF1000FB8BF23 +:10DCC000002515DB00263746002501E0A7420FDCC2 +:10DCD00058F8061059F80600F2F76CFF014628467E +:10DCE000F2F760FE0137BA45054606F10406EDDAA3 +:10DCF0005EA800EB84030134A345A8F1040843F8AF +:10DD0000A05CDAD1039D049F689C032C00F29880EC +:10DD1000DFE814F0CB009C009C00310010D109F129 +:10DD2000FF330EA951F823703F12A5E609F1FF3326 +:10DD30000EA850F8232002F07F0240F82320CEE600 +:10DD40004FF07C51F3F7E8F858B90746C9E64FF0B1 +:10DD5000000A4AA840F805A0043545457FF401AE05 +:10DD60001EE6B9F1000F4FF002070AF1010A3FF772 +:10DD70008BAE0025A2E6002D40F3DC804FEA850B38 +:10DD80005EAB36AE05F1FF3A5B4406EB8A0A53F808 +:10DD9000A08C54465B4635AABB462F4600E0C846D9 +:10DDA00054F804594146284601920093F2F7FAFDCF +:10DDB000814649462846F2F7F3FD4146F2F7F2FD67 +:10DDC000019AC4F804909442A060009BE7D13D46BC +:10DDD000012D5F469B4640F3AD805EAB9B445BF8F4 +:10DDE000A04C00E044465AF8049921464846F2F710 +:10DDF000D9FD804641464846F2F7D2FD2146F2F76A +:10DE0000D1FD5645CAF80480CAF80800EAD16C1C56 +:10DE100006EB84040020083654F8041DF2F7C2FD16 +:10DE2000B442F9D1002F7ED0369A379B099C00F17D +:10DE3000004002F1004203F10043A06022606360F1 +:10DE4000029A02F007005FB0BDE8F08F002DB8BF66 +:10DE500000200ADB36AE6C1C002006EB840454F86C +:10DE6000041DF2F79FFDB442F9D1002F35D000F127 +:10DE70000043099C014623603698F2F791FD002D7E +:10DE800008DD36AC04EB850554F8041FF2F78AFD73 +:10DE9000AC42F9D10FB100F10040099A5060029AEA +:10DEA00002F007005FB0BDE8F08F002D39DB6C1C7D +:10DEB00036AE002006EB840454F8041DF2F772FD20 +:10DEC000B442F9D10FB100F10040099A1060029AF2 +:10DED00002F007005FB0BDE8F08F0346C9E7069A7D +:10DEE0000EAC54F82530083ACDF808A00692002B65 +:10DEF0007FF4B2AE04EB850353F8041D013D083AEC +:10DF00000029F9D00692A7E6012314E60B9B9C009A +:10DF100046E52046F3F714F80EAA4D4642F82900CC +:10DF20009AE60020CEE7099C369A379BA0602260D3 +:10DF3000636085E7002075E7E01E01082DE9F843DE +:10DF400020F00043B3F1485F04460F46904603DAE1 +:10DF5000F2F7F6FF002857D021462046F2F72AFEB6 +:10DF600021460546F2F726FE294906462846F2F7DD +:10DF700021FE2849F2F714FD2946F2F71BFE264937 +:10DF8000F2F710FD2946F2F715FE2449F2F708FDD5 +:10DF90002946F2F70FFE2249F2F704FD8146B8F157 +:10DFA000000F22D038464FF07C51F2F703FE49466D +:10DFB00080463046F2F7FEFD01464046F2F7F0FC9F +:10DFC0002946F2F7F7FD3946F2F7EAFC154905460E +:10DFD0003046F2F7EFFD01462846F2F7E3FC014632 +:10DFE0002046F2F7DDFCBDE8F88349462846F2F703 +:10DFF000E1FD0C49F2F7D4FC3146F2F7DBFD214696 +:10E00000F2F7D0FCBDE8F8832046BDE8F88300BFF6 +:10E01000D3C92E2F342FD7321BEF3836010D50398C +:10E020008988083CABAA2A3E00207047002001499D +:10E03000704700BF0000F87F2DE9F04120F0004557 +:10E04000B5F1A14F0446064608DBB5F1FF4F6FDC82 +:10E05000002840F3A0806F48BDE8F0816E4B9D42E0 +:10E0600077DCB5F1445F68DB4FF0FF37214620468F +:10E07000F2F7A0FD01468046F2F79CFD6749054690 +:10E08000F2F798FD6649F2F78DFC2946F2F792FD0A +:10E090006449F2F787FC2946F2F78CFD6249F2F7F2 +:10E0A00081FC2946F2F786FD6049F2F77BFC2946A0 +:10E0B000F2F780FD5E49F2F775FC4146F2F77AFD12 +:10E0C0005C4980462846F2F775FD5B49F2F768FC2B +:10E0D0002946F2F76FFD5949F2F762FC2946F2F73B +:10E0E00069FD5749F2F75CFC2946F2F763FD554993 +:10E0F000F2F756FC2946F2F75DFD7B1C01464046CF +:10E100004CD0F2F74FFC2146F2F754FD4E4B4F4DE9 +:10E1100053F82710F2F744FC2146F2F741FC014680 +:10E1200055F82700F2F73CFC002E30DBBDE8F0810B +:10E130000146F2F737FCBDE8F0814549F2F732FCC1 +:10E140004FF07E51F2F7F2FE00288DD02046BDE858 +:10E15000F08100F087F83F4B04469D4229DCA3F58F +:10E16000D0039D4244DC0146F2F71CFC4FF07E5187 +:10E17000F2F716FC4FF0804105462046F2F712FCFC +:10E1800001462846F2F7CAFD002704466EE700F173 +:10E190000040BDE8F0813048BDE8F081F2F702FCB4 +:10E1A0002146F2F707FD01462046F2F7F9FBBDE8EC +:10E1B000F0812A4B9D4214DC4FF07F51F2F7F0FBC7 +:10E1C0004FF07F5105462046F2F7F4FC4FF07E51A8 +:10E1D000F2F7E8FB01462846F2F7A0FD02270446C5 +:10E1E00044E701461E48F2F799FD032704463DE740 +:10E1F0004FF07E51F2F7D4FB4FF07E51054620469A +:10E20000F2F7D0FB01462846F2F788FD01270446C5 +:10E210002CE700BFDB0FC93FFFFFDF3ED769853C1E +:10E2200059DA4B3D356B883D6E2EBA3D2549123E7D +:10E23000ABAAAA3E21A215BD6BF16E3D95879D3D0F +:10E24000388EE33DCDCC4C3E0C1F01081C1F01084D +:10E25000CAF24971FFFF973FDB0FC9BFFFFF1B40A9 +:10E26000000080BF20F00040704700BF2DE9F04162 +:10E2700020F00047FD0D7F3D162D064613DC002DD6 +:10E2800080461BDB194F2F41074214D01849F2F783 +:10E2900089FB0021F2F74AFE68B1002E1BDB28EA59 +:10E2A0000700BDE8F081B7F1FF4F04D30146F2F754 +:10E2B00079FBBDE8F0813046BDE8F0810C49F2F70A +:10E2C00071FB0021F2F732FE0028F4D0002E08DBAB +:10E2D0000020BDE8F0814FF4000343FA05F5A8449F +:10E2E000DDE7002FE7D00348BDE8F081FFFF7F00A6 +:10E2F000CAF24971000080BF30F0004001D1022015 +:10E300007047A0F50003B3F1FE4F01D2042070471F +:10E31000054B421E9A4201D803207047B0F1FF43DB +:10E3200058425841704700BFFEFF7F0038B530F0BB +:10E330000044024603460D4614D0B4F1FF4F0DD2FF +:10E34000B4F5000F0FD3E40D2C44FE2C2EDC002C72 +:10E350001DDD23F0FF4343EAC45038BD0146F2F708 +:10E3600021FB38BD38BD4FF09841F2F723FC194B23 +:10E3700002469D4207DBC0F3C7540346193CE3E75E +:10E38000154800F02DF81449F2F714FC38BD14F1CB +:10E39000160F13DA4CF250339D421146F0DD0F4850 +:10E3A00000F01EF80D49F2F705FC38BD11460B4888 +:10E3B00000F016F80949F2F7FDFB38BD04F1190029 +:10E3C00023F0FF4343EAC0504FF04C51F2F7F2FB09 +:10E3D00038BD00BFB03CFFFF6042A20DCAF24971D8 +:10E3E00001F0004120F000400843704700210A225C +:10E3F00000F0E8BF2DE9F84FDDF828B01646814659 +:10E400008A46984692B18BB1002503E011D0651C75 +:10E41000AE420BD97419640808FB04A74846394674 +:10E42000D8470028F2DA2646AE42F3D80020BDE8ED +:10E43000F88F3846BDE8F88F014B1868704700BF69 +:10E44000D005002070B50F4E0F4D761BB61007D0CB +:10E45000043D0024013455F8043F9847A642F9D101 +:10E460000A4E0B4D03F0E8FD761BB61008D0043DB4 +:10E470000024013455F8043F9847A642F9D170BDF5 +:10E4800070BD00BF5020010850200108582001082D +:10E4900050200108F0B4840743D0541E002A3ED017 +:10E4A000CDB2034603E0621E002C38D0144603F8B8 +:10E4B000015B9A07F7D1032C2AD9CDB245EA05258D +:10E4C0000F2C45EA054515D9A4F110073F0903F1C2 +:10E4D000100606EB07161A46156055609560D56064 +:10E4E0001032B242F8D104F00F040137032C03EBD1 +:10E4F00007130DD91E462246043A032A46F8045B48 +:10E50000FAD8221F22F003020432134404F0030459 +:10E510002CB1C9B21C4403F8011BA342FBD1F0BCCF +:10E52000704714460346C6E72DE9F04F87B00092C6 +:10E53000044602EB42020098520005928008A207AE +:10E5400001911D46029040F0838000998B077FD196 +:10E55000019AB1F1040918BF4FF00109062A7CD9CC +:10E56000019A00985308072A00FB034B40F00281F0 +:10E57000059E2644B9F1000F40F01B812168DBF8AD +:10E5800000202260CBF80010009B009823444FF03D +:10E59000000AD34604931F460393C0F10008B24615 +:10E5A000B74240F296805346DA469B46BAF1000FD6 +:10E5B00000F0D381039A9DE8090000FB0343B91AD8 +:10E5C000C4EB020C8C45A8BF8C46BCF1000F019334 +:10E5D00011DDB9F1020FCCEB070040F0448104EBF0 +:10E5E0000C0A224690F800C0137802F801CB52457D +:10E5F00000F8013BF6D1019B0098CBEB0302C6EB80 +:10E600000B06121AB24228BF3246002A10DD0198CA +:10E61000B9F1020FC2EB000340F0428107EB020C9C +:10E6200018783A7807F8010B674503F8012BF7D102 +:10E63000009A8A42C0F0CE80009CB44246D2019833 +:10E640000099841BA207B6FBF1F601963FF47DAF5B +:10E65000019A4FF00209062A82D8009B03FB024B65 +:10E660009846A044D84531D25F42DDF800A0234649 +:10E67000CDF804B04C469946C14523D2464608E041 +:10E680003268DBF800303360CBF80020CB4519D975 +:10E690005E4606EB070B58463146A847002811DDB9 +:10E6A000002CEDD0012C00F0A18152465B46317860 +:10E6B0001878013A002A06F8010B03F8011BF6DC72 +:10E6C000CB45E5D8019AD0449045D5D307B0BDE8F5 +:10E6D000F08F38462146A84700280DDC36E0326826 +:10E6E000DAF800303360CAF80020C2444FF0010B62 +:10E6F0004644B7423FF657AF30462146A847002868 +:10E70000C0F29081F4D1B9F1000FE8D0B9F1010F56 +:10E710000DD0009952463346187892F800C001395E +:10E72000002903F801CB02F8010BF5DCDDE7029BC1 +:10E7300050463146A4460C680268013B002B41F864 +:10E74000042B40F8044BF6DC6446CEE70FD1B9F158 +:10E75000000F40F0B280039B03981A683B68036087 +:10E760003A60039A009B4FF0010B1A440392009801 +:10E77000074415E7019A009B561E282A03FB06460C +:10E7800031D8B046274659463846A8470028414662 +:10E79000584679DBA84700283FF7ECAE384641469B +:10E7A000A84738EA200B28BFBB46B9F1000F3FF459 +:10E7B000E5AEB9F1010F00F09180009A5946234669 +:10E7C00018780F78013A002A03F8017B01F8010B51 +:10E7D000F6DCD9E62046009C2B46B1FBF4F122463C +:10E7E000FFF7A2FE28E74FEAD20803FB08F804EB84 +:10E7F00008074FEA48023946204692460392A84746 +:10E80000A244002851463846C0F29B80A847002801 +:10E8100040F30081C8F100039A46DA445946504655 +:10E820000493A847D8440028414658467EDBA847B1 +:10E83000002840F3E780039ADDF81080C2EB060A57 +:10E84000B04441465046A84700283146404652DB76 +:10E85000A847002897DC50463146A84736EA2008EA +:10E8600028BFD0468FE74FEA9C0C224688461168A5 +:10E8700003680CF1FF3CBCF1000F42F8043B40F888 +:10E88000041BF4DC4146B6E6A8470028FFF672AE4A +:10E8900038464146A84737EA200B28BFC34669E6F9 +:10E8A00092088C4639681868013A002A47F8040B28 +:10E8B00043F8041BF6DC6146BAE6B9F1010F26D035 +:10E8C0000099039B3A46187892F800C00139002954 +:10E8D00003F801CB02F8010BF5DC42E7029A5B4634 +:10E8E00021460F681868013A002A41F8040B43F8E2 +:10E8F000047BF6DC48E6A8470028FFF644AF504604 +:10E900003146A8473AEA200828BFB0463BE70399BA +:10E91000029B3846A4460C680268013B002B41F874 +:10E92000042B40F8044BF6DC64461AE7A84700289D +:10E9300081DB50464146A8473AEA200B28BFC34630 +:10E9400079E7A8470028FFF665AF20465146A8475B +:10E9500034EA200728BF57465CE7019A009B03FB77 +:10E960000248049A4245BFF4B1AE5F42DDF800B000 +:10E97000234692464C46CDF804809946D14522D292 +:10E98000564608E03268D8F800303360C8F80020F6 +:10E99000C84518D9464606EB070840463146A84701 +:10E9A000002810DD002CEDD0012C13D05A46434630 +:10E9B00031781878013A002A06F8010B03F8011B98 +:10E9C000F6DCC845E6D8019BDA449A45D6D307B0B1 +:10E9D000BDE8F08F029B414630680A68013B002B7E +:10E9E00046F8042B41F8040BF6DCD1E7029B5946AC +:10E9F00030680A68013B002B46F8042B41F8040BF1 +:10EA0000F6DC43E650464146A84738EA200B28BFCB +:10EA1000D34610E720465146A8473AEA200728BFC8 +:10EA20002746F7E6B7423FF6BEADB9F1000F09D170 +:10EA30003A6833683B60326000994FF0010B0F4435 +:10EA4000761AADE5B9F1010F0DD0009932463B467B +:10EA5000187892F800C00139002903F801CB02F8B8 +:10EA6000010BF5DCE8E7029B30463946A4460C680A +:10EA70000268013B002B41F8042B40F8044BF6DC04 +:10EA80006446D9E7830770B506461FD10368A3F132 +:10EA9000013222EA030313F0803F08BF031D15D1A2 +:10EAA000184653F8044BA4F1013525EA040414F088 +:10EAB000803FF5D003782BB1431C1C7818460133F6 +:10EAC000002CFAD100F07EF8304670BD3046F1E7F8 +:10EAD000C9B2F0B4002947D085070FD00278002AC8 +:10EAE0003FD091423ED0431C05E013F8012B002A91 +:10EAF00037D0914236D09A071846F6D1036841EADA +:10EB0000012747EA074783EA0702A2F10135A3F18B +:10EB1000013425EA020224EA0303134313F0803F81 +:10EB200011D1021D104652F8043B83EA0704A4F1F8 +:10EB30000136A3F1013526EA040425EA0303234341 +:10EB400013F0803FEED00378002B39D0994209D0E2 +:10EB5000431C01E0914205D0184613F8012B002A0E +:10EB6000F8D11046F0BC704784070BD00378002B17 +:10EB7000F8D0431C03E002780133002AF2D0990751 +:10EB80001846F8D10368A3F1013222EA030313F017 +:10EB9000803F0AD1031D184653F8042BA2F101311E +:10EBA00021EA020212F0803FF5D00378002BD9D081 +:10EBB000431C1A7818460133002AFAD1F0BC70477A +:10EBC0001846CFE780EA0102844612F0030F4FD1C6 +:10EBD00011F0030F32D14DF8044D11F0040F51F82C +:10EBE000043B0BD0A3F101329A4312F0803F04BFE3 +:10EBF0004CF8043B51F8043B16D100BF51F8044BCC +:10EC0000A3F101329A4312F0803FA4F101320BD1FB +:10EC10004CF8043BA24312F0803F04BF51F8043B80 +:10EC20004CF8044BEAD023460CF8013B13F0FF0FDD +:10EC30004FEA3323F8D15DF8044B704711F0010F10 +:10EC400006D011F8012B0CF8012B002A08BF7047E1 +:10EC500011F0020FBFD031F8022B12F0FF0F16BFD8 +:10EC60002CF8022B8CF8002012F47F4FB3D17047A0 +:10EC700011F8012B0CF8012B002AF9D1704700BFC5 +:10EC800020F0030110F00300C0F1000051F8043B34 +:10EC900000F1040C4FEACC0C6FF000021CBF22FA0A +:10ECA0000CF213434FF0010C4CEA0C2C4CEA0C4CC8 +:10ECB000A3EB0C0222EA030212EACC1204BF51F8C1 +:10ECC000043B0430F4D013F0FF0F1FBF013013F4E6 +:10ECD0007F4F013013F47F0F18BF0130704700BF22 +:10ECE000F0B40646FAB1114B1F6804E0E81A18D1D7 +:10ECF000BBB1013A17D016F8014B3B195B7825469A +:10ED000003F00303012B11F8013B08BF04F12005B8 +:10ED1000F818407800F003000128E7D12033E81A02 +:10ED2000E7D0F0BC70471046F0BC7047A40100204B +:10ED300040EA01039B0770B42AD1032A28D90C4664 +:10ED40000346214654F8045BA5F1013626EA050680 +:10ED500016F0803F05D1043A032A43F8045B2146AC +:10ED6000EFD89AB10C78013A1C7001333CB16AB10A +:10ED700011F8014F013A03F8014B002CF7D12AB1E9 +:10ED80001A44002103F8011B9342FBD170BC704769 +:10ED90000346E6E74FF0010C2DE9F0036446002539 +:10EDA0004FF0FF3663198B4200EB06070DD23F5D33 +:10EDB00010F80380B8452ED21D460124C6EB030C83 +:10EDC00063198B4200EB0607F1D34FF00109C2F83B +:10EDD00000C04C4600254FF0FF376319994200EB05 +:10EDE000070C0ED91CF804C010F80380E04519D9AF +:10EDF0001D460124C7EB03096319994200EB070C78 +:10EE0000F0D8701C0137874224BF3846C2F8009002 +:10EE1000BDE8F00370470CD04FF0010C2E4664465D +:10EE20006544BFE709D04FF001092F464C464D44D9 +:10EE3000D3E7644505D00134B4E74C4504D0013430 +:10EE4000CBE71D460124ADE71D460124C5E700BF01 +:10EE50002DE9F04FADF21C4D164607460D46104603 +:10EE6000194605AA1C46FFF795FF05AB80460DF233 +:10EE7000144243F8044F9342FBD15CB104F1FF3ECE +:10EE8000002306A8F25CC3EB0E010133A34240F855 +:10EE90002210F7D1059930463144424600F010FB6C +:10EEA000002879D108F1FF3C0346CDF808C0B444EE +:10EEB0008246CDF804802846CDF80CC01D46A046F9 +:10EEC00008E025B1059A934238BFC2EB08039A4483 +:10EED000002520460AEB0804221A0021384400F0DD +:10EEE000A5FA002853D1002C51D03B1913F8012C5E +:10EEF00006AB53F82230002BE3D1019A08F1FF3919 +:10EF0000954228BF2A464A4511D207EB0A03985C6E +:10EF100016F802C0B118844506D031E011F8010F8F +:10EF200013F802C084452BD101324A45F6D3019B28 +:10EF300002989D4228BF18461AD2DDF808C007EB98 +:10EF40000A0313F80C20DDF80CC09CF80010914265 +:10EF50006ED1624606EB050B06E012F8019D13F830 +:10EF600001C0E14504D108465A4500F1FF31F4D112 +:10EF7000013585425ED8059DAA44C5EB0805A8E782 +:10EF800001990025C1F101039A449244A1E70020B0 +:10EF90000DF21C4DBDE8F08FC8EB0403434538BFAC +:10EFA00043460133284605934FF0000A06EB080953 +:10EFB0004546A3460AEB0B04221A0021384400F010 +:10EFC00035FA0028E3D1002CE1D03B1913F8012CCD +:10EFD00006AB53F822301BBB0BF1FF38454507EB5E +:10EFE0000A0012D2435D99F800209A4218BF2B46BE +:10EFF00019D14A462B4605E012F8011F10F803C04C +:10F000008C4510D101334345F6D36B1E1DB9BFE7C4 +:10F0100013F1FF33BCD3F15CC25C9142F8D0059B85 +:10F020009A442046C6E7C5F1010292449A44F8E7A3 +:10F0300001989DE707EB0A00AAE700BF2DE9F04F12 +:10F04000037887B082460E46002B00F0EE800A78E7 +:10F050009AB107460131012502E011F8012B5AB19E +:10F06000934214BF002505F0010517F8013F0C4637 +:10F07000002BF2D1237823B93DB1504607B0BDE84B +:10F08000F08F002007B0BDE8F08F0AF10100317861 +:10F09000FFF71EFDA41B80460028F2D0012CEDD006 +:10F0A000A244504594BFC0EB0A0501251F2C07D987 +:10F0B000294632462346FFF7CBFE07B0BDE8F08F66 +:10F0C000214605AA3046FFF765FE059981460246AE +:10F0D0003144304600F0F4F900285BD1034609F1D1 +:10F0E000FF30029030440390CDF804909A462846B1 +:10F0F00099460AEB04073A1A0021404400F096F9B9 +:10F100000028BED1002FBCD0019B994528BF4B469B +:10F110009C4212D908EB030212F80A10F05CF218B4 +:10F1200088422FD108EB0A0504E012F8011FE85CC1 +:10F13000884227D101339C42F7D8019B02994B4565 +:10F1400076D9039808EB0A0C1CF8013002789A4231 +:10F150006ED1034606EB090B06E013F8015D1CF8BF +:10F160000200854204D111465B4501F1FF32F4D122 +:10F1700009F1010989455DD8059B9A44C3EB04094F +:10F180003846B6E701994FF00009C1F101029244F7 +:10F190009A44F5E7C9EB04034B4538BF4B460133AE +:10F1A000284605934FF0000B06EB09074D460BEB85 +:10F1B0000409C0EB09020021404400F037F900289F +:10F1C0007FF45FAFB9F1000F3FF45BAFAC4298BF83 +:10F1D00008EB0B0014D908EB050313F80B303A7851 +:10F1E0009A421CD13A462B4608EB0B0005E012F878 +:10F1F000011F10F803C08C4512D101339C42F6D890 +:10F200006B1E25B93AE713F1FF33FFF437AFF15C1A +:10F21000C25C9142F7D0059B9B444846C7E72B460A +:10F22000C5F1010293449B44F7E70C46012521E711 +:10F2300001999DE708EB0A0020E700BF024A01237D +:10F2400012685C3200F002B8D0050020F0B420B3A0 +:10F25000074617F8016B0D4601E0A64216D015F8D7 +:10F26000014B002CF9D1EEB13E4616F8015B0C467D +:10F2700000E073B114F8013BAB42FAD15DB1002359 +:10F280003B70166006463046F0BC704763B13846A6 +:10F29000DEE73746E8E72E46F3E710680028D7D1C7 +:10F2A0000646F0E71660EEE7176006460370EAE7E9 +:10F2B0002DE9F00F424C82B0D4F800C001900E4608 +:10F2C00000E02646344614F8015B0CEB050040785C +:10F2D00000F0080000F0FF0A0028F2D12D2D5BD0CD +:10F2E0002B2D04BF7578B41C33F010003CD0994628 +:10F2F000BAF1000F0CBF6FF0004B4FF0004BBBFB9F +:10F30000F9F8002709FB18BB38460CE0303DAB424A +:10F3100019DD7E1C05D0404523D820D009FB0050C4 +:10F32000012714F8015B0CEB0506767816F0040F44 +:10F33000ECD116F0030606D0012E14BF572637264F +:10F34000AD1BAB42E5DC7B1C15D0BAF1000F21D11F +:10F350000AB1EFB9116002B0BDE8F00F70475D452A +:10F36000DCDD4FF0FF37DCE7302D1AD0002BBED1AB +:10F370000A239946BCE70199BAF1000F4FF0220326 +:10F380000CBF6FF000404FF000400B60002AE2D04D +:10F39000611EDFE74042DBE7B41C75784FF0010ADD +:10F3A000A2E7207800F0DF00582803D0002B9ED180 +:10F3B00008239CE7102365789946023498E700BF3C +:10F3C000A401002030B4044C0D46134601462A46E1 +:10F3D000206830BCFFF76CBFD0050020024B13B192 +:10F3E000024800F005B8704700000000FDF3000877 +:10F3F000014600200246034600F096B838B5094D94 +:10F40000094C641BA41018BF05EB840505D0013C12 +:10F4100055F8043D9847002CF9D1BDE8384002F07A +:10F4200011BE00BF582001085C200108830770B49A +:10F43000C9B240D0541E2AB303788B4223D0431C58 +:10F4400004E0FCB1057814468D421CD013F0030F84 +:10F45000184604F1FF3203F10103F2D1032C14D852 +:10F46000651E54B303788B420DD0421C002302E08A +:10F4700004788C4207D0AB42104603F1010302F13D +:10F480000102F5D1002070BC704741EA0126034615 +:10F4900046EA06461A6818467240A2F1013525EA86 +:10F4A000020212F0803F03F10403D9D1043C032C83 +:10F4B0001846EFD8D4E71446D0E72046E3E700BF6C +:10F4C000032A70B428D940EA01039B0713D00578BA +:10F4D0000C78A54224D1013A002305E010F8015F21 +:10F4E00011F8014FA5421BD1934203F10103F5D15D +:10F4F000002070BC70470C46034625681E682146F4 +:10F50000AE42184604F1040403F1040304D1043AA2 +:10F51000032A18462146F0D8002AD8D11046E8E739 +:10F52000281B70BC704700BFF0B5274C85B026681B +:10F530000746D6F84841002C40D065681F2D1EDDD7 +:10F54000224818B94FF0FF3005B0F0BD4FF4C87035 +:10F55000039102920193AFF3008003990446029A4B +:10F56000019B0028EED0D6F848510020256060604D +:10F570000546C6F84841C4F88801C4F88C013FB973 +:10F580006B1C00200235636044F8251005B0F0BD07 +:10F590000126AE4004EB8500C0F88820D4F888210D +:10F5A000022F42EA0602C4F88821C0F80831E7D1E8 +:10F5B000D4F88C311E43C4F88C61E1E706F5A674DB +:10F5C000C6F84841B9E700BF342001080000000038 +:10F5D0001E1E646464646464000101030804090479 +:10F5E0000A040B040C040D040404050406040704B7 +:10F5F000FFFF00010103080409040A050B050C05BF +:10F600000D050405050506050705FFFF1CF60008A6 +:10F61000D8F500083AF60008F2F5000800020102E9 +:10F62000020203020402050206020702080409049A +:10F630000A040B040C040D04FFFF00020102020285 +:10F6400003020402050206020702080409040A056F +:10F650000B050C050D05FFFF7F230008372300086D +:10F660005323000801250008F9220008F5220008AC +:10F6700075290008B5270008D1270008A927000828 +:10F6800035270008AF2700080000004000080140AF +:10F6900001000000001C002800000040000801409C +:10F6A00002000000041C0028000000400008014087 +:10F6B00004000000081C0028000000400008014071 +:10F6C000080000000C1C0028000400400008014055 +:10F6D00040000000001D0028000400400008014018 +:10F6E00080000000041D002800040040000C0140C0 +:10F6F00001000000081D002800040040000C01402B +:10F70000020000000C1D0028002C014000080140F0 +:10F7100000010000001B0128002C014000080140EE +:10F72000000800000C1B012800080040000C0140EC +:10F7300040000000001E002800080040000C0140AE +:10F7400080000000041E002800080040000C01405A +:10F7500000010000081E002800080040000C0140C5 +:10F76000000200000C1E0028002C01400000004098 +:10F7700000040040000800400000040008000C00E5 +:10F78000D007320032003200320032003200320044 +:10F79000C800640000004145545231323334003017 +:10F7A00031323334353637383941424344454647A0 +:10F7B00048494A4B4C4D4E4F505152535455565751 +:10F7C00058595A00D9400008354100081141000835 +:10F7D0004D4100087541000885410008E5400008DA +:10F7E0003D420008F9400008054100080001000101 +:10F7F0000000803FF704353FF70435BF0000803F2D +:10F800000000803FF70435BFF70435BF0000803F9C +:10F810000000803FF70435BFF704353F0000803F0C +:10F820000000803FF704353FF704353F0000803F7C +:10F830000000803F00000000000080BF000080BF8B +:10F840000000803F000080BF00000000000080BF7B +:10F850000000803F000000000000803F000080BFEB +:10F860000000803F0000803F00000000000080BFDB +:10F870000000803F0000803F000000BF0000803F8C +:10F880000000803F000000BF000080BF0000803FFC +:10F890000000803F000080BF0000003F0000803F6C +:10F8A0000000803F0000003F0000803F0000803FDC +:10F8B0000000803F0000003F000080BF000080BFCC +:10F8C0000000803F000080BF000000BF000080BF3C +:10F8D0000000803F000000BF0000803F000080BFAC +:10F8E0000000803F0000803F0000003F000080BF1C +:10F8F0000000803F000000BFD0B35D3F0000803FAC +:10F900000000803F000000BFD0B35DBF0000803F1B +:10F910000000803F0000003FD0B35D3F000080BF8B +:10F920000000803F0000003FD0B35DBF000080BFFB +:10F930000000803F000080BF00000000000080BF8A +:10F940000000803F0000803F000000000000803F7A +:10F950000000803F000000000000803F0000803F6A +:10F960000000803F000080BF000080BF000000005A +:10F970000000803F000000000000803F000080BFCA +:10F980000000803F0000803F000080BF000000803A +:10F990000000803F0000803F0000000000000000E9 +:10F9A0000000803F000080BF000000000000000059 +:10F9B0000000803F0000000000000000000080BF49 +:10F9C0000000803F00000000000000000000803FB9 +:10F9D000000000000000000003010000E8FC000837 +:10F9E0000400000008FC00080400000068FB000898 +:10F9F0000201000090F90008000100000000000072 +:10FA00000600000088FC000806000000A8FB0008B3 +:10FA100001010000000000000400000048FC000894 +:10FA200006000000F0F8000808000000E8FA0008EE +:10FA300008000000F0F700080800000070F8000857 +:10FA400001010000000000000001000000000000B3 +:10FA500000010000000000000400000050F9000850 +:10FA60000600000088FA0008000100000000000005 +:10FA700002010000B0F900080101000000000000D0 +:10FA800000000000000000000000803F000080BF78 +:10FA90000000803F000080BF0000803F000080BF6A +:10FAA000000080BF0000803F0000803F0000803FDA +:10FAB0000000803F0000803F0000803F0000803F4A +:10FAC000000080BF000080BF0000803F00000000F9 +:10FAD00000000000000000000000803F0000000067 +:10FAE00000000000000000000000803F000080BF18 +:10FAF0000000803F000080BF0000803F000080BF0A +:10FB0000000080BF0000803F0000803F0000803F79 +:10FB10000000803F0000803F0000803F0000803FE9 +:10FB2000000080BF000080BF0000803F000080BF59 +:10FB30000000803F0000803F0000803F000080BF49 +:10FB4000000080BF000080BF0000803F0000803FB9 +:10FB50000000803F000080BF0000803F0000803F29 +:10FB6000000080BF0000803F0000803F000080BF99 +:10FB70000000803F000080BF0000803F000080BF89 +:10FB8000000080BF0000803F0000803F0000803FF9 +:10FB90000000803F0000803F0000803F0000803F69 +:10FBA000000080BF000080BF0000803FD0B35DBF79 +:10FBB0000000003F0000803F0000803FD0B35DBFE9 +:10FBC000000000BF000080BF0000803FD0B35D3F59 +:10FBD0000000003F0000803F0000803FD0B35D3F49 +:10FBE000000000BF000080BF0000803F0000000058 +:10FBF000000080BF0000803F0000803F0000000048 +:10FC00000000803F000080BF0000803F0000000037 +:10FC10000000803F000080BF0000803F000080BFE8 +:10FC2000000000000000803F0000803F0000803F97 +:10FC3000000000000000803F0000803F0000000046 +:10FC4000000080BF000080BF0000803F0000000077 +:10FC50000000803F000080BF0000803F000080BFA8 +:10FC6000000080BF000000000000803F0000000096 +:10FC70000000803F0000803F0000803F0000803F88 +:10FC8000000080BF000000000000803F0000000076 +:10FC9000A8AAAA3F0000803F0000803F000080BF6C +:10FCA000B0AA2ABF000080BF0000803F0000803F54 +:10FCB000B0AA2ABF000080BF0000803F0000000003 +:10FCC000A8AAAA3F000080BF0000803F000080BFBC +:10FCD000B0AA2ABF0000803F0000803F0000803FA4 +:10FCE000B0AA2ABF0000803F0000803F0000000053 +:10FCF000A8AAAA3F000000000000803F000080BFCB +:10FD0000B0AA2ABF000000000000803F0000803F32 +:10FD1000B0AA2ABF0000000024505542582C3431AC +:10FD20002C312C303030332C303030312C313135D7 +:10FD30003230302C302A31450D0A0024504D544BBE +:10FD40003235312C3131353230302A31460D0A000E +:10FD500024505542582C34312C312C303030332C37 +:10FD6000303030312C35373630302C302A32440D9B +:10FD70000A0024504D544B3235312C353736303053 +:10FD80002A32430D0A0024505542582C34312C316C +:10FD90002C303030332C303030312C33383430305C +:10FDA0002C302A32360D0A0024504D544B32353156 +:10FDB0002C33383430302A32370D0A002450554263 +:10FDC000582C34312C312C303030332C3030303111 +:10FDD0002C31393230302C302A32330D0A00245085 +:10FDE0004D544B3235312C31393230302A32320DCC +:10FDF0000A00B56206010300F00500FF19B56206AE +:10FE0000010300F00300FD15B56206010300F001D7 +:10FE100000FB11B56206010300F00000FA0FB562A5 +:10FE200006010300F00200FC13B56206010300F0B6 +:10FE30000400FE17B562060103000102010E47B57A +:10FE400062060103000103010F49B56206010300C8 +:10FE5000010601124FB562060103000112011E677F +:10FE6000B56206160800030703000000000031E534 +:10FE7000B56206080600C80001000100DE6A000045 +:10FE80000000000000C2010018FD00083BFD000852 +:10FE90000100000000E1000050FD000872FD0008B4 +:10FEA000020000000096000086FD0008A8FD000882 +:10FEB00003000000004B0000BCFD0008DEFD000850 +:10FEC0000400000080250000830601088306010865 +:10FED00041455254313233340000271008042302C4 +:10FEE00020010000000000008025000000C2010089 +:10FEF00002000000010000008025000000C2010097 +:10FF0000030000000200000080250000004B0000FC +:10FF1000050000000300000080250000004B0000E9 +:10FF20000500000004000000300000200200000076 +:10FF30008025000000C20100000000001000000049 +:10FF40008025000000C20100010000002000000028 +:10FF50008025000000C20100000000000100000038 +:10FF60008025000000C20100000000000800000021 +:10FF70008025000000C20100000300000400000012 +:10FF800080250000004B000000000000D90E010891 +:10FF9000E00E0108E50E0108F60E0108000F010849 +:10FFA0000B0F0108160F0108210F0108CD0E0108E3 +:10FFB0002A0F0108C70E0108330F01083D0F010881 +:10FFC000480F01084E0F0108510F0108610F010889 +:10FFD000680F010800000000710F0108750F01088B +:10FFE0007B0F0108810F0108840F01088B0F0108A6 +:10FFF0008E0F0108930F01089F0F0108A20F01083F :020000040801F1 -:10000000204D6F64652C20747970652027657869B0 -:10001000742720746F2072657475726E2C206F7255 -:10002000202768656C70270D0A000D0A2320000D3B -:100030001B5B4B001B5B324A1B5B313B314800456D -:1000400052523A20556E6B6E6F776E20636F6D6DF6 -:10005000616E642C20747279202768656C702700AB -:10006000082008006C6F6F7074696D6500656D66BF -:100070005F61766F6964616E6365006D6964726368 -:10008000006D696E636865636B006D6178636865B8 -:10009000636B00727373695F6368616E6E656C0099 -:1000A000727373695F70776D5F70726F7669646584 -:1000B00072006D696E7468726F74746C65006D6146 -:1000C000787468726F74746C65006D696E636F6DBF -:1000D0006D616E64006465616462616E6433645F67 -:1000E0006C6F77006465616462616E6433645F683D -:1000F000696768006E65757472616C33640064656D -:10010000616462616E6433645F7468726F74746C8E -:1001100065006D6F746F725F70776D5F726174658B -:1001200000736572766F5F70776D5F7261746500E2 -:1001300072657461726465645F61726D00666C61A2 -:1001400070735F737065656400666978656477696C -:100150006E675F616C74686F6C645F646972007372 -:10016000657269616C5F706F72745F315F73636534 -:100170006E6172696F0073657269616C5F706F7236 -:10018000745F325F7363656E6172696F007365726D -:1001900069616C5F706F72745F335F7363656E610A -:1001A00072696F0073657269616C5F706F72745F02 -:1001B000345F7363656E6172696F007265626F6F41 -:1001C000745F636861726163746572006D73705F00 -:1001D000626175647261746500636C695F62617508 -:1001E0006472617465006770735F626175647261E7 -:1001F0007465006770735F706173737468726F7594 -:1002000067685F6261756472617465006770735FCF -:1002100070726F76696465720073657269616C7281 -:10022000785F70726F76696465720074656C656D75 -:10023000657472795F70726F766964657200746557 -:100240006C656D657472795F737769746368006655 -:1002500072736B795F696E76657273696F6E007623 -:100260006261747363616C6500766261746D61785C -:1002700063656C6C766F6C7461676500766261743F -:100280006D696E63656C6C766F6C74616765007028 -:100290006F7765725F6164635F6368616E6E656CE2 -:1002A00000616C69676E5F6779726F00616C696786 -:1002B0006E5F61636300616C69676E5F6D616700AB -:1002C000616C69676E5F626F6172645F726F6C6CA4 -:1002D00000616C69676E5F626F6172645F70697400 -:1002E000636800616C69676E5F626F6172645F79F9 -:1002F0006177006D61785F616E676C655F696E63E1 -:100300006C696E6174696F6E006779726F5F6C7093 -:1003100066006D6F726F6E5F7468726573686F6C84 -:1003200064006779726F5F636D70665F66616374A6 -:100330006F72006779726F5F636D70666D5F666183 -:1003400063746F7200616C745F686F6C645F746873 -:10035000726F74746C655F6E65757472616C006148 -:100360006C745F686F6C645F666173745F6368610F -:100370006E6765007468726F74746C655F636F722A -:1003800072656374696F6E5F76616C756500746821 -:10039000726F74746C655F636F7272656374696F9A -:1003A0006E5F616E676C6500796177646561646238 -:1003B000616E64007961775F636F6E74726F6C5FFA -:1003C000646972656374696F6E007961775F6469EF -:1003D00072656374696F6E007472695F756E6172C5 -:1003E0006D65645F736572766F0072635F726174CE -:1003F000650072635F6578706F007468725F6D6925 -:1004000064007468725F6578706F00726F6C6C5F07 -:1004100070697463685F72617465007961775F7297 -:10042000617465007470615F7261746500747061FD -:100430005F627265616B706F696E74006661696C92 -:10044000736166655F64656C6179006661696C7390 -:100450006166655F6F66665F64656C6179006661A1 -:10046000696C736166655F7468726F74746C650043 -:100470006661696C736166655F6D696E5F757365F2 -:1004800063006661696C736166655F6D61785F7555 -:100490007365630067696D62616C5F666C61677349 -:1004A000006163635F6861726477617265006163B4 -:1004B000635F6C70665F666163746F720061636333 -:1004C00078795F6465616462616E64006163637A18 -:1004D0005F6465616462616E64006163635F756E31 -:1004E00061726D656463616C006163635F747269FE -:1004F0006D5F7069746368006163635F7472696DD6 -:100500005F726F6C6C006261726F5F7461625F73C7 -:10051000697A65006261726F5F6E6F6973655F6CA7 -:100520007066006261726F5F63665F76656C006221 -:1005300061726F5F63665F616C74006D61675F64B9 -:1005400065636C696E6174696F6E006770735F706C -:100550006F735F70006770735F706F735F690067C0 -:1005600070735F706F735F64006770735F706F7339 -:10057000725F70006770735F706F73725F6900679E -:1005800070735F706F73725F64006770735F6E612A -:10059000765F70006770735F6E61765F6900677089 -:1005A000735F6E61765F64006770735F77705F7210 -:1005B0006164697573006E61765F636F6E74726FEC -:1005C0006C735F68656164696E67006E61765F7306 -:1005D000706565645F6D696E006E61765F737065EE -:1005E00065645F6D6178006E61765F736C65775FDF -:1005F00072617465007069645F636F6E74726F6CB2 -:100600006C657200705F706974636800695F70691F -:1006100074636800705F726F6C6C00695F726F6CFE -:100620006C00705F79617700695F79617700507065 -:100630006974636866004970697463686600447031 -:1006400069746368660050726F6C6C660049726F03 -:100650006C6C660044726F6C6C66005079617766F2 -:10066000004979617766004479617766006C657648 -:10067000656C5F686F72697A6F6E006C6576656C29 -:100680005F616E676C6500705F616C7400695F61CB -:100690006C7400645F616C7400705F6C6576656C8F -:1006A00000695F6C6576656C00645F6C6576656C8F -:1006B00000705F76656C00695F76656C00645F76DC -:1006C000656C0061757800666561747572655F6E52 -:1006D000616D6520617578666C6167206F7220625C -:1006E0006C616E6B20666F72206C69737400636D51 -:1006F00069780064657369676E20637573746F6DE4 -:10070000206D697865720064656661756C7473004C -:10071000726573657420746F2064656661756C74AE -:100720007320616E64207265626F6F740064756D12 -:1007300070007072696E7420636F6E66696775729F -:1007400061626C652073657474696E677320696E8D -:100750002061207061737461626C6520666F726DD8 -:1007600000657869740066656174757265006C690E -:100770007374206F72202D76616C206F7220766109 -:100780006C00677073706173737468726F756768FB -:1007900000706173737468726F7567682067707337 -:1007A00020746F2073657269616C0068656C7000FD -:1007B0006D6170006D617070696E67206F66207288 -:1007C00063206368616E6E656C206F726465720091 -:1007D0006D69786572206E616D65206F72206C693D -:1007E0007374006D6F746F72006765742F73657436 -:1007F000206D6F746F72206F7574707574207661E0 -:100800006C75650070726F66696C6500696E646511 -:100810007820283020746F203229007361766500BB -:100820007361766520616E64207265626F6F74001B -:100830006E616D653D76616C7565206F7220626CCE -:10084000616E6B206F72202A20666F72206C697354 -:10085000740073686F772073797374656D20737497 -:1008600061747573004144584C333435004D505514 -:1008700036303530004D4D413834357800424D41E9 -:10088000323830004C534D333033444C48430046EB -:10089000414B45004E6F6E65004759524F00414332 -:1008A00043004241524F00534F4E41520047505374 -:1008B000004750532B4D41470052585F50504D0058 -:1008C0005642415400494E464C494748545F4143C3 -:1008D000435F43414C0052585F53455249414C00DD -:1008E0004D4F544F525F53544F5000534552564F43 -:1008F0005F54494C5400534F465453455249414C60 -:10090000004C45445F52494E47004641494C5341D3 -:1009100046450054454C454D4554525900504F579B -:1009200045524D4554455200564152494F003344BB -:100930000052585F504152414C4C454C5F50574D0E -:100940000052585F4D535000525353495F50574D1A -:1009500000545249005155414450005155414458AA -:100960000042490047494D42414C00593600484534 -:10097000583600464C59494E475F57494E47005933 -:1009800034004845583658004F43544F5838004FAC -:1009900043544F464C415450004F43544F464C41F2 -:1009A000545800414952504C414E450048454C492D -:1009B0005F3132305F4343504D0048454C495F3909 -:1009C000305F44454700565441494C34004845582F -:1009D00036480050504D5F544F5F534552564F00BC -:1009E0004455414C434F505445520053494E474C97 -:1009F00045434F5054455200435553544F4D00000A -:100A0000990801089E080108A2080108B508010814 -:100A1000A7080108AD080108B1080108000000009E -:100A200064000108020000005819002000000000C6 -:100A3000282300006D000108000000005A19002062 -:100A400000000000010000007B000108020000001F -:100A50005E1A0020B0040000A40600008100010816 -:100A600002000000601A002000000000D007000013 -:100A70008A00010802000000621A00200000000045 -:100A8000D00700009300010801000000641A002054 -:100A90000000000012000000A0000108010000009A -:100AA000651A00200000000001000000B2000108EB -:100AB000020000001C1A002000000000D007000007 -:100AC000BE000108020000001E1A00200000000005 -:100AD000D0070000CA00010802000000201A002010 -:100AE00000000000D0070000D5000108020000004F -:100AF000221A002000000000D0070000E4000108D6 -:100B000002000000241A002000000000D0070000AE -:100B1000F400010802000000261A00200000000076 -:100B2000D0070000FE00010802000000281A002083 -:100B300000000000D00700001201010802000000C0 -:100B40002A1A002032000000007D00002101010867 -:100B5000020000002C1A002032000000F201000008 -:100B60003001010800000000661A002000000000AB -:100B7000010000003D01010800000000671A00208C -:100B800000000000640000004901010801000000AD -:100B9000681A0020FFFFFFFF010000005F0101084D -:100BA000000000006C1A0020000000000800000097 -:100BB00076010108000000006D1A0020000000000E -:100BC000080000008D010108000000006E1A0020DE -:100BD0000000000008000000A4010108000000005F -:100BE0006F1A00200000000008000000BB0101088F -:100BF00000000000801A0020300000007E0000008D -:100C0000CC01010804000000701A0020B0040000AC -:100C100000C20100D901010804000000741A00207C -:100C2000B004000000C20100E60101080400000059 -:100C3000781A00200000000000C20100F301010842 -:100C4000040000007C1A0020B004000000C2010073 -:100C50000C020108000000006A1A002000000000D9 -:100C60000200000019020108000000005C1A0020C8 -:100C700000000000030000002B020108000000003B -:100C8000841A002000000000020000003E0201085B -:100C900000000000851A0020000000000100000094 -:100CA0004F02010800000000861A0020000000002A -:100CB000010000005F02010800000000501A00203F -:100CC0000A000000C80000006902010800000000DE -:100CD000511A00200A000000320000007C020108C6 -:100CE00000000000521A00200A000000320000003C -:100CF0008F02010800000000531A002000000000CD -:100D000009000000A1020108000000002E1A0020C6 -:100D10000000000008000000AC0201080000000014 -:100D20002F1A00200000000008000000B602010891 -:100D300000000000301A0020000000000800000041 -:100D4000C002010803000000321A00204CFFFFFF20 -:100D500068010000D102010803000000341A0020DD -:100D60004CFFFFFF68010000E302010803000000E0 -:100D7000361A00204CFFFFFF68010000F302010853 -:100D800002000000421A00206400000084030000FA -:100D900009030108020000003A1A002000000000C8 -:100DA000000100001203010800000000401A0020AA -:100DB0000000000080000000220301080200000083 -:100DC0003C1A002064000000E8030000330301081F -:100DD000020000003E1A002064000000E80300004A -:100DE0004503010800000000321E00200100000041 -:100DF000FA0000005F03010800000000331E00201D -:100E00000000000001000000740301080000000061 -:100E1000361E002000000000960000008E0301082E -:100E200002000000341E00200100000084030000C6 -:100E3000C304010800000000301E00200000000074 -:100E400020000000A803010800000000311E00205F -:100E50000000000064000000B4030108010000006D -:100E6000381A0020FFFFFFFF01000000CA0301083D -:100E700001000000801E0020FFFFFFFF01000000B6 -:100E8000D803010801000000811E002000000000BE -:100E900001000000EA03010800000000E01D00203E -:100EA00000000000FA000000F2030108000000004A -:100EB000E11D00200000000064000000FA030108AA -:100EC00000000000E21D002000000000640000009F -:100ED0000204010800000000E31D002000000000E3 -:100EE000640000000B04010800000000E41D002065 -:100EF00000000000640000001B0401080000000066 -:100F0000E51D00200000000064000000240401082A -:100F100000000000E61D002000000000640000004A -:100F20002D04010802000000E81D0020E803000075 -:100F3000D00700003C04010800000000781E0020DB -:100F400000000000C80000004B0401080000000081 -:100F5000791E002000000000C80000005E040108A7 -:100F6000020000007A1E0020E8030000D007000005 -:100F700070040108020000007C1E002064000000D4 -:100F8000D007000082040108020000007E1E00203D -:100F900064000000B80B0000940401080000000089 -:100FA000821E002000000000FF000000A1040108D4 -:100FB00000000000391A00200000000005000000B9 -:100FC000AE04010800000000F01D00200000000039 -:100FD000FA000000BD04010800000000F21D00201E -:100FE0000000000064000000CC04010800000000C4 -:100FF000F11D00200000000064000000DA04010878 -:1010000000000000041E002000000000010000009D -:10101000E904010803000000EE1D0020D4FEFFFFDC -:101020002C010000F804010803000000EC1D002062 -:10103000D4FEFFFF2C01000006050108000000009F -:10104000F41D00200000000030000000140501081D -:1010500005000000F81D0020000000000100000055 -:101060002305010805000000FC1D00200000000011 -:10107000010000002F05010805000000001E0020EF -:1010800000000000010000003B0501080300000013 -:10109000EA1D0020B0B9FFFF504600004B050108D3 -:1010A00000000000981D002000000000C8000000A3 -:1010B0005505010800000000A21D002000000000EE -:1010C000C80000005F05010800000000AC1D002002 -:1010D00000000000C80000006905010800000000D1 -:1010E000991D002000000000C800000074050108E0 -:1010F00000000000A31D002000000000C800000048 -:101100007F05010800000000AD1D00200000000068 -:10111000C80000008A050108000000009A1D002098 -:1011200000000000C8000000940501080000000055 -:10113000A41D002000000000C80000009E0501085A -:1011400000000000AE1D002000000000C8000000EC -:10115000A805010802000000841E00200000000015 -:10116000D0070000B605010800000000881E00201E -:101170000000000001000000CB0501080200000093 -:101180008A1E00200A000000D0070000D9050108CF -:10119000020000008C1E00200A000000D0070000A2 -:1011A000E705010800000000871E00200000000085 -:1011B00064000000F505010800000000901D0020FB -:1011C000000000000200000004060108000000000A -:1011D000951D002000000000C80000000C0601085A -:1011E000000000009F1D002000000000C80000005B -:1011F000DB02010800000000A91D00200000000023 -:10120000C80000001406010800000000941D002022 -:1012100000000000C80000001B06010800000000DC -:101220009E1D002000000000C8000000CA02010846 -:1012300000000000A81D002000000000C800000001 -:101240002206010800000000961D0020000000009A -:10125000C80000002806010800000000A01D0020B2 -:1012600000000000C8000000ED02010800000000BE -:10127000AA1D002000000000C80000002E06010882 -:1012800005000000B81D0020000000006400000000 -:101290003606010805000000C41D00200000000003 -:1012A000640000003E06010805000000D01D00207B -:1012B0000000000064000000460601080500000070 -:1012C000B41D002000000000640000004D0601086D -:1012D00005000000C01D00200000000064000000A8 -:1012E0005406010805000000CC1D0020000000008D -:1012F000640000005B06010805000000BC1D002022 -:101300000000000064000000610601080500000004 -:10131000C81D0020000000006400000067060108EE -:1013200005000000D41D0020000000006400000043 -:101330006D06010805000000DC1D00200000000013 -:101340000A0000007B06010805000000D81D0020EF -:10135000000000000A0000008706010800000000ED -:10136000971D002000000000C80000008D06010845 -:1013700000000000A11D002000000000C8000000C7 -:101380009306010800000000AB1D002000000000D3 -:10139000C800000099060108000000009B1D002005 -:1013A00000000000C8000000A106010800000000C5 -:1013B000A51D002000000000C8000000A9060108CB -:1013C00000000000AF1D002000000000C800000069 -:1013D000B1060108000000009D1D00200000000073 -:1013E000C8000000B706010800000000A71D00208B -:1013F00000000000C8000000BD0601080000000059 -:10140000B11D002000000000C8000000524F4C4CED -:101410003B50495443483B5941573B414C543B5046 -:101420006F733B506F73523B4E6176523B4C455647 -:10143000454C3B4D41473B56454C3B0041524D3B93 -:1014400000414E474C453B00484F52495A4F4E3B96 -:10145000004241524F3B00564152494F3B004D41E3 -:10146000473B0048454144465245453B00484541BD -:101470004441444A3B0043414D535441423B0043A5 -:10148000414D545249473B0047505320484F4D452A -:101490003B0047505320484F4C443B00504153536E -:1014A000544852553B004245455045523B004C453F -:1014B000444D41583B004C45444C4F573B004C4C2D -:1014C00049474854533B0043414C49423B00474F36 -:1014D0005645524E4F523B004F53442053573B000A -:1014E00054454C454D455452593B00746564666DF6 -:1014F0006A69736C670000000000004B000000CBBD -:1015000061636F7366000000000000007371727405 -:1015100066000000000FC93F000F494000CB964015 -:10152000000FC9400053FB4000CB164100ED2F4196 -:10153000000F49410031624100537B41003A8A412A -:1015400000CB9641005CA34100EDAF41007EBC4161 -:10155000000FC94100A0D5410031E24100C2EE4177 -:101560000053FB4100F20342003A0A42008310425A -:1015700000CB164200141D42005C234200A5294204 -:1015800000ED2F4200363642007E3C4200C7424208 -:10159000000F4942A2000000F90000008300000093 -:1015A0006E0000004E000000440000001500000026 -:1015B00029000000FC000000270000005700000088 -:1015C000D1000000F500000034000000DD00000044 -:1015D000C0000000DB000000620000009500000079 -:1015E000990000003C000000430000009000000053 -:1015F00041000000FE0000005100000063000000F8 -:10160000AB000000DE000000BB000000C5000000D1 -:1016100061000000B7000000240000006E00000020 -:101620003A000000420000004D000000D20000001F -:10163000E000000006000000490000002E0000004D -:10164000EA00000009000000D10000009200000044 -:101650001C000000FE0000001D000000EB00000068 -:101660001C000000B100000029000000A7000000DD -:101670003E000000E800000082000000350000008D -:10168000F50000002E000000BB0000004400000038 -:1016900084000000E90000009C00000070000000D1 -:1016A00026000000B40000005F0000007E00000083 -:1016B000410000003900000091000000D600000049 -:1016C00039000000830000005300000039000000D2 -:1016D000F40000009C000000840000005F00000097 -:1016E0008B000000BD000000F90000002800000091 -:1016F0003B0000001F000000F80000009700000001 -:10170000FF000000DE00000005000000980000005F -:101710000F000000EF0000002F000000110000008B -:101720008B0000005A0000000A0000006D0000005D -:101730001F0000006D000000360000007E00000069 -:10174000CF00000027000000CB00000009000000CF -:10175000B70000004F000000460000003F000000FE -:10176000660000009E0000005F000000EA0000002C -:101770002D0000007500000027000000BA000000E6 -:10178000C7000000EB000000E5000000F1000000D1 -:101790007B0000003D000000070000003900000051 -:1017A000F70000008A0000005200000092000000D4 -:1017B000EA0000006B000000FB0000005F0000007A -:1017C000B10000001F0000008D0000005D0000005F -:1017D0000800000056000000030000003000000078 -:1017E00046000000FC0000007B0000006B000000D1 -:1017F000AB000000F0000000CF000000BC000000C3 -:10180000200000009A000000F400000036000000F4 -:101810001D000000A9000000E3000000910000008E -:10182000610000005E000000E60000001B000000F8 -:10183000080000006500000099000000850000001D -:101840005F00000014000000A0000000680000001D -:10185000400000008D000000FF000000D8000000E4 -:10186000800000004D000000730000002700000011 -:101870003100000006000000060000001500000016 -:1018800056000000CA00000073000000A80000001D -:10189000C900000060000000E20000007B000000C2 -:1018A000C00000008C0000006B000000040000007D -:1018B00007000000090000000000C93F0000F039E7 -:1018C0000000DA370000A2330000842E0000502B05 -:1018D0000000C2270000D0220000C41F0000C61B69 -:1018E000000044176937AC3168212233B40F143338 -:1018F0006821A2333863ED3EDA0F493F5E987B3FA3 -:10190000DA0FC93F00202020202020202020282876 -:1019100028282820202020202020202020202020AF -:1019200020202020208810101010101010101010EF -:10193000101010101004040404040404040404101F -:1019400010101010101041414141414101010101AD -:101950000101010101010101010101010101010177 -:101960001010101010104242424242420202020283 -:101970000202020202020202020202020202020247 -:1019800010101010200000000000000000000000F7 -:101990000000000000000000000000000000000047 -:1019A0000000000000000000000000000000000037 -:1019B0000000000000000000000000000000000027 -:1019C0000000000000000000000000000000000017 -:1019D0000000000000000000000000000000000007 -:1019E00000000000000000000000000000000000F7 -:1019F00000000000000000000000000000000000E7 -:101A0000000000000000000043000000A8010020CA -:101A1000F8B500BFF8BC08BC9E467047F8B500BFDB -:081A2000F8BC08BC9E467047AB -:081A2800C9ED000835010008BA -:041A30001101000898 -:101A34000303010000010000F55300080000803F8B -:101A44000000000000000000DC05DC05DC05DC050E -:101A5400DC05DC05DC05DC050000803F010100003D -:101A64000000000000000000000000000100000071 -:101A74000000000000000000020000000000000060 -:101A8400000000000300000000000000000000004F -:101A94000400000030000020000000003C14010895 -:101AA40000000000010000004114010801000000D2 -:101AB40002000000481401080200000003000000B6 -:101AC4005114010803000000040000005714010829 -:101AD40004000000050000005E1401080500000079 -:101AE400060000006314010806000000070000005F -:101AF4006D140108070000000800000076140108B6 -:101B040008000000090000007F140108090000001B -:101B14000A000000881401080A0000000B000000FD -:101B2400921401080B0000000C0000009C14010832 -:101B34000C0000000D000000A61401080D000000B8 -:101B44000E000000AE1401080E0000000F0000009B -:101B5400B61401080F00000010000000BE140108B4 -:101B64001000000011000000C7140108110000005B -:101B740012000000CE14010812000000130000003F -:101B8400D81401081300000014000000E014010838 -:101B9400140000001500000000000000FF00000019 -:101BA4000000000000000000010203040607080909 -:101BB40000127A0000A24A04020406080000000091 -:101BC40001020304010203040607080901000000DE -:101BD4000419010800000000000000009404002023 -:101BE400FC04002064050020000000000000000048 -:101BF40000000000000000000000000000000000E1 -:101C0400000000000000000000000000081A0108A5 -:101C140000000000000000000000000000000000C0 -:101C240000000000000000000000000000000000B0 -:101C340000000000000000000000000000000000A0 -:101C44000000000000000000000000000000000090 -:101C54000000000000000000000000000000000080 -:101C64000000000000000000000000000000000070 -:101C74000000000000000000000000000000000060 -:101C840001000000000000000E33CDAB34126DE6FD -:101C9400ECDE05000B000000000000000000000066 -:101CA4000000000000000000000000000000000030 -:101CB4000000000000000000000000000000000020 -:101CC4000000000000000000000000000000000010 -:101CD4000000000000000000000000000000000000 -:101CE40000000000000000000000000000000000F0 -:101CF40000000000000000000000000000000000E0 -:101D040000000000000000000000000000000000CF -:101D140000000000000000000000000000000000BF -:101D240000000000000000000000000000000000AF -:101D3400000000000000000000000000000000009F -:101D4400000000000000000000000000000000008F -:101D5400000000000000000000000000000000007F -:101D6400000000000000000000000000000000006F -:101D7400000000000000000000000000000000005F -:101D8400000000000000000000000000000000004F -:101D9400000000000000000000000000000000003F -:101DA400000000000000000000000000000000002F -:101DB400000000000000000000000000000000001F -:101DC400000000000000000000000000000000000F -:101DD40000000000000000000000000000000000FF -:101DE40000000000000000000000000000000000EF -:101DF40000000000000000000000000000000000DF -:101E040000000000000000000000000000000000CE -:101E140000000000000000000000000000000000BE -:101E240000000000000000000000000000000000AE -:101E3400000000000000000000000000000000009E -:101E4400000000000000000000000000000000008E -:101E5400000000000000000000000000000000007E -:101E6400000000000000000000000000000000006E -:101E7400000000000000000000000000000000005E -:101E8400000000000000000000000000000000004E -:101E9400000000000000000000000000000000003E -:101EA400000000000000000000000000000000002E -:101EB400000000000000000000000000000000001E -:101EC400000000000000000000000000000000000E -:101ED40000000000000000000000000000000000FE -:101EE40000000000000000000000000000000000EE -:101EF40000000000000000000000000000000000DE -:101F040000000000000000000000000000000000CD -:101F140000000000000000000000000000000000BD -:101F240000000000000000000000000000000000AD -:101F3400000000000000000000000000000000009D -:101F4400000000000000000000000000000000008D -:101F5400000000000000000000000000000000007D -:101F6400000000000000000000000000000000006D -:101F7400000000000000000000000000000000005D -:101F8400000000000000000000000000000000004D -:101F9400000000000000000000000000000000003D -:101FA400000000000000000000000000000000002D -:101FB400000000000000000000000000000000001D -:101FC400000000000000000000000000000000000D -:101FD40000000000000000000000000000000000FD -:101FE40000000000000000000000000000000000ED -:101FF40000000000000000000000000000000000DD -:04200400A80100200F +:10000000A80F0108AF0F0108B90F0108C30F0108BD +:10001000CC0F0108DA0F0108E60F0108ED0F010807 +:10002000F30F0108001001080B1001081810010857 +:1000300000000000E30C0108E70C010821A80008FB +:100040000E0D0108130D0108E1A20008270D01089B +:10005000300D0108C9A200084D0D0108520D01081C +:1000600085A80008810D01088306010891A20008F7 +:10007000860D01088E0D0108A9A10008A20D010836 +:10008000B10D010889A10008CB0D01088306010804 +:10009000D59E0008D00D0108D40D0108E1A000088C +:1000A000210D0108F00D010831A50008030E01081B +:1000B000090E010879A70008240E01082C0E01087A +:1000C0002DA700083B0E0108400E0108B9A000084A +:1000D00063030108500E0108D1A500087E0E010837 +:1000E000720E0108019F00087708010883060108C5 +:1000F000C99E000883060108850E01088D0E0108BF +:10010000950E01089D0E0108A40E0108AF0E01080E +:10011000B40E0108000000004166726F33322043C4 +:100120004C492076657273696F6E20322E32204DF5 +:1001300061792032382032303134202F2030333A68 +:1001400034303A3432202D2028636C65616E666C41 +:10015000696768742900417661696C61626C652029 +:10016000636F6D6D616E64733A0D0A002573092526 +:10017000730D0A0053797374656D20557074696D41 +:10018000653A202564207365636F6E64732C205676 +:100190006F6C746167653A202564202A20302E3107 +:1001A0005620282564532062617474657279290D84 +:1001B0000A004350552025644D487A2C206465740C +:1001C00065637465642073656E736F72733A2000A3 +:1001D0002573200041434348573A202573002E25BC +:1001E00063004379636C652054696D653A2025642A +:1001F0002C20493243204572726F72733A20256475 +:100200002C20636F6E6669672073697A653A2025D2 +:10021000640D0A00202564202564000D0A526562E1 +:100220006F6F74696E672E2E2E00536176696E674C +:100230002E2E2E004D75737420626520616E79201C +:100240006F72646572206F662041455452313233BB +:10025000340D0A0043757272656E742061737369A0 +:10026000676E6D656E743A20004572726F723A2047 +:10027000456E61626C6520616E6420706C756720EC +:10028000696E204750532066697273740D0A0045E9 +:100290006E61626C65642066656174757265733A3F +:1002A0002000417661696C61626C652066656174ED +:1002B000757265733A2000496E76616C69642066D8 +:1002C000656174757265206E616D652E2E2E0D0A46 +:1002D0000044697361626C65642000456E61626C04 +:1002E000656420000D0A4C656176696E6720434C99 +:1002F00049206D6F64652E2E2E0D0A0052657365C0 +:100300007474696E6720746F2064656661756C74BF +:10031000732E2E2E004E4709004F4B090043757374 +:10032000746F6D206D697865723A200D0A4D6F7497 +:100330006F720954687209526F6C6C09506974636A +:1003400068095961770D0A002325643A090025736D +:10035000090053616E69747920636865636B3A09BB +:10036000007265736574006C6F616400496E76613C +:100370006C6964206D6978657220747970652E2EC1 +:100380002E0D0A004C6F61646564202573206D6931 +:10039000782E2E2E0D0A0057726F6E67206E756DC7 +:1003A000626572206F6620617267756D656E747329 +:1003B0002C206E65656473206964782074687220EF +:1003C000726F6C6C207069746368207961770D0AB4 +:1003D000004D6F746F72206E756D626572206D7561 +:1003E0007374206265206265747765656E203120C4 +:1003F000616E642025640D0A0043757272656E7427 +:10040000206D697865723A2025730D0A0041766186 +:10041000696C61626C65206D69786572733A200061 +:100420004D697865722073657420746F2025730D93 +:100430000A0043757272656E742073657474696E18 +:1004400067733A200D0A0025732073657420746F5A +:1004500020004552523A2056616C756520617373D5 +:1004600069676E6D656E74206F7574206F6620729B +:10047000616E67650D0A004552523A20556E6B6EEB +:100480006F776E207661726961626C65206E616D56 +:10049000650D0A0043757272656E742070726F6626 +:1004A000696C653A2025640D0A0055736167653AE9 +:1004B0000D0A6D6F746F7220696E646578205B76CB +:1004C000616C75655D202D2073686F77205B6F729E +:1004D000207365745D206D6F746F722076616C752A +:1004E000650D0A004E6F2073756368206D6F746F21 +:1004F000722C207573652061206E756D62657220A7 +:100500005B302C2025645D0D0A004D6F746F7220E6 +:100510002564206973207365742061742025640D3F +:100520000A00496E76616C6964206D6F746F722089 +:1005300076616C75652C20313030302E2E323030A3 +:10054000300D0A0053657474696E67206D6F746FA7 +:100550007220256420746F2025640D0A006175786F +:100560002025752025750D0A00496E76616C696439 +:10057000204665617475726520696E6465783A20FD +:100580006D757374206265203C2025750D0A00434B +:10059000757272656E7420436F6E6669673A2043A8 +:1005A0006F70792065766572797468696E6720620C +:1005B000656C6F7720686572652E2E2E0D0A006DB2 +:1005C000697865722025730D0A00636D69782025AE +:1005D0006400636D6978202564203020302030204D +:1005E000300D0A0066656174757265202D25730DE6 +:1005F0000A00666561747572652025730D0A006DC9 +:1006000061702025730D0A00736574202573203DE9 +:1006100020000D0A456E746572696E6720434C496F +:10062000204D6F64652C207479706520276578698A +:10063000742720746F2072657475726E2C206F722F +:10064000202768656C70270D0A000D0A2320000D15 +:100650001B5B4B001B5B324A1B5B313B3148004547 +:1006600052523A20556E6B6E6F776E20636F6D6DD0 +:10067000616E642C20747279202768656C70270085 +:10068000082008006C6F6F7074696D6500656D6699 +:100690005F61766F6964616E6365006D6964726342 +:1006A000006D696E636865636B006D617863686592 +:1006B000636B00727373695F6368616E6E656C0073 +:1006C000727373695F70776D5F70726F766964655E +:1006D00072006D696E7468726F74746C65006D6120 +:1006E000787468726F74746C65006D696E636F6D99 +:1006F0006D616E64006465616462616E6433645F41 +:100700006C6F77006465616462616E6433645F6816 +:10071000696768006E65757472616C336400646546 +:10072000616462616E6433645F7468726F74746C68 +:1007300065006D6F746F725F70776D5F7261746565 +:1007400000736572766F5F70776D5F7261746500BC +:1007500072657461726465645F61726D00666C617C +:1007600070735F7370656564006669786564776946 +:100770006E675F616C74686F6C645F64697200734C +:10078000657269616C5F706F72745F315F7363650E +:100790006E6172696F0073657269616C5F706F7210 +:1007A000745F325F7363656E6172696F0073657247 +:1007B00069616C5F706F72745F335F7363656E61E4 +:1007C00072696F0073657269616C5F706F72745FDC +:1007D000345F7363656E6172696F007265626F6F1B +:1007E000745F636861726163746572006D73705FDA +:1007F000626175647261746500636C695F626175E2 +:100800006472617465006770735F626175647261C0 +:100810007465006770735F706173737468726F756D +:1008200067685F6261756472617465006770735FA9 +:1008300070726F76696465720073657269616C725B +:10084000785F70726F76696465720074656C656D4F +:10085000657472795F70726F766964657200746531 +:100860006C656D657472795F73776974636800662F +:1008700072736B795F696E76657273696F6E0076FD +:100880006261747363616C6500766261746D617836 +:1008900063656C6C766F6C74616765007662617419 +:1008A0006D696E63656C6C766F6C74616765007002 +:1008B0006F7765725F6164635F6368616E6E656CBC +:1008C00000616C69676E5F6779726F00616C696760 +:1008D0006E5F61636300616C69676E5F6D61670085 +:1008E000616C69676E5F626F6172645F726F6C6C7E +:1008F00000616C69676E5F626F6172645F706974DA +:10090000636800616C69676E5F626F6172645F79D2 +:100910006177006D61785F616E676C655F696E63BA +:100920006C696E6174696F6E006779726F5F6C706D +:1009300066006D6F726F6E5F7468726573686F6C5E +:1009400064006779726F5F636D70665F6661637480 +:100950006F72006779726F5F636D70666D5F66615D +:1009600063746F7200616C745F686F6C645F74684D +:10097000726F74746C655F6E65757472616C006122 +:100980006C745F686F6C645F666173745F636861E9 +:100990006E6765007468726F74746C655F636F7204 +:1009A00072656374696F6E5F76616C7565007468FB +:1009B000726F74746C655F636F7272656374696F74 +:1009C0006E5F616E676C6500796177646561646212 +:1009D000616E64007961775F636F6E74726F6C5FD4 +:1009E000646972656374696F6E007961775F6469C9 +:1009F00072656374696F6E007472695F756E61729F +:100A00006D65645F736572766F0072635F726174A7 +:100A1000650072635F6578706F007468725F6D69FE +:100A200064007468725F6578706F00726F6C6C5FE1 +:100A300070697463685F72617465007961775F7271 +:100A4000617465007470615F7261746500747061D7 +:100A50005F627265616B706F696E74006661696C6C +:100A6000736166655F64656C6179006661696C736A +:100A70006166655F6F66665F64656C61790066617B +:100A8000696C736166655F7468726F74746C65001D +:100A90006661696C736166655F6D696E5F757365CC +:100AA00063006661696C736166655F6D61785F752F +:100AB0007365630067696D62616C5F666C61677323 +:100AC000006163635F68617264776172650061638E +:100AD000635F6C70665F666163746F72006163630D +:100AE00078795F6465616462616E64006163637AF2 +:100AF0005F6465616462616E64006163635F756E0B +:100B000061726D656463616C006163635F747269D7 +:100B10006D5F7069746368006163635F7472696DAF +:100B20005F726F6C6C006261726F5F7461625F73A1 +:100B3000697A65006261726F5F6E6F6973655F6C81 +:100B40007066006261726F5F63665F76656C0062FB +:100B500061726F5F63665F616C74006D61675F6493 +:100B600065636C696E6174696F6E006770735F7046 +:100B70006F735F70006770735F706F735F6900679A +:100B800070735F706F735F64006770735F706F7313 +:100B9000725F70006770735F706F73725F69006778 +:100BA00070735F706F73725F64006770735F6E6104 +:100BB000765F70006770735F6E61765F6900677063 +:100BC000735F6E61765F64006770735F77705F72EA +:100BD0006164697573006E61765F636F6E74726FC6 +:100BE0006C735F68656164696E67006E61765F73E0 +:100BF000706565645F6D696E006E61765F737065C8 +:100C000065645F6D6178006E61765F736C65775FB8 +:100C100072617465007069645F636F6E74726F6C8B +:100C20006C657200705F706974636800695F7069F9 +:100C300074636800705F726F6C6C00695F726F6CD8 +:100C40006C00705F79617700695F7961770050703F +:100C5000697463686600497069746368660044700B +:100C600069746368660050726F6C6C660049726FDD +:100C70006C6C660044726F6C6C66005079617766CC +:100C8000004979617766004479617766006C657622 +:100C9000656C5F686F72697A6F6E006C6576656C03 +:100CA0005F616E676C6500705F616C7400695F61A5 +:100CB0006C7400645F616C7400705F6C6576656C69 +:100CC00000695F6C6576656C00645F6C6576656C69 +:100CD00000705F76656C00695F76656C00645F76B6 +:100CE000656C0061757800666561747572655F6E2C +:100CF000616D6520617578666C6167206F72206236 +:100D00006C616E6B20666F72206C69737400636D2A +:100D100069780064657369676E20637573746F6DBD +:100D2000206D697865720064656661756C74730026 +:100D3000726573657420746F2064656661756C7488 +:100D40007320616E64207265626F6F740064756DEC +:100D500070007072696E7420636F6E666967757279 +:100D600061626C652073657474696E677320696E67 +:100D70002061207061737461626C6520666F726DB2 +:100D800000657869740066656174757265006C69E8 +:100D90007374206F72202D76616C206F72207661E3 +:100DA0006C00677073706173737468726F756768D5 +:100DB00000706173737468726F7567682067707311 +:100DC00020746F2073657269616C0068656C7000D7 +:100DD0006D6170006D617070696E67206F66207262 +:100DE00063206368616E6E656C206F72646572006B +:100DF0006D69786572206E616D65206F72206C6917 +:100E00007374006D6F746F72006765742F7365740F +:100E1000206D6F746F72206F7574707574207661B9 +:100E20006C75650070726F66696C6500696E6465EB +:100E30007820283020746F20322900736176650095 +:100E40007361766520616E64207265626F6F7400F5 +:100E50006E616D653D76616C7565206F7220626CA8 +:100E6000616E6B206F72202A20666F72206C69732E +:100E7000740073686F772073797374656D20737471 +:100E800061747573004144584C333435004D5055EE +:100E900036303530004D4D413834357800424D41C3 +:100EA000323830004C534D333033444C48430046C5 +:100EB000414B45004E6F6E65004759524F0041430C +:100EC00043004241524F00534F4E4152004750534E +:100ED000004750532B4D41470052585F50504D0032 +:100EE0005642415400494E464C494748545F41439D +:100EF000435F43414C0052585F53455249414C00B7 +:100F00004D4F544F525F53544F5000534552564F1C +:100F10005F54494C5400534F465453455249414C39 +:100F2000004C45445F52494E47004641494C5341AD +:100F300046450054454C454D4554525900504F5775 +:100F400045524D4554455200564152494F00334495 +:100F50000052585F504152414C4C454C5F50574DE8 +:100F60000052585F4D535000525353495F50574DF4 +:100F70000054524900515541445000515541445884 +:100F80000042490047494D42414C0059360048450E +:100F9000583600464C59494E475F57494E4700590D +:100FA00034004845583658004F43544F5838004F86 +:100FB00043544F464C415450004F43544F464C41CC +:100FC000545800414952504C414E450048454C4907 +:100FD0005F3132305F4343504D0048454C495F39E3 +:100FE000305F44454700565441494C340048455809 +:100FF00036480050504D5F544F5F534552564F0096 +:101000004455414C434F505445520053494E474C70 +:1010100045434F5054455200435553544F4D0000E3 +:10102000B90E0108BE0E0108C20E0108D50E010856 +:10103000C70E0108CD0E0108D10E01080000000006 +:101040008406010802000000F419002000000000DE +:10105000282300008D06010800000000F61900207A +:1010600000000000010000009B06010802000000D3 +:10107000FA1A0020B0040000A4060000A10601082E +:1010800002000000FC1A002000000000D007000051 +:10109000AA06010802000000FE1A0020000000005D +:1010A000D0070000B306010801000000001B00206B +:1010B0000000000012000000C0060108010000004E +:1010C000011B00200000000001000000D206010802 +:1010D00002000000B81A002000000000D007000045 +:1010E000DE06010802000000BA1A0020000000001D +:1010F000D0070000EA06010802000000BC1A002028 +:1011000000000000D0070000F50601080200000002 +:10111000BE1A002000000000D007000004070108EC +:1011200002000000C01A002000000000D0070000EC +:101130001407010802000000C21A0020000000008D +:10114000D00700001E07010802000000C41A00209A +:1011500000000000D0070000320701080200000074 +:10116000C61A002032000000007D0000410701087F +:1011700002000000C81A002032000000F201000046 +:101180005007010800000000021B002000000000C2 +:10119000010000005D07010800000000031B0020A3 +:1011A0000000000064000000690701080100000061 +:1011B000041B0020FFFFFFFF010000007F07010864 +:1011C00000000000081B00200000000008000000D4 +:1011D0009607010800000000091B00200000000025 +:1011E00008000000AD070108000000000A1B0020F5 +:1011F0000000000008000000C40701080000000013 +:101200000B1B00200000000008000000DB070108A5 +:10121000000000001C1B0020300000007E000000C9 +:10122000EC070108040000000C1B0020B0040000C3 +:1012300000C20100F907010804000000101B002093 +:10124000B004000000C2010006080108040000000C +:10125000141B00200000000000C201001308010858 +:1012600004000000181B0020B004000000C20100B0 +:101270002C08010800000000061B002000000000F0 +:10128000020000003908010800000000F81A0020E0 +:1012900000000000030000004B08010800000000EF +:1012A000201B002000000000020000005E08010872 +:1012B00000000000211B00200000000001000000D1 +:1012C0006F08010800000000221B00200000000041 +:1012D000010000007F08010800000000EC1A002057 +:1012E0000A000000C8000000890801080000000092 +:1012F000ED1A00200A000000320000009C080108DE +:1013000000000000EE1A00200A0000003200000079 +:10131000AF08010800000000EF1A002000000000E4 +:1013200009000000C108010800000000CA1A0020DE +:101330000000000008000000CC08010800000000C8 +:10134000CB1A00200000000008000000D6080108A9 +:1013500000000000CC1A002000000000080000007F +:10136000E008010803000000CE1A00204CFFFFFF38 +:1013700068010000F108010803000000D01A0020F5 +:101380004CFFFFFF68010000030901080300000093 +:10139000D21A00204CFFFFFF68010000130901086A +:1013A00002000000DE1A0020640000008403000038 +:1013B0002909010802000000D61A002000000000E0 +:1013C000000100003209010800000000DC1A0020C2 +:1013D0000000000080000000420901080200000037 +:1013E000D81A002064000000E80300005309010837 +:1013F00002000000DA1A002064000000E803000088 +:101400006509010800000000D81E0020010000004E +:10141000FA0000007F09010800000000D91E00202A +:101420000000000001000000940901080000000015 +:10143000DC1E00200000000096000000AE0901083C +:1014400002000000DA1E00200100000084030000FA +:10145000E30A010800000000D61E00200000000082 +:1014600020000000C809010800000000D71E00206D +:101470000000000064000000D40901080100000021 +:10148000D41A0020FFFFFFFF01000000EA09010855 +:1014900001000000261F0020FFFFFFFF01000000E9 +:1014A000F809010801000000271F002000000000CB +:1014B000010000000A0A010800000000841E00204C +:1014C00000000000FA000000120A010800000000FD +:1014D000851E002000000000640000001A0A0108B8 +:1014E00000000000861E00200000000064000000D4 +:1014F000220A010800000000871E002000000000F2 +:10150000640000002B0A010800000000881E002073 +:1015100000000000640000003B0A01080000000019 +:10152000891E00200000000064000000440A010839 +:10153000000000008A1E002000000000640000007F +:101540004D0A0108020000008C1E0020E803000084 +:10155000D00700005C0A0108000000001E1F0020E8 +:1015600000000000C80000006B0A01080000000035 +:101570001F1F002000000000C80000007E0A0108B4 +:1015800002000000201F0020E8030000D007000038 +:10159000900A010802000000221F002064000000E1 +:1015A000D0070000A20A010802000000241F00204A +:1015B00064000000B80B0000B40A0108000000003D +:1015C000281F002000000000FF000000C10A0108E1 +:1015D00000000000D51A00200000000005000000F7 +:1015E000CE0A010800000000941E00200000000048 +:1015F000FA000000DD0A010800000000961E00202D +:101600000000000064000000EC0A01080000000077 +:10161000951E00200000000064000000FA0A010886 +:1016200000000000A81E00200000000001000000D3 +:10163000090B010803000000921E0020D4FEFFFFEA +:101640002C010000180B010803000000901E002070 +:10165000D4FEFFFF2C010000260B01080000000053 +:10166000981E00200000000030000000340B01082C +:10167000050000009C1E002000000000010000008A +:10168000430B010805000000A01E00200000000020 +:10169000010000004F0B010805000000A41E0020FF +:1016A00000000000010000005B0B010803000000C7 +:1016B0008E1E0020B0B9FFFF504600006B0B0108E2 +:1016C000000000003C1E002000000000C8000000D8 +:1016D000750B010800000000461E002000000000FD +:1016E000C80000007F0B010800000000501E002011 +:1016F00000000000C8000000890B01080000000085 +:101700003D1E002000000000C8000000940B0108EE +:1017100000000000471E002000000000C80000007C +:101720009F0B010800000000511E00200000000077 +:10173000C8000000AA0B0108000000003E1E0020A7 +:1017400000000000C8000000B40B01080000000009 +:10175000481E002000000000C8000000BE0B010869 +:1017600000000000521E002000000000C800000021 +:10177000C80B0108020000002A1F00200000000022 +:10178000D0070000D60B0108000000002E1F00202B +:101790000000000001000000EB0B01080200000047 +:1017A000301F00200A000000D0070000F90B0108DC +:1017B00002000000321F00200A000000D0070000D5 +:1017C000070C0108000000002D1F00200000000091 +:1017D00064000000150C010800000000341E002009 +:1017E0000000000002000000240C010800000000BE +:1017F000391E002000000000C80000002C0C010869 +:1018000000000000431E002000000000C80000008F +:10181000FB080108000000004D1E00200000000031 +:10182000C8000000340C010800000000381E002031 +:1018300000000000C80000003B0C01080000000090 +:10184000421E002000000000C8000000EA08010855 +:10185000000000004C1E002000000000C800000036 +:10186000420C0108000000003A1E002000000000A9 +:10187000C8000000480C010800000000441E0020C1 +:1018800000000000C80000000D0901080000000071 +:101890004E1E002000000000C80000004E0C010891 +:1018A000050000005C1E0020000000006400000035 +:1018B000560C010805000000681E00200000000012 +:1018C000640000005E0C010805000000741E00208A +:1018D0000000000064000000660C01080500000024 +:1018E000581E002000000000640000006D0C01087C +:1018F00005000000641E00200000000064000000DD +:10190000740C010805000000701E0020000000009B +:10191000640000007B0C010805000000601E002030 +:101920000000000064000000810C010805000000B8 +:101930006C1E00200000000064000000870C0108FD +:1019400005000000781E0020000000006400000078 +:101950008D0C010805000000801E00200000000022 +:101960000A0000009B0C0108050000007C1E0020FE +:10197000000000000A000000A70C010800000000A1 +:101980003B1E002000000000C8000000AD0C010854 +:1019900000000000451E002000000000C8000000FC +:1019A000B30C0108000000004F1E002000000000E2 +:1019B000C8000000B90C0108000000003F1E002014 +:1019C00000000000C8000000C10C01080000000079 +:1019D000491E002000000000C8000000C90C0108DA +:1019E00000000000531E002000000000C80000009E +:1019F000D10C010800000000411E00200000000082 +:101A0000C8000000D70C0108000000004B1E002099 +:101A100000000000C8000000DD0C0108000000000C +:101A2000551E002000000000C8000000524F4C4C22 +:101A30003B50495443483B5941573B414C543B5020 +:101A40006F733B506F73523B4E6176523B4C455621 +:101A5000454C3B4D41473B56454C3B0041524D3B6D +:101A600000414E474C453B00484F52495A4F4E3B70 +:101A7000004241524F3B00564152494F3B004D41BD +:101A8000473B0048454144465245453B0048454197 +:101A90004441444A3B0043414D535441423B00437F +:101AA000414D545249473B0047505320484F4D4504 +:101AB0003B0047505320484F4C443B005041535348 +:101AC000544852553B004245455045523B004C4519 +:101AD000444D41583B004C45444C4F573B004C4C07 +:101AE00049474854533B0043414C49423B00474F10 +:101AF0005645524E4F523B004F53442053573B00E4 +:101B000054454C454D455452593B004155544F5452 +:101B1000554E453B00746564666D6A69736C670079 +:101B20000000004B000000CB61636F736600000093 +:101B3000000000007371727466000000000FC93F5E +:101B4000000F494000CB9640000FC9400053FB40B6 +:101B500000CB164100ED2F41000F49410031624199 +:101B600000537B41003A8A4100CB9641005CA3417F +:101B700000EDAF41007EBC41000FC94100A0D5413E +:101B80000031E24100C2EE410053FB4100F203424A +:101B9000003A0A420083104200CB164200141D4254 +:101BA000005C234200A5294200ED2F420036364258 +:101BB000007E3C4200C74242000F4942A2000000A2 +:101BC000F9000000830000006E0000004E000000DD +:101BD000440000001500000029000000FC00000087 +:101BE0002700000057000000D1000000F5000000B1 +:101BF00034000000DD000000C0000000DB00000039 +:101C00006200000095000000990000003C00000008 +:101C1000430000009000000041000000FE000000B2 +:101C20005100000063000000AB000000DE00000077 +:101C3000BB000000C500000061000000B70000000C +:101C4000240000006E0000003A0000004200000086 +:101C50004D000000D2000000E0000000060000007F +:101C6000490000002E000000EA000000090000000A +:101C7000D1000000920000001C000000FE000000E7 +:101C80001D000000EB0000001C000000B10000007F +:101C900029000000A70000003E000000E80000004E +:101CA0008200000035000000F50000002E0000005A +:101CB000BB0000004400000084000000E9000000B8 +:101CC0009C0000007000000026000000B40000002E +:101CD0005F0000007E0000004100000039000000AD +:101CE00091000000D60000003900000083000000D1 +:101CF0005300000039000000F40000009C000000C8 +:101D0000840000005F0000008B000000BD000000A8 +:101D1000F9000000280000003B0000001F00000048 +:101D2000F800000097000000FF000000DE00000047 +:101D300005000000980000000F000000EF00000008 +:101D40002F000000110000008B0000005A0000006E +:101D50000A0000006D0000001F0000006D00000080 +:101D6000360000007E000000CF00000027000000C9 +:101D7000CB00000009000000B70000004F00000089 +:101D8000460000003F000000660000009E000000CA +:101D90005F000000EA0000002D0000007500000058 +:101DA00027000000BA000000C7000000EB000000A0 +:101DB000E5000000F10000007B0000003D00000095 +:101DC0000700000039000000F70000008A00000052 +:101DD0005200000092000000EA0000006B000000CA +:101DE000FB0000005F000000B10000001F000000C9 +:101DF0008D0000005D00000008000000560000009B +:101E0000030000003000000046000000FC0000005D +:101E10007B0000006B000000AB000000F000000041 +:101E2000CF000000BC000000200000009A0000006D +:101E3000F4000000360000001D000000A9000000B2 +:101E4000E300000091000000610000005E0000005F +:101E5000E60000001B000000080000006500000014 +:101E600099000000850000005F00000014000000E1 +:101E7000A000000068000000400000008D0000008D +:101E8000FF000000D8000000800000004D000000AE +:101E90007300000027000000310000000600000071 +:101EA000060000001500000056000000CA000000F7 +:101EB00073000000A8000000C900000060000000DE +:101EC000E20000007B000000C00000008C00000069 +:101ED0006B00000004000000070000000900000083 +:101EE0000000C93F0000F0390000DA370000A233DB +:101EF0000000842E0000502B0000C2270000D022DA +:101F00000000C41F0000C61B000044176937AC3135 +:101F100068212233B40F14336821A2333863ED3EB5 +:101F2000DA0F493F5E987B3FDA0FC93F002020203F +:101F30002020202020202828282828202020202079 +:101F40002020202020202020202020202088101049 +:101F500010101010101010101010101010040404A5 +:101F60000404040404040410101010101010414163 +:101F70004141414101010101010101010101010151 +:101F80000101010101010101101010101010424265 +:101F90004242424202020202020202020202020221 +:101FA00002020202020202021010101020000000C1 +:101FB0000000000000000000000000000000000021 +:101FC0000000000000000000000000000000000011 +:101FD0000000000000000000000000000000000001 +:101FE00000000000000000000000000000000000F1 +:101FF00000000000000000000000000000000000E1 +:1020000000000000000000000000000000000000D0 +:1020100000000000000000000000000000000000C0 +:1020200000000000000000000000000000000000B0 +:1020300043000000A8010020F8B500BFF8BC08BCB0 +:102040009E467047F8B500BFF8BC08BC9E46704776 +:08205000DDF300083501000872 +:04205800110100086A +:10205C000303010000010100955900080000803FB6 +:10206C000000000000000000DC05DC05DC05DC05E0 +:10207C00DC05DC05DC05DC050000803F010100000F +:10208C000000000000000000000000000100000043 +:10209C000000000000000000020000000000000032 +:1020AC000000000003000000000000000000000021 +:1020BC00000000005C1A0108000000000100000094 +:1020CC00611A01080100000002000000681A0108F2 +:1020DC000200000003000000711A01080300000058 +:1020EC0004000000771A010804000000050000003D +:1020FC007E1A01080500000006000000831A010882 +:10210C0006000000070000008D1A010807000000FF +:10211C0008000000961A01080800000009000000E1 +:10212C009F1A0108090000000A000000A81A010803 +:10213C000A0000000B000000B21A01080B0000009E +:10214C000C000000BC1A01080C0000000D0000007F +:10215C00C61A01080D0000000E000000CE1A01087E +:10216C000E0000000F000000D61A01080F0000003E +:10217C0010000000DE1A0108100000001100000021 +:10218C00E71A01081100000012000000EE1A010805 +:10219C001200000013000000F81A010813000000E0 +:1021AC0014000000001B01081400000015000000C2 +:1021BC000B1B0108150000001600000000000000B9 +:1021CC00FF000000000000000000000001020304FA +:1021DC000607080900127A0000A24A040204060845 +:1021EC0000000000010203040102030406070809B1 +:1021FC00010000002C1F01080000000094040020C6 +:10220C00FC04002064050020000000000000000019 +:10221C0000000000000000000000000000000000B2 +:10222C000000000000000000000000003020010849 +:10223C000000000000000000000000000000000092 +:10224C000000000000000000000000000000000082 +:10225C000000000000000000000000000000000072 +:10226C000000000000000000000000000000000062 +:10227C000000000000000000000000000000000052 +:10228C000000000000000000000000000000000042 +:10229C000000000000000000000000000000000032 +:1022AC0001000000000000000E33CDAB34126DE6CF +:1022BC00ECDE05000B000000000000000000000038 +:1022CC000000000000000000000000000000000002 +:1022DC0000000000000000000000000000000000F2 +:1022EC0000000000000000000000000000000000E2 +:1022FC0000000000000000000000000000000000D2 +:10230C0000000000000000000000000000000000C1 +:10231C0000000000000000000000000000000000B1 +:10232C0000000000000000000000000000000000A1 +:10233C000000000000000000000000000000000091 +:10234C000000000000000000000000000000000081 +:10235C000000000000000000000000000000000071 +:10236C000000000000000000000000000000000061 +:10237C000000000000000000000000000000000051 +:10238C000000000000000000000000000000000041 +:10239C000000000000000000000000000000000031 +:1023AC000000000000000000000000000000000021 +:1023BC000000000000000000000000000000000011 +:1023CC000000000000000000000000000000000001 +:1023DC0000000000000000000000000000000000F1 +:1023EC0000000000000000000000000000000000E1 +:1023FC0000000000000000000000000000000000D1 +:10240C0000000000000000000000000000000000C0 +:10241C0000000000000000000000000000000000B0 +:10242C0000000000000000000000000000000000A0 +:10243C000000000000000000000000000000000090 +:10244C000000000000000000000000000000000080 +:10245C000000000000000000000000000000000070 +:10246C000000000000000000000000000000000060 +:10247C000000000000000000000000000000000050 +:10248C000000000000000000000000000000000040 +:10249C000000000000000000000000000000000030 +:1024AC000000000000000000000000000000000020 +:1024BC000000000000000000000000000000000010 +:1024CC000000000000000000000000000000000000 +:1024DC0000000000000000000000000000000000F0 +:1024EC0000000000000000000000000000000000E0 +:1024FC0000000000000000000000000000000000D0 +:10250C0000000000000000000000000000000000BF +:10251C0000000000000000000000000000000000AF +:10252C00000000000000000000000000000000009F +:10253C00000000000000000000000000000000008F +:10254C00000000000000000000000000000000007F +:10255C00000000000000000000000000000000006F +:10256C00000000000000000000000000000000005F +:10257C00000000000000000000000000000000004F +:10258C00000000000000000000000000000000003F +:10259C00000000000000000000000000000000002F +:1025AC00000000000000000000000000000000001F +:1025BC00000000000000000000000000000000000F +:1025CC0000000000000000000000000000000000FF +:1025DC0000000000000000000000000000000000EF +:1025EC0000000000000000000000000000000000DF +:1025FC0000000000000000000000000000000000CF +:10260C0000000000000000000000000000000000BE +:10261C0000000000000000000000000000000000AE +:04262C00A8010020E1 :0400000508000000EF :00000001FF From bd3d853b61f5bfc38f79c4f5f304d607bdb5a021 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Wed, 28 May 2014 19:10:37 +0100 Subject: [PATCH 10/16] Reorder code to remove not operator and improve readability. --- src/flight_common.c | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/src/flight_common.c b/src/flight_common.c index 2d4e60579d..96b368546e 100644 --- a/src/flight_common.c +++ b/src/flight_common.c @@ -79,7 +79,8 @@ static void pidBaseflight(pidProfile_t *pidProfile, controlRateConfig_t *control // ----------PID controller---------- for (axis = 0; axis < 3; axis++) { // -----Get the desired angle rate depending on flight mode - if (axis == 2) { // YAW is always gyro-controlled (MAG correction is applied to rcCommand) 100dps to 1100dps max yaw rate + if (axis == FD_YAW) { + // YAW is always gyro-controlled (MAG correction is applied to rcCommand) 100dps to 1100dps max yaw rate AngleRate = (float)((controlRateConfig->yawRate + 10) * rcCommand[YAW]) / 50.0f; } else { // calculate error and limit the angle to 50 degrees max inclination @@ -89,14 +90,16 @@ static void pidBaseflight(pidProfile_t *pidProfile, controlRateConfig_t *control errorAngle = autotune(rcAliasToAngleIndexMap[axis], &inclination, errorAngle); } - if (!f.ANGLE_MODE) { //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID + if (f.ANGLE_MODE) { + // it's the ANGLE mode - control is angle based, so control loop is needed + AngleRate = errorAngle * pidProfile->A_level; + } else { + //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID AngleRate = (float)((controlRateConfig->rollPitchRate + 20) * rcCommand[axis]) / 50.0f; // 200dps to 1200dps max yaw rate if (f.HORIZON_MODE) { - // mix up angle error to desired AngleRateTmp to add a little auto-level feel + // mix up angle error to desired AngleRate to add a little auto-level feel AngleRate += errorAngle * pidProfile->H_level; } - } else { // it's the ANGLE mode - control is angle based, so control loop is needed - AngleRate = errorAngle * pidProfile->A_level; } } @@ -151,7 +154,7 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa prop = max(abs(rcCommand[PITCH]), abs(rcCommand[ROLL])); // range [0;500] for (axis = 0; axis < 3; axis++) { if ((f.ANGLE_MODE || f.HORIZON_MODE) && (axis == FD_ROLL || axis == FD_PITCH)) { // MODE relying on ACC - // 50 degrees max inclination + // observe max inclination errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination), +max_angle_inclination) - inclination.rawAngles[axis] + angleTrim->raw[axis]; From dcbb82c8451d5b47a3a0a26808484301ea28dea0 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Wed, 28 May 2014 15:11:29 +0100 Subject: [PATCH 11/16] Update Development.md --- docs/Development.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/Development.md b/docs/Development.md index e5a339c7f7..812cf947d9 100644 --- a/docs/Development.md +++ b/docs/Development.md @@ -22,7 +22,7 @@ All pull requests to add/improve the testability of the code or testing methods 2. Strike a balance between simplicity and not-repeating code. 3. Methods that return a boolean should be named as a question, and should not change state. e.g. 'isOkToArm()' 4. Methods that start with the word 'find' can return a null, methods that start with 'get' should not. -5. Methods should have verb or verb-phrase names, like `deletePage` or `save`. +5. Methods should have verb or verb-phrase names, like `deletePage` or `save`. Variables should not, they generally should be nouns. Tell the system to 'do' something 'with' something. e.g. deleteAllPages(pageList). 6. Keep methods short - it makes it easier to test. 7. Don't be afraid of moving code to a new file - it helps to reduce test dependencies. 8. Avoid noise-words in variable names, like 'data' or 'info'. Think about what you're naming and name it well. Don't be afraid to rename anything. From 4a23491d49ede7ce3fda827206b7cef630fc8403 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Wed, 28 May 2014 20:04:07 +0100 Subject: [PATCH 12/16] Introduce better naming consistency for some union members. remove type prefix from a typedef. Conflicts: obj/cleanflight_OLIMEXINO.hex src/flight_common.c --- obj/cleanflight_NAZE.hex | 14 +++++++------- obj/cleanflight_OLIMEXINO.hex | 12 ++++++------ src/config.c | 8 ++++---- src/config_master.h | 4 ++-- src/flight_autotune.c | 6 +++--- src/flight_common.c | 14 +++++++------- src/flight_common.h | 12 ++++++------ src/flight_imu.c | 6 +++--- src/flight_mixer.c | 12 ++++++------ src/mw.c | 10 +++++----- src/sensors_acceleration.c | 14 +++++++------- src/sensors_acceleration.h | 2 +- src/sensors_compass.c | 6 +++--- src/sensors_compass.h | 2 +- src/serial_cli.c | 4 ++-- src/serial_msp.c | 10 +++++----- 16 files changed, 68 insertions(+), 68 deletions(-) diff --git a/obj/cleanflight_NAZE.hex b/obj/cleanflight_NAZE.hex index 4f92c4a936..70339f6efe 100644 --- a/obj/cleanflight_NAZE.hex +++ b/obj/cleanflight_NAZE.hex @@ -1883,11 +1883,11 @@ :10759000DFF8B4A1069B35F90A20595F801A084428 :1075A000F9F73CFB5A49F9F741FC8346FFF780FEA7 :1075B00030B1584A5146905D5A46FFF711FC834658 -:1075C000DFF888A19AF80320C2B9059B39F90500B4 -:1075D0001A7914325043F9F721FB4A49F9F726FC8E -:1075E0009AF8043081467BB1D8F848105846F9F72C -:1075F00069FB01464846F9F75DFA04E05846D8F8B9 -:107600004410F9F75FFB8146434B0136585FF9F7A9 +:1075C000DFF888A19AF803202AB15846D8F8441069 +:1075D000F9F778FB17E0059B39F905001A791432A1 +:1075E0005043F9F71BFB4749F9F720FC9AF80430A0 +:1075F00081464BB1D8F848105846F9F763FB01466D +:107600004846F9F757FA8146434B0136585FF9F778 :1076100005FB424B0437D968F9F754FB82465146C3 :107620004846F9F745FAF9698346F9F74BFBDFF865 :107630002091049907905846F9F744FBB96AF9F785 @@ -4771,8 +4771,8 @@ :102A0000753701087C370108873701088C370108C2 :102A1000000000004166726F333220434C4920763B :102A2000657273696F6E20322E32204D61792032CB -:102A3000382032303134202F2031333A33363A3592 -:102A400030202D2028636C65616E666C6967687440 +:102A3000382032303134202F2032303A30353A319C +:102A400034202D2028636C65616E666C696768743C :102A50002900417661696C61626C6520636F6D6D00 :102A6000616E64733A0D0A0025730925730D0A001F :102A700053797374656D20557074696D653A2025BE diff --git a/obj/cleanflight_OLIMEXINO.hex b/obj/cleanflight_OLIMEXINO.hex index 2aa427b369..9f2419e87a 100644 --- a/obj/cleanflight_OLIMEXINO.hex +++ b/obj/cleanflight_OLIMEXINO.hex @@ -1463,11 +1463,11 @@ :105B5000FDF722FFDFF8B4A1069B35F90A20595F53 :105B6000801A0844FAF7D2FF5A49FBF7D7F8834660 :105B7000FFF780FE30B1584A5146905D5A46FFF714 -:105B800011FC8346DFF888A19AF80320C2B9059B6F -:105B900039F905001A7914325043FAF7B7FF4A4928 -:105BA000FBF7BCF89AF8043081467BB1D8F848106E -:105BB0005846FAF7FFFF01464846FAF7F3FE04E0BD -:105BC0005846D8F84410FAF7F5FF8146434B0136A2 +:105B800011FC8346DFF888A19AF803202AB1584611 +:105B9000D8F84410FBF70EF817E0059B39F905001B +:105BA0001A7914325043FAF7B1FF4749FBF7B6F8B8 +:105BB0009AF8043081464BB1D8F848105846FAF7A5 +:105BC000F9FF01464846FAF7EDFE8146434B0136A0 :105BD000585FFAF79BFF424B0437D968FAF7EAFFA0 :105BE000824651464846FAF7DBFEF9698346FAF7E2 :105BF000E1FFDFF82091049907905846FAF7DAFFA1 @@ -4107,7 +4107,7 @@ :10008000FF0D0108040E0108000000004166726FB8 :10009000333220434C492076657273696F6E20328B :1000A0002E32204D61792032382032303134202FE9 -:1000B0002031333A33363A3539202D2028636C65A8 +:1000B0002032303A30343A3031202D2028636C65BC :1000C000616E666C696768742900417661696C616C :1000D000626C6520636F6D6D616E64733A0D0A002A :1000E00025730925730D0A0053797374656D2055C6 diff --git a/src/config.c b/src/config.c index 8cc799d3ce..8c6638ebbd 100755 --- a/src/config.c +++ b/src/config.c @@ -60,11 +60,11 @@ profile_t currentProfile; // profile config struct static const uint8_t EEPROM_CONF_VERSION = 70; -static void resetAccelerometerTrims(int16_flightDynamicsTrims_t *accelerometerTrims) +static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims) { - accelerometerTrims->trims.pitch = 0; - accelerometerTrims->trims.roll = 0; - accelerometerTrims->trims.yaw = 0; + accelerometerTrims->values.pitch = 0; + accelerometerTrims->values.roll = 0; + accelerometerTrims->values.yaw = 0; } static void resetPidProfile(pidProfile_t *pidProfile) diff --git a/src/config_master.h b/src/config_master.h index e2cd07d4e5..6efb7ed04a 100644 --- a/src/config_master.h +++ b/src/config_master.h @@ -34,8 +34,8 @@ typedef struct master_t { gyroConfig_t gyroConfig; uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees). - int16_flightDynamicsTrims_t accZero; - int16_flightDynamicsTrims_t magZero; + flightDynamicsTrims_t accZero; + flightDynamicsTrims_t magZero; batteryConfig_t batteryConfig; diff --git a/src/flight_autotune.c b/src/flight_autotune.c index b6cd98d891..a90dab720c 100644 --- a/src/flight_autotune.c +++ b/src/flight_autotune.c @@ -129,10 +129,10 @@ float autotune(angle_index_t angleIndex, const rollAndPitchInclination_t *inclin updatePidIndex(); if (rising) { - currentAngle = DECIDEGREES_TO_DEGREES(inclination->rawAngles[angleIndex]); + currentAngle = DECIDEGREES_TO_DEGREES(inclination->raw[angleIndex]); } else { targetAngle = -targetAngle; - currentAngle = DECIDEGREES_TO_DEGREES(-inclination->rawAngles[angleIndex]); + currentAngle = DECIDEGREES_TO_DEGREES(-inclination->raw[angleIndex]); } #if 1 @@ -244,7 +244,7 @@ float autotune(angle_index_t angleIndex, const rollAndPitchInclination_t *inclin updateTargetAngle(); - return targetAngle - DECIDEGREES_TO_DEGREES(inclination->rawAngles[angleIndex]); + return targetAngle - DECIDEGREES_TO_DEGREES(inclination->raw[angleIndex]); } void autotuneReset(void) diff --git a/src/flight_common.c b/src/flight_common.c index 96b368546e..e3a7a66550 100644 --- a/src/flight_common.c +++ b/src/flight_common.c @@ -35,8 +35,8 @@ pidControllerFuncPtr pid_controller = pidMultiWii; // which pid controller are w void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims) { - rollAndPitchTrims->trims.roll = 0; - rollAndPitchTrims->trims.pitch = 0; + rollAndPitchTrims->values.roll = 0; + rollAndPitchTrims->values.pitch = 0; } void resetErrorAngle(void) @@ -84,7 +84,7 @@ static void pidBaseflight(pidProfile_t *pidProfile, controlRateConfig_t *control AngleRate = (float)((controlRateConfig->yawRate + 10) * rcCommand[YAW]) / 50.0f; } else { // calculate error and limit the angle to 50 degrees max inclination - errorAngle = (constrain(rcCommand[axis] + GPS_angle[axis], -500, +500) - inclination.rawAngles[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here + errorAngle = (constrain(rcCommand[axis] + GPS_angle[axis], -500, +500) - inclination.raw[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here if (shouldAutotune()) { errorAngle = autotune(rcAliasToAngleIndexMap[axis], &inclination, errorAngle); @@ -94,7 +94,7 @@ static void pidBaseflight(pidProfile_t *pidProfile, controlRateConfig_t *control // it's the ANGLE mode - control is angle based, so control loop is needed AngleRate = errorAngle * pidProfile->A_level; } else { - //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID + //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID AngleRate = (float)((controlRateConfig->rollPitchRate + 20) * rcCommand[axis]) / 50.0f; // 200dps to 1200dps max yaw rate if (f.HORIZON_MODE) { // mix up angle error to desired AngleRate to add a little auto-level feel @@ -156,12 +156,12 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa if ((f.ANGLE_MODE || f.HORIZON_MODE) && (axis == FD_ROLL || axis == FD_PITCH)) { // MODE relying on ACC // observe max inclination errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination), - +max_angle_inclination) - inclination.rawAngles[axis] + angleTrim->raw[axis]; + +max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis]; if (shouldAutotune()) { errorAngle = DEGREES_TO_DECIDEGREES(autotune(rcAliasToAngleIndexMap[axis], &inclination, DECIDEGREES_TO_DEGREES(errorAngle))); } - + PTermACC = errorAngle * pidProfile->P8[PIDLEVEL] / 100; // 32 bits is needed for calculation: errorAngle*P8[PIDLEVEL] could exceed 32768 16 bits is ok for result PTermACC = constrain(PTermACC, -pidProfile->D8[PIDLEVEL] * 5, +pidProfile->D8[PIDLEVEL] * 5); @@ -224,7 +224,7 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat } else { // calculate error and limit the angle to max configured inclination errorAngle = constrain((rcCommand[axis] << 1) + GPS_angle[axis], -((int) max_angle_inclination), - +max_angle_inclination) - inclination.rawAngles[axis] + angleTrim->raw[axis]; // 16 bits is ok here + +max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis]; // 16 bits is ok here if (shouldAutotune()) { errorAngle = DEGREES_TO_DECIDEGREES(autotune(rcAliasToAngleIndexMap[axis], &inclination, DECIDEGREES_TO_DEGREES(errorAngle))); diff --git a/src/flight_common.h b/src/flight_common.h index 083b86c1e6..7d42e1d788 100644 --- a/src/flight_common.h +++ b/src/flight_common.h @@ -69,12 +69,12 @@ typedef struct int16_flightDynamicsTrims_s { int16_t roll; int16_t pitch; int16_t yaw; -} int16_flightDynamicsTrims_def_t; +} flightDynamicsTrims_def_t; typedef union { int16_t raw[3]; - int16_flightDynamicsTrims_def_t trims; -} int16_flightDynamicsTrims_t; + flightDynamicsTrims_def_t values; +} flightDynamicsTrims_t; typedef struct rollAndPitchTrims_s { int16_t roll; @@ -83,7 +83,7 @@ typedef struct rollAndPitchTrims_s { typedef union { int16_t raw[2]; - rollAndPitchTrims_t_def trims; + rollAndPitchTrims_t_def values; } rollAndPitchTrims_t; typedef struct rollAndPitchInclination_s { @@ -93,8 +93,8 @@ typedef struct rollAndPitchInclination_s { } rollAndPitchInclination_t_def; typedef union { - int16_t rawAngles[ANGLE_INDEX_COUNT]; - rollAndPitchInclination_t_def angle; + int16_t raw[ANGLE_INDEX_COUNT]; + rollAndPitchInclination_t_def values; } rollAndPitchInclination_t; diff --git a/src/flight_imu.c b/src/flight_imu.c index bc3422bb16..b77acefe29 100755 --- a/src/flight_imu.c +++ b/src/flight_imu.c @@ -327,8 +327,8 @@ static void getEstimatedAttitude(void) // Attitude of the estimated vector anglerad[AI_ROLL] = atan2f(EstG.V.Y, EstG.V.Z); anglerad[AI_PITCH] = atan2f(-EstG.V.X, sqrtf(EstG.V.Y * EstG.V.Y + EstG.V.Z * EstG.V.Z)); - inclination.angle.rollDeciDegrees = lrintf(anglerad[AI_ROLL] * (1800.0f / M_PI)); - inclination.angle.pitchDeciDegrees = lrintf(anglerad[AI_PITCH] * (1800.0f / M_PI)); + inclination.values.rollDeciDegrees = lrintf(anglerad[AI_ROLL] * (1800.0f / M_PI)); + inclination.values.pitchDeciDegrees = lrintf(anglerad[AI_PITCH] * (1800.0f / M_PI)); if (sensors(SENSOR_MAG)) heading = calculateHeading(&EstM); @@ -361,7 +361,7 @@ static void getEstimatedAttitude(void) bool isThrustFacingDownwards(rollAndPitchInclination_t *inclination) { - return abs(inclination->angle.rollDeciDegrees) < DEGREES_80_IN_DECIDEGREES && abs(inclination->angle.pitchDeciDegrees) < DEGREES_80_IN_DECIDEGREES; + return abs(inclination->values.rollDeciDegrees) < DEGREES_80_IN_DECIDEGREES && abs(inclination->values.pitchDeciDegrees) < DEGREES_80_IN_DECIDEGREES; } int32_t calculateBaroPid(int32_t vel_tmp, float accZ_tmp, float accZ_old) diff --git a/src/flight_mixer.c b/src/flight_mixer.c index c4c864e59d..123ffed8cd 100755 --- a/src/flight_mixer.c +++ b/src/flight_mixer.c @@ -450,8 +450,8 @@ void mixTable(void) break; case MULTITYPE_GIMBAL: - servo[0] = (((int32_t)servoConf[0].rate * inclination.angle.pitchDeciDegrees) / 50) + determineServoMiddleOrForwardFromChannel(0); - servo[1] = (((int32_t)servoConf[1].rate * inclination.angle.rollDeciDegrees) / 50) + determineServoMiddleOrForwardFromChannel(1); + servo[0] = (((int32_t)servoConf[0].rate * inclination.values.pitchDeciDegrees) / 50) + determineServoMiddleOrForwardFromChannel(0); + servo[1] = (((int32_t)servoConf[1].rate * inclination.values.rollDeciDegrees) / 50) + determineServoMiddleOrForwardFromChannel(1); break; case MULTITYPE_AIRPLANE: @@ -504,11 +504,11 @@ void mixTable(void) if (rcOptions[BOXCAMSTAB]) { if (gimbalConfig->gimbal_flags & GIMBAL_MIXTILT) { - servo[0] -= (-(int32_t)servoConf[0].rate) * inclination.angle.pitchDeciDegrees / 50 - (int32_t)servoConf[1].rate * inclination.angle.rollDeciDegrees / 50; - servo[1] += (-(int32_t)servoConf[0].rate) * inclination.angle.pitchDeciDegrees / 50 + (int32_t)servoConf[1].rate * inclination.angle.rollDeciDegrees / 50; + servo[0] -= (-(int32_t)servoConf[0].rate) * inclination.values.pitchDeciDegrees / 50 - (int32_t)servoConf[1].rate * inclination.values.rollDeciDegrees / 50; + servo[1] += (-(int32_t)servoConf[0].rate) * inclination.values.pitchDeciDegrees / 50 + (int32_t)servoConf[1].rate * inclination.values.rollDeciDegrees / 50; } else { - servo[0] += (int32_t)servoConf[0].rate * inclination.angle.pitchDeciDegrees / 50; - servo[1] += (int32_t)servoConf[1].rate * inclination.angle.rollDeciDegrees / 50; + servo[0] += (int32_t)servoConf[0].rate * inclination.values.pitchDeciDegrees / 50; + servo[1] += (int32_t)servoConf[1].rate * inclination.values.rollDeciDegrees / 50; } } } diff --git a/src/mw.c b/src/mw.c index 1566dcf57f..acba110590 100755 --- a/src/mw.c +++ b/src/mw.c @@ -267,7 +267,7 @@ void annexCode(void) static uint32_t LEDTime; if ((int32_t)(currentTime - LEDTime) >= 0) { LEDTime = currentTime + 50000; - ledringState(f.ARMED, inclination.angle.pitchDeciDegrees, inclination.angle.rollDeciDegrees); + ledringState(f.ARMED, inclination.values.pitchDeciDegrees, inclination.values.rollDeciDegrees); } } #endif @@ -450,16 +450,16 @@ void loop(void) i = 0; // Acc Trim if (rcSticks == THR_HI + YAW_CE + PIT_HI + ROL_CE) { - currentProfile.accelerometerTrims.trims.pitch += 2; + currentProfile.accelerometerTrims.values.pitch += 2; i = 1; } else if (rcSticks == THR_HI + YAW_CE + PIT_LO + ROL_CE) { - currentProfile.accelerometerTrims.trims.pitch -= 2; + currentProfile.accelerometerTrims.values.pitch -= 2; i = 1; } else if (rcSticks == THR_HI + YAW_CE + PIT_CE + ROL_HI) { - currentProfile.accelerometerTrims.trims.roll += 2; + currentProfile.accelerometerTrims.values.roll += 2; i = 1; } else if (rcSticks == THR_HI + YAW_CE + PIT_CE + ROL_LO) { - currentProfile.accelerometerTrims.trims.roll -= 2; + currentProfile.accelerometerTrims.values.roll -= 2; i = 1; } if (i) { diff --git a/src/sensors_acceleration.c b/src/sensors_acceleration.c index e2abd098ea..421b4df10c 100644 --- a/src/sensors_acceleration.c +++ b/src/sensors_acceleration.c @@ -28,7 +28,7 @@ extern bool AccInflightCalibrationMeasurementDone; extern bool AccInflightCalibrationSavetoEEProm; extern bool AccInflightCalibrationActive; -static int16_flightDynamicsTrims_t *accelerationTrims; +static flightDynamicsTrims_t *accelerationTrims; void accSetCalibrationCycles(uint16_t calibrationCyclesRequired) { @@ -95,8 +95,8 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri accZero_saved[FD_ROLL] = accelerationTrims->raw[FD_ROLL]; accZero_saved[FD_PITCH] = accelerationTrims->raw[FD_PITCH]; accZero_saved[FD_YAW] = accelerationTrims->raw[FD_YAW]; - angleTrim_saved.trims.roll = rollAndPitchTrims->trims.roll; - angleTrim_saved.trims.pitch = rollAndPitchTrims->trims.pitch; + angleTrim_saved.values.roll = rollAndPitchTrims->values.roll; + angleTrim_saved.values.pitch = rollAndPitchTrims->values.pitch; } if (InflightcalibratingA > 0) { for (axis = 0; axis < 3; axis++) { @@ -118,8 +118,8 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri accelerationTrims->raw[FD_ROLL] = accZero_saved[FD_ROLL]; accelerationTrims->raw[FD_PITCH] = accZero_saved[FD_PITCH]; accelerationTrims->raw[FD_YAW] = accZero_saved[FD_YAW]; - rollAndPitchTrims->trims.roll = angleTrim_saved.trims.roll; - rollAndPitchTrims->trims.pitch = angleTrim_saved.trims.pitch; + rollAndPitchTrims->values.roll = angleTrim_saved.values.roll; + rollAndPitchTrims->values.pitch = angleTrim_saved.values.pitch; } InflightcalibratingA--; } @@ -137,7 +137,7 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri } -void applyAccelerationTrims(int16_flightDynamicsTrims_t *accelerationTrims) +void applyAccelerationTrims(flightDynamicsTrims_t *accelerationTrims) { accADC[FD_ROLL] -= accelerationTrims->raw[FD_ROLL]; accADC[FD_PITCH] -= accelerationTrims->raw[FD_PITCH]; @@ -160,7 +160,7 @@ void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims) applyAccelerationTrims(accelerationTrims); } -void setAccelerationTrims(int16_flightDynamicsTrims_t *accelerationTrimsToUse) +void setAccelerationTrims(flightDynamicsTrims_t *accelerationTrimsToUse) { accelerationTrims = accelerationTrimsToUse; } diff --git a/src/sensors_acceleration.h b/src/sensors_acceleration.h index 5a0e50071f..13aaf57dbc 100644 --- a/src/sensors_acceleration.h +++ b/src/sensors_acceleration.h @@ -20,4 +20,4 @@ extern uint16_t acc_1G; bool isAccelerationCalibrationComplete(void); void accSetCalibrationCycles(uint16_t calibrationCyclesRequired); void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims); -void setAccelerationTrims(int16_flightDynamicsTrims_t *accelerationTrimsToUse); +void setAccelerationTrims(flightDynamicsTrims_t *accelerationTrimsToUse); diff --git a/src/sensors_compass.c b/src/sensors_compass.c index 0add266b2f..9b639b776e 100644 --- a/src/sensors_compass.c +++ b/src/sensors_compass.c @@ -33,11 +33,11 @@ void compassInit(void) magInit = 1; } -int compassGetADC(int16_flightDynamicsTrims_t *magZero) +int compassGetADC(flightDynamicsTrims_t *magZero) { static uint32_t t, tCal = 0; - static int16_flightDynamicsTrims_t magZeroTempMin; - static int16_flightDynamicsTrims_t magZeroTempMax; + static flightDynamicsTrims_t magZeroTempMin; + static flightDynamicsTrims_t magZeroTempMax; uint32_t axis; if ((int32_t)(currentTime - t) < 0) diff --git a/src/sensors_compass.h b/src/sensors_compass.h index b163ef58cd..8d4622688e 100644 --- a/src/sensors_compass.h +++ b/src/sensors_compass.h @@ -2,7 +2,7 @@ #ifdef MAG void compassInit(void); -int compassGetADC(int16_flightDynamicsTrims_t *magZero); +int compassGetADC(flightDynamicsTrims_t *magZero); #endif extern int16_t magADC[XYZ_AXIS_COUNT]; diff --git a/src/serial_cli.c b/src/serial_cli.c index 3dd33d85a2..70b94cca55 100644 --- a/src/serial_cli.c +++ b/src/serial_cli.c @@ -242,8 +242,8 @@ const clivalue_t valueTable[] = { { "accxy_deadband", VAR_UINT8, ¤tProfile.accxy_deadband, 0, 100 }, { "accz_deadband", VAR_UINT8, ¤tProfile.accz_deadband, 0, 100 }, { "acc_unarmedcal", VAR_UINT8, ¤tProfile.acc_unarmedcal, 0, 1 }, - { "acc_trim_pitch", VAR_INT16, ¤tProfile.accelerometerTrims.trims.pitch, -300, 300 }, - { "acc_trim_roll", VAR_INT16, ¤tProfile.accelerometerTrims.trims.roll, -300, 300 }, + { "acc_trim_pitch", VAR_INT16, ¤tProfile.accelerometerTrims.values.pitch, -300, 300 }, + { "acc_trim_roll", VAR_INT16, ¤tProfile.accelerometerTrims.values.roll, -300, 300 }, { "baro_tab_size", VAR_UINT8, ¤tProfile.barometerConfig.baro_sample_count, 0, BARO_SAMPLE_COUNT_MAX }, { "baro_noise_lpf", VAR_FLOAT, ¤tProfile.barometerConfig.baro_noise_lpf, 0, 1 }, diff --git a/src/serial_msp.c b/src/serial_msp.c index 04dc0af44c..f1aa8f9fa4 100755 --- a/src/serial_msp.c +++ b/src/serial_msp.c @@ -390,8 +390,8 @@ static void evaluateCommand(void) rxMspFrameRecieve(); break; case MSP_SET_ACC_TRIM: - currentProfile.accelerometerTrims.trims.pitch = read16(); - currentProfile.accelerometerTrims.trims.roll = read16(); + currentProfile.accelerometerTrims.values.pitch = read16(); + currentProfile.accelerometerTrims.values.roll = read16(); headSerialReply(0); break; case MSP_SET_RAW_GPS: @@ -608,7 +608,7 @@ static void evaluateCommand(void) case MSP_ATTITUDE: headSerialReply(6); for (i = 0; i < 2; i++) - serialize16(inclination.rawAngles[i]); + serialize16(inclination.raw[i]); serialize16(heading); break; case MSP_ALTITUDE: @@ -779,8 +779,8 @@ static void evaluateCommand(void) // Additional commands that are not compatible with MultiWii case MSP_ACC_TRIM: headSerialReply(4); - serialize16(currentProfile.accelerometerTrims.trims.pitch); - serialize16(currentProfile.accelerometerTrims.trims.roll); + serialize16(currentProfile.accelerometerTrims.values.pitch); + serialize16(currentProfile.accelerometerTrims.values.roll); break; case MSP_UID: headSerialReply(12); From 695c6a06282a90e4e534bd1006b5bfee6aac1ce2 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Wed, 28 May 2014 19:36:04 +0100 Subject: [PATCH 13/16] Enable writing to EEPROM when using the autotune switch after landing. --- src/mw.c | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/mw.c b/src/mw.c index acba110590..26b41bfcbe 100755 --- a/src/mw.c +++ b/src/mw.c @@ -96,8 +96,7 @@ void updateAutotuneState(void) autoTuneWasUsed = true; } else { if (havePidsBeenUpdatedByAutotune()) { - //writeEEPROM(); - blinkLedAndSoundBeeper(5, 50, 1); + saveAndReloadCurrentProfileToCurrentProfileSlot(); autotuneReset(); } } From b712e8e325d65f750a6d9a2b6ca697cfa1fd0dcc Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Wed, 28 May 2014 19:40:54 +0100 Subject: [PATCH 14/16] Updating NAZE binary with autotune eeprom write enable. --- obj/cleanflight_NAZE.hex | 1404 +++++++++++++++++++------------------- 1 file changed, 702 insertions(+), 702 deletions(-) diff --git a/obj/cleanflight_NAZE.hex b/obj/cleanflight_NAZE.hex index 70339f6efe..3912e892d1 100644 --- a/obj/cleanflight_NAZE.hex +++ b/obj/cleanflight_NAZE.hex @@ -2,7 +2,7 @@ :1000000000500020C9110008791200089D55000811 :100010007912000879120008791200080000000027 :10002000000000000000000000000000791200083D -:10003000791200080000000079120008C96B00085E +:10003000791200080000000079120008C56B000862 :100040007912000879120008791200087912000864 :10005000791200087912000879120008CD2D0008E5 :100060007912000879120008791200087912000844 @@ -332,11 +332,11 @@ :1014A000A821682001F03EFA9DF800209DF8013047 :1014B00043EA022323809DF802209DF8033043EA8B :1014C000022363809DF804209DF8053043EA02233F -:1014D000A38002B010BD000008B5642005F0A7FB92 +:1014D000A38002B010BD000008B5642005F0A5FB94 :1014E00068202321F02201F013FA10B9032005F03F -:1014F0003BFC052005F09BFB044B68201A7820215B +:1014F00039FC052005F099FB044B68201A7820215F :1015000042F00F02BDE8084001F002BA02060020D6 -:1015100037B5054619200C4605F089FB0DF1070388 +:1015100037B5054619200C4605F087FB0DF107038A :1015200068200F21012201F0FDF99DF80730D32B2F :1015300015D10C4B4E2C2B600B4B6B600B4BEB60A7 :101540000B4B06D05D2C08D0362C14BF0022402255 @@ -369,12 +369,12 @@ :1016F00000209DF8013043EA022323809DF8022058 :101700009DF8033043EA022363809DF804209DF88E :10171000053043EA0223A38002B010BD08B51920AA -:1017200005F085FA68201521002201F0F1F810B9C2 -:10173000032005F019FB0C4B16211A78682042F0A3 +:1017200005F083FA68201521002201F0F1F810B9C4 +:10173000032005F017FB0C4B16211A78682042F0A5 :10174000180201F0E5F817210022682001F0E0F806 :101750003D210122682001F0DBF8BDE80840682047 :101760003E21012201F0D4B80000002038B5054622 -:1017700019200C4605F05BFA68201521002201F0C3 +:1017700019200C4605F059FA68201521002201F0C5 :10178000C7F818B3124B622C2B60124B6B60124BD4 :10179000AB60124BEB60124B0FD004D80A2C12D066 :1017A000142C0ED00BE0BC2C04D0B4F5807F06D1F5 @@ -391,14 +391,14 @@ :10185000682001F067F89DF800209DF8013043EA08 :10186000022323809DF802209DF8033043EA0223DF :1018700063809DF804209DF8053043EA0223A3808D -:1018800002B010BD07B5232005F0D1F968207521FD +:1018800002B010BD07B5232005F0CFF968207521FF :1018900001220DF1070301F045F828B19DF807007A :1018A000B0F168035842584103B05DF804FB0000F2 :1018B00007B54FF40053ADF8043002238DF807301C :1018C00004238DF806301C4B1C4A1B68934201D13F :1018D0001B4803E01B4A934203D11B4801A901F0B6 :1018E000A9F96B218022682001F012F8052005F08B -:1018F0009EF919210022682001F00AF86B210322C9 +:1018F0009CF919210022682001F00AF86B210322CB :10190000682001F005F837210222682001F000F874 :101910000E4B1A211A78682000F0FAFF1B211822BA :10192000682000F0F5FF1C211022682000F0F0FF75 @@ -410,7 +410,7 @@ :1019800086069DF80930174C03F001031E4306D06C :10199000012E01D1002317E0022E0CD113E00DF12E :1019A000070368200C21012200F0BCFF9DF80730DE -:1019B00013F00F0303D1052005F0D6F905E0042B41 +:1019B00013F00F0303D1052005F0D4F905E0042B43 :1019C00001D1267001E001232370074B2B60074BE8 :1019D0006B602378002B14BF6E236F232B72384665 :1019E00005B0F0BD04060020E5170008091800083E @@ -479,7 +479,7 @@ :101DD000C7F8109000F067FF0126082304A80494B8 :101DE0008DF815308DF814808DF816600BF0A0FE7C :101DF00028238DF80C3003A80F238DF80D308DF8B3 -:101E00000E308DF80F600BF0EDFF142004F00FFF83 +:101E00000E308DF80F600BF0EDFF142004F00DFF85 :101E100032460DF107037720D02100F083FD9DF8B5 :101E20000730444C0322552BE375228418BFC7F8B2 :101E3000149073D1D12132460DF10703772000F0C1 @@ -530,9 +530,9 @@ :1021000000F006BC444BF7B51A68444B04469A42AB :102110000FD0434D02234FF400568DF80730284668 :10212000102301A9ADF804608DF8063000F082FD9F -:102130006E610A2004F07BFD7720A02101220DF1C1 +:102130006E610A2004F079FD7720A02101220DF1C3 :10214000030300F0EFFB002863D01E21012277205B -:1021500000F0DEFB4FF42F6004F05EFD0025A5F1DA +:1021500000F0DEFB4FF42F6004F05CFD0025A5F1DC :1021600060010026022201AB7720C9B28DF804601D :102170008DF8056000F0D6FB9DF804209DF8053031 :1021800043EA0223274AAB520235102DE7D1D78903 @@ -620,11 +620,11 @@ :1026A000ADF804508DF806308DF8077000F0C2FACE :1026B0001423204602A9ADF80850C6F800808DF812 :1026C0000B708DF80A3000F0B5FA25610825384CFA -:1026D000A3685B0503D40A2004F09EFAF7E74FF4E1 -:1026E00080670A20676104F097FA013D27610A209C -:1026F00004F092FA15F0FF05E9D14FF40068C4F830 -:1027000014800A2004F088FA67610A2004F084FA31 -:1027100027610A2004F080FA4FF44063C4F8108067 +:1026D000A3685B0503D40A2004F09CFAF7E74FF4E3 +:1026E00080670A20676104F095FA013D27610A209E +:1026F00004F090FA15F0FF05E9D14FF40068C4F832 +:1027000014800A2004F086FA67610A2004F082FA35 +:1027100027610A2004F07EFA4FF44063C4F8108069 :10272000ADF80830022302A98DF80B3020461C2397 :102730008DF80A3000F07EFA30680CF027F802A815 :102740000CF0ACF82A4630684FF440710CF0E4F815 @@ -683,16 +683,16 @@ :102A90008053ADF8043002238DF8073004238DF8FD :102AA00006305E480DEB030108E05D4A934207D112 :102AB00004A94FF480435B4821F80C3D00F0BAF8BC -:102AC000322004F0B4F8002111221E20FFF720FF6D -:102AD000012160221E20FFF71BFF642004F0A7F8ED +:102AC000322004F0B2F8002111221E20FFF720FF6F +:102AD000012160221E20FFF71BFF642004F0A5F8EF :102AE00002A8FFF793FF00240A2527462646022165 -:102AF00001221E20FFF70CFF322004F098F802A8F4 +:102AF00001221E20FFF70CFF322004F096F802A8F6 :102B0000FFF784FFBDF90820BDF90A10BDF90C30AC :102B100014449142B8BF0A461E449A42B8BF1346B5 :102B200013F5805F0F4409DD3C4B013DDA6882F00C :102B30001002DA60DBD14FF0010801E04FF000082D :102B40001E2000211222FFF7E3FE0A2502210122A6 -:102B50001E20FFF7DDFE322004F069F802A8FFF71F +:102B50001E20FFF7DDFE322004F067F802A8FFF721 :102B600055FFBDF90820BDF90A10BDF90C30A41AB3 :102B70009142B8BF0A46F61A9A42B8BF134613F5F7 :102B8000805FC1EB070707DD244B013DDA6882F067 @@ -702,7 +702,7 @@ :102BC00020F0004068603046FEF728F801461848BB :102BD000FEF72CF920F00040A860002170221E2092 :102BE000FFF796FE012120221E20FFF791FE1E20F6 -:102BF00002210022FFF78CFE642004F018F8B8F1DF +:102BF00002210022FFF78CFE642004F016F8B8F1E1 :102C0000000F04D14FF07E532B606B60AB6004B0BB :102C1000BDE8F0819401002000127A00000C014010 :102C2000001BB7000010014000406F460400002068 @@ -727,8 +727,8 @@ :102D5000010318BF18468DF805308DF8060001AB49 :102D60006D20FF210322FFF779FD0023237004B0BB :102D700070BD00BF6A060020422100200E4B0F4AA2 -:102D80009B68128810B51A420D4C03D003F024FF43 -:102D900020600BE003F020FF2368984206D9094A1F +:102D80009B68128810B51A420D4C03D003F022FF45 +:102D900020600BE003F01EFF2368984206D9094A21 :102DA000C31A12683B2193FBF1F31360064BBDE895 :102DB000104018680AF004BF000C01406E060020A5 :102DC000800600207C06002074060020FFF7D6BF96 @@ -742,12 +742,12 @@ :102E40000120FFF730FF20680AF0BAFE236802A8CD :102E50000293012400238DF80C308DF80E408DF87C :102E60000D800AF065FE2B780D4A59B203F01F035E -:102E70009C40490942F8214003F0C8FE094B3C3808 +:102E70009C40490942F8214003F0C6FE094B3C380A :102E8000186004B0BDE8F0816C0600206E060020DA :102E9000740600207106002070060020000C01401E -:102EA00000E100E07806002038B5044603F0AEFEED +:102EA00000E100E07806002038B5044603F0ACFEEF :102EB000084B19683C3188420BD31860064D074B0C -:102EC0000B201C602B88064C236103F0A5FE2B8889 +:102EC0000B201C602B88064C236103F0A3FE2B888B :102ED000636138BD780600206C0600207C06002067 :102EE000000C01402DE9F843C3794278002B0446D9 :102EF00014BF0223002302B10133344A002552F8E3 @@ -850,7 +850,7 @@ :10350000E162256201A9E561A5626562A4F8425203 :10351000A4F844528DF80630C4F808900223A7712D :103520008DF80730FFF786FB206BFFF7A3FF4146BE -:103530002046FFF78FFF322003F079FB1A4BD4F8B7 +:103530002046FFF78FFF322003F077FB1A4BD4F8B9 :1035400034811B681D46B5FBF9F1B1F5803F03D30B :10355000012DF8D96D08F6E7144A4046B3FBF2F2A4 :1035600089B2D2B200F08CFC40463146104A00F0DD @@ -1016,7 +1016,7 @@ :103F60009A4207D3064A1268907898428CBF002084 :103F70000120704700207047881B00208A1B00200A :103F8000740C0020114B70B51860202500241E46CB -:103F90000020FDF761FD04440A2002F048FE013DC7 +:103F90000020FDF761FD04440A2002F046FE013DC9 :103FA000F6D1C4F34F10FFF797FF316801234C7827 :103FB0002246904203D30133062B2244F9D1044A0E :103FC00013708A785343034A138070BD740C002029 @@ -1060,20 +1060,20 @@ :1042200049FC296A07463046FCF74CFD01463846F2 :10423000FCF740FC0AF082FCA080BDE8F88300BFD8 :10424000B00C0020110000208C0C002070B5144D23 -:1042500006462B78134CABB102F0D8FC23683344EC -:1042600098421CD30020287002F08EFC02F0CEFC95 +:1042500006462B78134CABB102F0D6FC23683344EE +:1042600098421CD30020287002F08CFC02F0CCFC99 :104270000D4B20601A780AB1013A1A700B4B0122DB -:104280001A7070BD02F0C2FC23683233984206D324 -:104290000120287002F078FC02F0B8FC206070BDAC +:104280001A7070BD02F0C0FC23683233984206D326 +:104290000120287002F076FC02F0B6FC206070BDB0 :1042A000B70C0020C40C0020B90C0020B80C002072 :1042B00073B5234D8DF807302B788DF8062002AAB0 :1042C0008DF804008DF805101A4412F8042C443AB5 :1042D000D2B20A2A2CD81B49022B31F8124003D83B :1042E00014B12046FFF7B2FF2B78022B0BD9164BE7 -:1042F0001E6802F08BFC001B864204D2104A002389 +:1042F0001E6802F089FC001B864204D2104A00238B :104300001370124A1370124B1A78012A1A4600D001 :104310009CB92B78022B02D8094901330B700D4B45 -:1043200000201070187002B0BDE8704002F02CBC84 +:1043200000201070187002B0BDE8704002F02ABC86 :10433000022B4FF03204D4D9D6E702B070BD00BFD3 :10434000BB0C00207C200108C40C0020B90C00200C :10435000B80C0020B70C0020014B1860704700BF5C @@ -1093,7 +1093,7 @@ :1044300002464D23EBE725B153204D210A46442384 :10444000E5E7104B5B7C1BB153204D210246DDE7B5 :104450000D4B1B7823B13220BDE8F047FFF7F6BEC5 -:104460000A4B28461D70BDE8F04702F08DBB00BF27 +:104460000A4B28461D70BDE8F04702F08BBB00BF29 :1044700035220020B60C0020BC0C0020C00C00200F :10448000BA0C002023220020B90C0020B70C002019 :10449000014B1870704700BFB90C00200F4B1A7801 @@ -1108,13 +1108,13 @@ :10452000002007F0FBF84FF4E1336360A360E36021 :1045300023615223E070237510BD000030B51F4C7D :104540001F4D85B0204605F029FF2946204605F07D -:104550003FFF05F1240002F049F905F1680006F07B -:1045600007FC14F8500C03F0C7F904F1A60004F09E +:104550003FFF05F1240002F047F905F1680006F07D +:1045600007FC14F8500C03F0C5F904F1A60004F0A0 :104570006DFDA4F14C0005F02FFC04F19A0000F051 -:10458000ABFE05F1280001F09DFF05F14B03009300 +:10458000ABFE05F1280001F09BFF05F14B03009302 :1045900005F13803019304F1A403029304F15A00D6 :1045A000A91D2A4604F1A20303F0ECFF04F1140054 -:1045B00005B0BDE8304001F08BBF00BF28200020CF +:1045B00005B0BDE8304001F089BF00BF28200020D1 :1045C0005C1C002008B5054B4FF4827202FB0030E2 :1045D000034900F59E70FCF781FD08BD8C1B00208F :1045E000D81F0020F8B5274B46221A7040F24C42E3 @@ -1126,7 +1126,7 @@ :10464000FC322046116809F0E7FF0428054607D030 :10465000E7E7204609F0C2FF04280546ECD0E0E772 :104660000A4B04349C42E4D109F084FF042D02D1AA -:10467000FFF714FF20B90A20BDE8F84002F074BB30 +:10467000FFF714FF20B90A20BDE8F84002F072BB32 :10468000F8BD00BF8C1B002000F801084CFC01089D :10469000034B9B6818420CBF00200120704700BFED :1046A0008C1B0020024B9A6810439860704700BF33 @@ -1161,7 +1161,7 @@ :104870005460A3644D4B84F85560E364412384F88D :10488000513084F85660019AA062C4F834A004F153 :104890005C00A4F8582084F8529084F8536002F029 -:1048A000EBFC042384F86030152384F86430404B1B +:1048A000E9FC042384F86030152384F86430404B1D :1048B000C4F868A0E3663F4B3F48236705F5847161 :1048C000A4F85A6084F8617084F8627084F8748087 :1048D00005F040FF4FF44873A4F8A630C82384F8CD @@ -1196,7 +1196,7 @@ :104AA000094805F0D9FC094806F0B6FF074806F0AA :104AB00031FF20B90548BDE81040FFF723BD10BD08 :104AC0008C1B002008000100941C0020AC1C00205E -:104AD00007B5FFF7E3FC10B90A2002F045F9104BC7 +:104AD00007B5FFF7E3FC10B90A2002F043F9104BC9 :104AE0001049184640F24C42FCF7F8FA90F8482476 :104AF000022A84BF002280F8482490F848144FF41A :104B0000827202FB0101084801F59E71FCF7E6FA8A @@ -1225,7 +1225,7 @@ :104C700013F8011B09B9154603E0002AFBDD013AD0 :104C8000F6E7002D04DD30464146B847013DF8E720 :104C900014F8011B11B13046B847F9E7BDE8F081BF -:104CA000014B186801F032BFD00C00202DE9F0470D +:104CA000014B186801F030BFD00C00202DE9F0470F :104CB00088B006460F4603921C46039A531C039382 :104CC0001178002900F08D80252901D0304686E03A :104CD0000023911C049303915578302D05D1D31CEA @@ -1247,7 +1247,7 @@ :104DD000251DFFF741FF2C466FE730462946B847AF :104DE0006BE708B0BDE8F0870FB407B50A4904AB1C :104DF00008680A4953F8042B09680193FFF756FF26 -:104E0000074B186801F0A1FE0028F9D003B05DF847 +:104E0000074B186801F09FFE0028F9D003B05DF849 :104E100004EB04B0704700BFCC0C0020C80C00208D :104E2000D00C0020034A044B1A60044B00221A6085 :104E3000704700BFA14C0008C80C0020CC0C00201B @@ -1323,7 +1323,7 @@ :1052900073700E4B1A680E4B5189198051895980D1 :1052A00052899A800B4A12685288DA80E388013367 :1052B000E380FFF7BFFF00B91DB9BDE8704000F003 -:1052C000BDBB70BDD80C002023220020E80C0020BC +:1052C000BBBB70BDD80C002023220020E80C0020BE :1052D0007E220020E40C0020024B00221860024BCA :1052E0009A807047E40C0020D80C0020044B186012 :1052F0000448054B03600023C3800372704700BF5E @@ -1335,15 +1335,15 @@ :1053500000221A70BDE81040FFF7D8BF10BD00BF93 :10536000D40C0020E40C0020F0B57E4C87B0FFF791 :1053700059FDFFF727FBFFF7ABFBA07B003018BF01 -:10538000012001F05FFC4FF40030FFF781F906AB1C +:10538000012001F05DFC4FF40030FFF781F906AB1E :1053900003F8140D1846FCF76DFB0220FFF778F9AF :1053A00018B104F58270FEF7EDFD6F486F4DFEF702 :1053B00013FE0E2004F0C6FF6D48B4F8EE1094F80A -:1053C000ED20B5F95A3001F0E1FA2F4610B903206B -:1053D00001F0CAFC674B10225A6108221A610A26A2 +:1053C000ED20B5F95A3001F0DFFA2F4610B903206D +:1053D00001F0C8FC674B10225A6108221A610A26A4 :1053E000644D1920EB68013E83F01003EB60EB681D -:1053F00083F00803EB6001F01AFC012001F0C4FB0C -:10540000192001F014FC002001F0BEFB16F0FF068D +:1053F00083F00803EB6001F018FC012001F0C2FB10 +:10540000192001F012FC002001F0BCFB16F0FF0691 :10541000E6D108232B6110232B6102F0FDFA60799D :10542000554903F013F9FEF74FFD544806F086FB8B :1054300063790E2B01D0082B03D101238DF80F3097 @@ -1361,582 +1361,582 @@ :1054F0008470316804F0EAFF4FF48070FFF7C8F859 :1055000040B1204A05F5907095F81D11A2F1F20303 :1055100004F0B2FC4FF48060FFF7BAF808B101F074 -:10552000E1FA4FF40060FFF7B3F808B105F0A8FC0A -:1055300001F052FB144B18606379052B03D14FF433 -:10554000C87000F0A7FE4FF47A7001F055F9C8203A -:1055500000F0CEFF0D4B01225A7300225A7007B0A3 +:10552000DFFA4FF40060FFF7B3F808B105F0A8FC0C +:1055300001F050FB144B18606379052B03D14FF435 +:10554000C87000F0A5FE4FF47A7001F053F9C8203E +:1055500000F0CCFF0D4B01225A7300225A7007B0A5 :10556000F0BD00BF8C1B0020721C0020D81F002043 :105570006E1C0020000C01409C1B0020AC1C002075 :10558000DC200020CE200020F80C00202322002068 -:1055900008B5FFF7E9FE00F077FAFCE708B5034B22 +:1055900008B5FFF7E9FE00F075FAFCE708B5034B24 :1055A000B3F9D40003F06EF9FEE700BF8C1B0020B6 -:1055B00038B51A4B1A4C5D7D637C15B36BBBA37871 -:1055C0009BB101F003FC174D08B92B781BB101F01A -:1055D00075FD00232B70144810F8041C01F08CFD9D -:1055E0000123124A6374137038BD01F035FEA0B177 -:1055F00005203221012208F063F9BDE8384001F0AE -:105600005DBD13B101F0E6FD6574A3782BB9074BBE -:105610001B7813B1034B01221A7038BD35220020CC -:1056200023220020200D0020DC1F0020060D00207A -:1056300008B5022004F07CFE18B900F031FE28B94C -:105640000AE000F04BFF0028F7D108BD01F0DAF8BE -:1056500080F00100C0B205E0022004F069FE0028DD -:10566000F4D0012000F0010008BD0000054B1A68CD -:105670003AB900F5F42000F590701860024B08224A -:105680005A6170471C0D0020000C0140034B0022A2 -:105690001A60034B08221A61704700BF1C0D0020DE -:1056A000000C0140084A136863B1C01A002809DBE6 -:1056B000064903F5F423C86803F5907380F00800E9 -:1056C000C8601360704700BF1C0D0020000C014033 -:1056D000A94B2DE9F04FB3F90600A84B85B0B3F8FC -:1056E000582090420FDBB0F5FA6F93F8564007DA76 -:1056F000811A4C43A2F5FA6294FBF2F4643403E09D -:10570000C4F1640400E064249D4A93F85410B2F894 -:1057100012C192F9EC2093F8A25093F8A360524280 -:1057200093F8553092B201910021029203930A46F8 -:10573000914B40F2E637CB5E0093CCEB030303F2D0 -:10574000F31EBE4503D8002BB8BF5B4201E04FF407 -:10575000FA73022ADFF834822CD025B1AB42CCBFD9 -:10576000C5EB030300236427DFF848A293FBF7FE91 -:105770006FF0630B3AF81E900BFB0E3B0EF1010E1F -:105780003AF91EA00FFA89FECEEB0A0E0EFB0BFEB5 -:105790009EFBF7FECE4428F801E0DDF8048003FB11 -:1057A00008FE784B9EFBF3F33B449BB2634393FBB1 -:1057B000F7F714E026B1B342CCBFC6EB03030023D6 -:1057C000DDF808E003FB0EF7A8F80470039F002B38 -:1057D000B8BF5B427B436B4F93FBF7F76437674B74 -:1057E000DFF8D48102EB030E9EF80490642307FBDC -:1057F00009F999FBF3F902F808909EF80E909EF8CB -:1058000018E007FB09F907FB0EF7DFF8B08199FBF9 -:10581000F3F902F80890DDF8008097FBF3F35A4F94 -:10582000E045D355594F02DA7B5A5B427B52013235 -:10583000032A01F102017FF47BAF514C4FF4FA626D -:10584000B4F81411FFF790F9B4F814314FF47A74E6 -:10585000C01A4443C3F5FA63B4FBF3F464214C4823 -:1058600094FBF1F36FF0630630F8132006FB03445A -:10587000013330F9130013B2C31A5C4394FBF1F106 -:10588000444C0A44637A414DFA80002B38D0424B95 -:105890001888424B1B88C01A00B2FFF7CDF90646A4 -:1058A00009F016F90746304609F086F90646B5F9BB -:1058B0000200FBF7B3F98046B5F90000FBF7AEF93B -:1058C00039468146FBF7FEF9314682464046FBF7F2 -:1058D000F9F901465046FBF7EBF8FBF7B9FB3946FF -:1058E00028804046FBF7EEF9314607464846FBF76D -:1058F000E9F901463846FBF7DDF8FBF7A9FB6880BC -:105900000220FEF7C5FE264D88B1264A13780133E2 -:10591000DBB213700622B3FBF2F102FB113313F07A -:10592000FF0F04D1FEF7F6FAFEF716FB2870287871 -:10593000003018BF0120FEF715FDA3781BB11A4BEC -:1059400008225A6142E0FFF773FE20B1164BDA6875 -:1059500082F00802DA6001232370637B0BB90D4AE1 -:105960001370124B5B7D0BB1002323702378104D15 -:1059700033B3FFF78BFE26E07E220020D81F0020E5 -:105980008C1B00200CFEFFFF3B2100204C2200203E -:10599000542200202322002042210020EA2000205F -:1059A000EC0C0020FC0C0020000C014035220020F3 -:1059B000F00C00206C2200203E2100203821002025 -:1059C0002868FFF753FE2868FFF76CFE05F038FAE9 -:1059D0008020FEF75DFEA8B1134B144A1B681168C6 -:1059E000591A00290EDB03F543435033A0781360A6 -:1059F0000F4B003018BF0120B3F90210B3F900209B -:105A0000FDF766F906F0AAF8202004F091FC18B121 -:105A1000054B186804F018FC064B9B680BB1064850 -:105A2000984705B0BDE8F08FF00C0020000D002075 -:105A3000281000201C210020E0200020024B9A7832 -:105A40000AB100229A707047232200200B4B19786C -:105A50001A4651B1997879B9597831B901229A70B9 -:105A6000074B1A88074B1A807047937823B9022096 -:105A7000FF21012207F024BF704700BF232200202E -:105A800042210020EA2000202DE9F84F904F04F039 -:105A900067FD386804F08CFD8E4C002800F03F82D2 -:105AA000386804F035FE4FF48040FEF7F1FD20B178 -:105AB000894B1B780BB9FFF7C1FF386804F0CCFEA7 -:105AC0004FF40070FEF7E4FD90B1814B834D1A68EE -:105AD000834B9A4208D92B681B681B6A984718B9F0 -:105AE0002B681B685B6A98472B681B685B69984743 -:105AF0000022B4F81451B4F81661134679489B0893 -:105B0000115E0232A942C4BF63F07F03DBB2B1422F -:105B1000B8BF43F04003082A8146EFD1724EDFF848 -:105B2000E48132789A4205D198F80020F92A04D805 -:105B3000013200E0002288F800204FF480403370EA -:105B4000FEF7A6FD58B1B4F81211B4F8DC20B9F98B -:105B50000630881A834202DD0A4493420ADB4FF47E -:105B60008040FEF795FDC8B9B9F90620B4F81431A4 -:105B70009A4213DA01F084FB01F08AFB5B4BB3F825 -:105B800076305BB1544B1A78594B002A00F03B83B6 -:105B90001A78002A00F03783FFF758FF98F8003092 -:105BA000142B40F0C380524B504D93F802B09A46EC -:105BB000BBF1000F18D0B5F8763023B933785F2BDE -:105BC00001D1FFF73BFF94F81A31002B00F0AE80B3 -:105BD000B5F87630002B40F0A98033787D2B40F06B -:105BE000A580FFF72BFFA1E03378572B18D14FF496 -:105BF0007A7000F001FE4FF48070FEF749FD08B1A5 -:105C000003F08CFA042004F093FB10B10A2000F09A -:105C10006FFC082004F08CFBF0B9364B18801BE0B9 -:105C20000420FEF735FDB8B12F4B1B785A2B13D14A -:105C3000314B1A782AB183F800B0304B01221A7028 -:105C40000AE02F4A137883F0010313700BB102208E -:105C500000E00320FEF71CFC33785D2B00F0DA82B5 -:105C60005B2B00F0D9825E2B00F00083B5F8763014 -:105C70002BB932786F2A02D1FFF7E8FE13E094F8CF -:105C80001A211AB113B933787E2BF5D03378972BBC -:105C900004D14FF4C87000F0FDFA04E0A72B04BF54 -:105CA00001238AF80E303378BB2B03D1B5F85E3070 -:105CB000023304E0B72B05D1B5F85E30023BA5F8FE -:105CC0005E3028E0BE2B1FD1B5F85C30023320E0F7 -:105CD000F00C00208C1B002035220020DC2000204E -:105CE000404B4C007E220020040D0020D81F0020D5 -:105CF0002322002042210020210D0020100D002031 -:105D0000F50C0020220D0020BD2B0FD1B5F85C3022 -:105D1000023BA5F85C3094F84804FEF753FCFEF70C -:105D200061FCFEF703FF002388F800300420FEF733 -:105D3000AFFC48B37E4A7F4B117871B17E498978B8 -:105D400059B1B9F90600B4F81411884205DD197883 -:105D500019B97A483225058011705B7C53B1784BB4 -:105D60001A782AB9774A127812B9744A3221118006 -:105D7000012208E0734B1A7832B16F4A92781AB94F -:105D80001A70714B01221A7070480123002230F8FA -:105D9000021F5E1EA1F21555B5F5C77F8CBF002509 -:105DA00001259D4009B22A4340F21355A942CCBFB8 -:105DB00000250125B5402A4340F2A465A942D4BF7D -:105DC000002101215D1CA94003330A430D2B92B22F -:105DD000DDD100235E49574E01EB4301B1F8761047 -:105DE0000A420CBF0021012199550133162BF1D134 -:105DF0007378514D23B1022004F09AFA68B914E087 -:105E00004FF40070FEF744FC78B1524B1B681B68DE -:105E10009B6898470028EED107E0EB783BB901F08A -:105E20002FFA454B0122DA7001E00023EB70B378C2 -:105E30004BB10023EB702B7933B901F021FA3E4BC3 -:105E400001221A7100E02B71EA78434B12B93A4AE9 -:105E5000127912B110225A6101E010221A61042055 -:105E600004F066FA10B3F3788BB1AB7983B9324A98 -:105E700001219171394A1168394A1160394AD18832 -:105E8000394A1180394A1360394A136000E0AB7116 -:105E90004FF40050FEF7FCFB40B133792BB1EB7BA4 -:105EA00023B9254B0122DA7300E0EB73022004F0E2 -:105EB0003FFA10B1737933B90FE0082004F038FAD3 -:105EC0000028F7D119E06B7943B91B4B01225A71B5 -:105ED000284B1A88284B1A8000E06B71B3792BB1DC -:105EE0006B7A23B9144B01225A7200E06B72F3797A -:105EF0001BB1204B1A88214B1A80202004F018FA7D -:105F000008B104F045F9337B03B10123AB72637927 -:105F1000082B01D00E2B6BD100236B7268E0184D5B -:105F20002B68042B64D8DFE803F02D37424C570070 -:105F3000F50C00203522002023220020240D002013 -:105F4000050D0020210D0020100D002084220020CE -:105F5000D81F0020DC200020000C0140642100201C -:105F6000682100204C2200200C0D0020141000207D -:105F7000C00F00204221002030210020EA20002014 -:105F8000140D0020012308202B6004F0D1F918B172 -:105F9000A24800F0A5FB58BB2B68042001332B60FE -:105FA00004F0C6F918B1386800F0A8FA00BB2B68F5 -:105FB000042001332B6004F0BBF910B102F0DEF9CC -:105FC000B0B92B684FF4807001332B60FEF760FB93 -:105FD00010B103F0C9F80BE0002310202B6004F08F -:105FE000A7F908B100F08CFD4FF40050FEF750FB0C -:105FF00000F0F2FDA2893860894B22B11968411A7C -:106000000029C0F2F2801044186001F02DFFFFF764 -:106010005FFB00F0E1FD834B83491A683860821A08 -:1060200018600A80FFF7C4FA082004F081F97F4E57 -:10603000002830D07E4A9188154601F145039BB275 -:106040008A2B7C4A7C4B24D87C4847790FB31F8825 -:106050001388407BFA1A92B293B21FB2B337BCBF17 -:1060600002F5B4739BB21AB2B32AC4BFA3F5B473DA -:106070009BB294F8EC2070B152B252425343327B3F -:106080001BB253436FF01D0293FBF2F31944A98036 -:1060900001E01B881380042004F04AF9002879D01D -:1060A000664B9A79002A75D01F7C614D002F69D10B -:1060B00096F8A510624896F8A420624BB5F806E061 -:1060C00029B3B0F900000FFA8EF1C0EB010CBCF15E -:1060D000000FB8BFCCF1000C94450FDD8142C8BF62 -:1060E0005242DFF884C11FFA8EFEC8BF92B2CCF8CC -:1060F0000070724401271F70EA804BE01A78002A72 -:1061000034D0514A1F701168504A11602EE0078840 -:106110000FFA8EFC38B2C0EB0C0CBCF1000FB8BF0C -:10612000CCF1000C944518DD494ADFF82081B2F823 -:1061300000C0F444C7EB0C0C0FFA8CFC4FF4FA6E61 -:10614000D8F800709CFBFEF10F440EFB11C11180CA -:106150000122C8F800701A7008E01A7832B13A4A81 -:1061600019701768394A1760394A1180394BB4F8E9 -:10617000D0101B6864311844B4F8D220FEF7F4FC48 -:10618000E88007E0334B6A8894F91C111B6801FB17 -:1061900003236B8096F8A83053B1284BDA780AB9FC -:1061A0001B792BB1224B2C4A1188DA880A44DA80F9 -:1061B000202004F0BDF840B1204BDA790AB91A7AF0 -:1061C0001AB11B7B0BB103F041FF2448244B00F1B3 -:1061D0004C01B4F8F6201D6800F15803A84702F0FE -:1061E00063FB02F0DFFA02F039FB1E4B1B78002B39 -:1061F0004DD14FF40060FEF74BFA002847D0BDE8C0 -:10620000F84F04F067BE9B78002B3FF4C7ACFFF754 -:1062100015FCC3E401222AE0022228E08A1C0020A7 -:10622000080D0020F80C0020180D0020D81F0020B9 -:106230004C22002030210020422100202322002077 -:106240000C0D0020F40C00206421002068210020A7 -:106250000E0D0020C00F0020C80F0020DC1F002002 -:1062600018000020401600201410002003225FFABE -:1062700082FB0BF1FF3384F84834FEF7B3F9FEF7E5 -:1062800027FC022028215A4607F01AFBEEE4BDE85D -:10629000F88F00BF014B1880704700BF320D0020FF -:1062A000034B1888D0F1010038BF0020704700BFB1 -:1062B000320D0020204B00222DE9F0411968804664 -:1062C00013461E4C1E4E25881E4FB5F5C87F04BFD1 -:1062D0000025F550F05832F907C0194D844446F8AE -:1062E00003C0043300260C2BD6538E5202F1020257 -:1062F000E7D12388012B19D12B68404603F1C8024E -:106300004FF4C87392FBF3F20A806A68C83292FBBA -:10631000F3F24A80AA68C83292FBF3F30A4A128861 -:106320009B1A8B8000F0A8FFFEF70AFC2388013B34 -:106330002380BDE8F08100BF340D0020320D002025 -:10634000380D00205C210020120000202DE9F041D2 -:10635000354D04462B88322B0ED1344B1A68344B02 -:10636000118819805188928859809A80314B02880F -:106370001A8042885A8001E0002B34D02B49002239 -:10638000D1F800C013460F46298832292A4904BF94 -:106390000020C8502948CE5832F900804644CE50DB -:1063A000043300210C2B11522CF8021002F10202CE -:1063B000EAD12B88012B13D1214A02201170214AE6 -:1063C0001370FEF765F81A4A3B68118819805188E6 -:1063D000928859809A80174B1A885B882280638044 -:1063E0002B88013B2B80184B1A78DAB11249002216 -:1063F0001A700E4B08681B68322290FBF2F018806E -:10640000486890FBF2F058808968204691FBF2F2D0 -:106410000E490988521A9A8000F02EFFBDE8F0411B -:10642000FEF78EBBBDE8F081240D0020340D002066 -:10643000260D00202E0D0020440D00205C210020A0 -:10644000050D0020210D0020100D0020120000205D -:10645000064B028819888A1A1A80598842888A1A33 -:106460005A80998882888A1A9A8070475C21002015 -:106470000F4B10B55B6804460E4898470E4B0D480D -:106480001A780146FDF73EFE0C4B1B8813B12046DF -:10649000FFF710FF0420FEF7FBF810B12046FFF7CE -:1064A00055FFBDE81040064B1868FFF7D1BF00BF8D -:1064B000EC2000205C2100202C0D0020320D00205B -:1064C000340D0020014B1860704700BF340D0020D0 -:1064D000014B1860704700BF10210020034B188843 -:1064E000D0F1010038BF0020704700BF600D0020D0 -:1064F000014B1880704700BF600D00202DE9F0416E -:10650000224D2B68C31A002B3CDB214E28603378C8 -:10651000204C012B10D123699847636898472B685A -:1065200022881D4813442B601C4963699847002347 -:1065300033700220BDE8F081A3689847E36898476C -:10654000174818490068D1F80080134B0078D3F839 -:1065500000C008F10103834208BF0023124A134818 -:10656000176840F828C050F82300BC44C0EB0C0763 -:106570000B6017602B6862880120134430702B6019 -:10658000BDE8F0810020BDE8F08100BF580D00207B -:106590006C0D0020F82000205C0D0020640D002010 -:1065A00010210020540D0020740D00207C0D0020CF -:1065B000F8B51E4C1E4A236810681B781D4D013B20 -:1065C000B0FBF3F0FAF726FB1B49FAF72FFC1B4947 -:1065D00008F082FB01464FF07E50FAF769FA18493D -:1065E000FAF770FB08F0AAFA236807465C68286887 -:1065F000FAF714FB2146FAF765FB124B06461868BA -:10660000381AFAF70BFB214607464FF07E50FAF78F -:106610004FFA01463846FAF755FB01463046FAF77D -:1066200049FA08F08BFA2860F8BD00BF102100205D -:10663000740D0020700D002080E6C547B1DC423E9D -:10664000D048874A680D002010B5154B154A1B68C5 -:1066500011681878144B01381B68B3FBF0F008235D -:1066600091FBF3F4091B0844106090FBF3F0FAF778 -:10667000D5FA0E49FAF7DAFB0D4908F02DFB014671 -:106680004FF07E50FAF714FA0A49FAF71BFBFAF7B3 -:10669000DFFC094B1860094B1A88013A1A8010BDBB -:1066A00010210020780D0020740D002080E6C547E1 -:1066B000B1DC423ED048874A680D0020600D0020C2 -:1066C00038B5054C10256561FCF7DAF9034B01225A -:1066D00025611A7038BD00BF000C0140530E002028 -:1066E000F8B5374B374D1B682A6804469A1A002ABA -:1066F00063DB03F5C333A03333482B60FCF786F923 -:106700003148324B01461A78FDF7FCFC304B314AD8 -:10671000997B184679B12968002311600021E15264 -:106720000E4629492C4F595AD9532C4FD95302336D -:10673000062BF3D186732A4B1B7863B1224B218839 -:106740001888411A198058886188411A5980988898 -:10675000A188411A99801368002B2CD02A681E4802 -:10676000D31A204A1D49934216D81F4BDA6882F08B -:106770000802DA600023144AC55E9A5A14B2A54290 -:10678000C4BF154D5A53CD5EA542BCBF134C1A531E -:106790000233062BEFD10EE00E4A00231360C55ED4 -:1067A000CA5E2A44022592FBF5F2E2522B44062BE4 -:1067B000F5D1FEF7C5F90120F8BD0020F8BD00BFF6 -:1067C000F00C0020440E002014210020520E002066 -:1067D00023220020480E00203C0E00204C0E0020FA -:1067E000530E00207FC3C901000C0140014B18600B -:1067F000704700BF540E0020014B1880704700BF47 -:10680000580E0020034B1888D0F1010038BF00203B -:10681000704700BF580E00203C4B2DE9F74F5B68D6 -:106820003B4898473B4B3A481A780146FDF76AFCCB -:10683000394B374F1A889846DFF8E8A0002A3CD039 -:10684000364B00251B68364E93F800B02C46B8F83E -:106850000030DFF8D490B3F57A7F05D100233046BD -:1068600049F80430FEF79AF9785F59F80430034488 -:1068700049F80430FAF7D2F901463046FEF791F9AB -:1068800000237B532AF80530B8F80030012B25D1BE -:106890003046FEF7C8F90346BBF1000F0FD058464B -:1068A0000193FAF7BBF9019B01461846FAF7C6FBBC -:1068B00028B1194B4FF47A721A8000231BE059F863 -:1068C00004304FF47A7203F5FA7393FBF2F30A2063 -:1068D0000F2101222AF8053006F0F2FF04340C2CB7 -:1068E00005F1020506F11406B1D1B8F80030013BFC -:1068F000A8F80030E1E7F95A3AF803208A1AFA5268 -:106900000233062BF7D103B0BDE8F08F1C21002025 -:1069100044210020A40E0020580E0020540E002018 -:10692000680E0020EE0F00205C0E002038B50546F2 -:106930000A4C00230A4829462370FBF759F848B946 -:1069400007482946FAF7E4FD20B905482946FAF731 -:106950000DFF08B10123237038BD00BFA40E002035 -:106960001C21002003780BB1054A137043780BB14A -:10697000044A137083780BB1034A1370704700BF49 -:10698000A40E00202C0D0020520E00202DE9F7430C -:106990008146084614469846FFF7C8FF0746002878 -:1069A00000F08A80464E00233370464D072C38D8BD -:1069B000DFE804F0080819242F373704022003F019 -:1069C000C9FC2EE08DF8043001A84FF448733E490D -:1069D000ADF80630FAF7E0FC18B101232B70042360 -:1069E0003370012C1DD03848FAF7B2FF30B10223C2 -:1069F0002B70022C4FF00103337012D03248FAF79B -:106A000027FE30B103232B70032C4FF002033370A9 -:106A100007D02D48FAF722FD18B104232B7001236B -:106A200033702B782BB90CB11C46BBE7022003F066 -:106A300091FC2648FBF766FB30B92448FBF79AF92E -:106A400010B9042003F086FC4846FFF78BFF0220B4 -:106A500003F06EFC10B11C4B1B6898471C4B1B6865 -:106A60009847FBF7BFFF18B11A4B03221A7002E0D8 -:106A7000082003F06FFC082003F05AFC164C054672 -:106A8000C0B1642798FBF7F63046FAF7C7F881469D -:106A900007FB168000B2FAF7C1F81049FAF712F9AD -:106AA00001464846FAF706F80D49FAF70BF92F4662 -:106AB000206001E000232360384603B0BDE8F08386 -:106AC0002C0D0020500D0020EC200020F82000208C -:106AD0001C210020520E0020241000208988883CB0 -:106AE0000000204108B50120FCF774F9102003F0E4 -:106AF00029FC024B00221A6008BD00BF2C21002097 -:106B00000148FCF7D1B900BF2C21002008B503686B -:106B10001B68984708BD38B505460C4614F8011B9C -:106B200019B12846FFF7F2FFF8E738BD08B503684A -:106B30005B68984708BD08B503689B68984708BD1F -:106B400008B50368DB68984708BD08B503681B698A -:106B5000984708BD08B503685B69984708BD000001 -:106B6000034B4FF4805208B15A6170471A61704765 -:106B700000080140034B4FF4805208B11A6170477E -:106B80005A6170470008014008B5024B1B689847DE -:106B900008BD00BFA80E0020064B00201A68064B57 -:106BA0009A4208BF054A064B18BF064A1A60FFF70B -:106BB000EBBF00BF94010020001BB700756B0008FD -:106BC000A80E0020616B0008024B1A6801321A609F -:106BD000704700BFAC0E002010B5094A0949136880 -:106BE0008C6812689342F8D1074A106811684FF414 -:106BF0007A725043001BB0FBF1F002FB030010BDA2 -:106C0000AC0E002010E000E0B00E0020014B186830 -:106C1000704700BFAC0E002038B50446FFF7DCFF1C -:106C20000546FFF7D9FF401BA042FAD338BD10B587 -:106C300004462CB14FF47A70FFF7EEFF013CF8E701 -:106C400010BD000070B53A4D8CB006AC06460FCDB5 -:106C50000FC495E8030084E80300304606F0B2FE56 -:106C60003448012107F066FD44F61D20012107F09C -:106C700055FD0120014607F045FD2F4D07F07EFD33 -:106C800000238DF802300CAC4FF6FF732B48694699 -:106C900024F8303DFBF7CEFF28466946FBF7CAFFD4 -:106CA00027486946FBF7C6FF264B07AC5A6842F0F7 -:106CB00000725A60FFF770FF08232B6110232B61CD -:106CC0000DAD214B1A68214B9A4204D1A378142BA5 -:106CD00004BF1023A37054F8040C21460834FBF7BA -:106CE000A9FFAC42EDD101A807F0C0FC019B184AF6 -:106CF000F021B3FBF2F3174A17481360174B1A68D9 -:106D00004FF47A73B2FBF3F2154B013A5A60154A0D -:106D100082F8231000229A6007221A60FBF7B4FC65 -:106D2000FBF7B6FA6420FFF782FF0CB070BD00BF1E -:106D3000C01E010807004000000C0140000801408F -:106D4000001001400000014094010020001BB7002A -:106D500040420F00B00E0020005800409801002073 -:106D600010E000E000ED00E040F2DB14604308B505 -:106D70000D4B10225A6108221A61841E0A4B2046CC -:106D8000DA6882F01002DA60DA6882F00802DA600B -:106D9000FFF74DFF0120FFF7F7FE1920FFF747FF30 -:106DA0000020FFF7F1FEE9E7000C014010B1034AB3 -:106DB000034B1A60034A044BDA607047EFBEADDE46 -:106DC000F04F00200400FA0500ED00E0034B1878B6 -:106DD000D0F1010038BF0020704700BFCC0E00206A -:106DE0002DE9F04F9F4B87B01B780591013B012B9C -:106DF00000F233819C4B1E78864240F02E819B4BE3 -:106E00001B78022B00F02981994D00232B80994B90 -:106E100031F916009B5D0493049A974B1A70974AB8 -:106E2000127803922AB9964B40421A6802F1004246 -:106E30001A60F9F7F3FE9349F9F7F8FF9149044610 -:106E4000F9F740FFFAF704F98D4F80B2D7F800B098 -:106E50008C49029068805846F9F734FFFAF7F8F841 -:106E6000894AA8801368002118460193FAF7BEF8F2 -:106E7000DFF80892DFF810A24FF00008834F019B63 -:106E8000002855D03B68204619460193FAF7D6F8FA -:106E9000019B38B17E4B029AC3F800B0744B3C6042 -:106EA000DA80C0E018464146FAF7C8F8002800F03A -:106EB000BA80784F3B78002B32D120465946F9F7FB -:106EC000F7FD4FF07C51FAF79BF8734C28B16068DE -:106ED0007249F9F7F7FE60600FE060687049F9F7F2 -:106EE000F1FEDFF8D4B101905946FAF789F8019B19 -:106EF00008B9636001E0C4F804B001233B70694B3A -:106F0000049A1B68CAF80080134400229A72039AFC -:106F100082F0010389F800305C4BC3F8008082E006 -:106F2000594B1C60FFF772FE5F4BFA3018607AE035 -:106F300020461946FAF764F820B1029B4C4ACAF879 -:106F40000040D3803868DAF80010F9F7B1FD8346C5 -:106F5000FFF75CFE544B1B68C01A00280DDA584638 -:106F60004FF07C51FAF76AF800285CD0464B204677 -:106F70001968FAF763F8002855D0454B3868196846 -:106F8000FAF75CF8444C48B10123206844492B804F -:106F9000F9F798FE41492060A06809E002235846AD -:106FA0004FF07E512B80FAF749F828B1A0683C4990 -:106FB000F9F788FEA06004E020683849F9F782FEFE -:106FC0002060384B2C4A1B682E49206892F800B08C -:106FD0000193F9F777FEFAF761F8019B03F80B00CC -:106FE000A0689B44FAF75AF899F800308BF814001F -:106FF00083F0010389F80030264BCAF800801A7824 -:10700000C7F800800132D2B2032A01D01A700AE018 -:1070100000221A70204B25495868F9F753FEFAF7F9 -:107020003DF88BF80A0016B92B8864332B8099F849 -:1070300000300BB11E4B00E01E4B114A1360059B44 -:1070400033F91600F9F7EAFD0E49F9F7EFFE0C4A9D -:1070500001461068F9F72CFD00E0104607B0BDE8C6 -:10706000F08F00BFCC0E0020280F0020D50E00208E -:10707000E2200020E8200108CD0E0020300F002083 -:10708000240F002000002041B80E0020B40E002084 -:10709000C80E0020D40E0020BC0E00200AD7833F6B -:1070A000EC51783FD00E00202C0F002000007A44D5 -:1070B0000000A0410000A0C16F12833A044B0022DF -:1070C0001A60044B00221A70034B01221A70704799 -:1070D000240F0020CC0E00201400002001464C227A -:1070E0000148F9F7FBBF00BFD80E002001494C2230 -:1070F000F9F7F4BFD80E0020254B264A1B7870B54F -:10710000032B04460E46137003D1BDE87040FFF711 -:10711000EDBF012B204D03D1FFF7E0FF002302E07C -:10712000022B01D101232B701C4A012313701C4A2E -:1071300013701C4A002313601B4A13601B4B1C4A2C -:107140001C601C4B1E702B781B4DD65C1B4B1C4AC5 -:107150001E701C4BA05D1A60F9F760FD1A49F9F723 -:1071600065FE34442860A07AF9F758FD1749F9F70D -:107170005DFE6860207DF9F751FD1549F9F7A2FD24 -:10718000A860F9F78BFF00232075A37270BD00BFC4 -:1071900014000020CC0E0020280F0020300F00200B -:1071A000D40E0020B80E0020B40E0020D00E002017 -:1071B000E8200108D50E0020BC0E0020CD0E0020D6 -:1071C0000000A041240F00200000204100007A446C -:1071D0005555553FF8B5194B194D1A78511E0129CF -:1071E00021D8184B184F1C68184B194978681E781D -:1071F000F9F768FDF9F752FF26441649B072B868EE -:10720000F9F760FDF9F74AFF30752078F9F706FDC8 -:107210000146F9F74FFCF9F741FFA37AA0702373F9 -:10722000237DA37505E0032A03D100221A700123F0 -:1072300001E02B7801332B70F8BD00BFCC0E00208D -:1072400014000020D00E0020BC0E0020CD0E002027 -:1072500000007A449A99993F064B10B518680021AE -:107260004FF00104F9F7C2FE08B14FF0000404F03A -:10727000010010BD240F00200023038043807047CD -:10728000024B00221A605A60704700BF7C0F00203A -:10729000054B00221A605A609A60044B00221A6063 -:1072A0005A609A60704700BF700F0020340F0020B2 -:1072B000044B987818B1587C003018BF012000F0BA -:1072C00001007047232200202DE9F04F87B005937D -:1072D000884B0492B3F90220B3F90030002AB8BFFA -:1072E0005242002BB8BF5B4200249A42B8BF1A46F4 -:1072F000804603922546A1462746029401942646DD -:107300007D4BDA7812B91B79002B54D0022E52D063 -:10731000784BDDF810C0E85E784BCCF10001EB5EF5 -:10732000624603EB4000FDF71FFCDFF8F8A1DDF833 -:1073300014C035F90AB03CF90530CBEB000000EB86 -:10734000030BFFF7B5FFA0B16D4B5846F35C0093FC -:10735000F9F764FC6B49F9F769FD009B0246514659 -:107360001846FFF73DFD6749F9F7ACFCF9F770FEE9 -:10737000834698F8070098F81B2000FB0BF0642365 -:107380006FF0040190FBF3F0514302EB8202FDF732 -:10739000EBFBDFF894A1019054F80A005A495844D5 -:1073A00042F21072FDF7E0FB98F8113044F80A0041 -:1073B000584300130290504BDA781AB11B790BB97D -:1073C000022E33D14B4B5020EF5EDFF844A17843BF -:1073D00018F8063035F90A20DFF8509190FBF3F0E9 -:1073E000042392FBF3F3C01A54F809304FF47A5295 -:1073F00018444649FDF7B8FB35F90A3049F804004E -:10740000002BB8BF5B42B3F5206FC4BF002349F81F -:10741000043059F804207D2392FBF3F908EB0603AE -:107420009B7A03FB09F9402399FBF3F9324B1A7954 -:10743000D2B1022E18D0DDF80CC04FF4FA710CFB5B -:1074400007F2CCF5FA73DDF804C003FB0C22DDF87B -:107450000CC092FBF1F20CFB09F0DDF808C003FB55 -:107460000C0393FBF1F308E0DB780BB1022E02D1A1 -:107470004B463A4601E0029B019A2549DFF8B0B03D -:10748000695A04200FFA81FC16F80BB09CFBF0FA45 -:107490000BFB0AFB6FF04F0A9BFBFAFA02EB0A0B9D -:1074A0001C4A35F902A0A952CAEB0C0C9CFBF0F067 -:1074B000194ADFF880C054F802A054F80C10A0500C -:1074C000164A5144B25C01445143202291FBF2F12F -:1074D0005B1A134801369B44032E44F80CA025F890 -:1074E00000B004F1040405F102057FF409AF07B010 -:1074F000BDE8F08F4C22002023220020FA12002049 -:10750000EA20010800002041F0D8FFFF80C1FFFF02 -:10751000E80F0020900F0020B00F00203B2100203A -:1075200032210020281000207C0F0020700F002046 -:107530003E2100204C0F00202DE9F04F89B006932A -:107540006E4B804618880591F9F764FB6C49F9F792 -:10755000B9FB00240490474625462646022EDFF854 -:10756000E4910BD1059AB9F9040053790A335843D1 -:10757000F9F754FB6349F9F759FC44E0624B39F9D8 -:107580000500EB5E614918444FF4FA72FDF7ECFA1E -:10759000DFF8B4A1069B35F90A20595F801A084428 -:1075A000F9F73CFB5A49F9F741FC8346FFF780FEA7 -:1075B00030B1584A5146905D5A46FFF711FC834658 -:1075C000DFF888A19AF803202AB15846D8F8441069 -:1075D000F9F778FB17E0059B39F905001A791432A1 -:1075E0005043F9F71BFB4749F9F720FC9AF80430A0 -:1075F00081464BB1D8F848105846F9F763FB01466D -:107600004846F9F757FA8146434B0136585FF9F778 -:1076100005FB424B0437D968F9F754FB82465146C3 -:107620004846F9F745FAF9698346F9F74BFBDFF865 -:107630002091049907905846F9F744FBB96AF9F785 -:1076400041FB54F80910F9F735FA354A3549FDF789 -:1076500093FA44F80900DFF8FC90834654F80910C7 -:107660005046F9F725FA44F809A0024604994FF06C -:107670007E500192F9F7DAFB019A01461046F9F7BC -:1076800021FB294B294A54F803C0A1588146604682 -:1076900001920293CDF80CC0F9F70CFA4946F9F7BC -:1076A00009FADDF80CC0029B019A214944F80390C5 -:1076B00044F802C0F9F7BAFB796BF9F703FB1D4AEE -:1076C0001D49FDF759FA594681460798F9F7F2F92D -:1076D0004946F9F7EDF907F031FA18494FF47A7293 -:1076E000FDF742FA164B032E585304F1040405F13A -:1076F00002057FF433AF09B0BDE8F08F180D00200C -:10770000BD37863500004842FA1200200CFEFFFF0C -:1077100000002041EA200108E80F00201C21002081 -:1077200000007A4300007AC3640F0020400F00205D -:107730000000404000009643000096C318FCFFFF85 -:10774000322100204C22002028100020232200207B -:10775000340F0020980F00202DE9F04F002485B051 -:1077600007468A469346039306462546022DDFF8D0 -:107770007C814FEA450907D19AF80520B8F9043011 -:107780001B3253435B1144E04D4A38F9150032F97E -:107790001520CBF1000102EB40005A46FDF7E4F959 -:1077A000484B33F91520039B801A33F91510421802 -:1077B0000192FFF77DFD019AB8B14349104615F8D3 -:1077C00001C0CDF800C0F9F729FA4049F9F72EFBBE -:1077D000DDF800C002463B496046FFF701FB3B492C -:1077E000F9F770FAF9F734FC02463949C87868B9F4 -:1077F0009AF8040038F909301B30434309791B110A -:1078000039B1797C4A4303EB222302E0FB795A43E6 -:107810001311304A785D32F90980042298FBF2F89E -:10782000C8EB030800FB08F0DFF8C4C0C0110290E9 -:10783000BCF80000284B00FB08F0E258B17AC012F7 -:1078400001FB00202549E0504FF400120193CDF8D0 -:1078500000C0FDF789F9019BDDF800C0E050204B26 -:107860004FF6FF72E15844F80380BCF80030C1EBDA -:1078700008011B09B2FBF3F35943DFF878C0194B39 -:10788000891154F8038054F80C20E150029B4244C3 -:1078900003EB6030337D0A445A430135124B00EB51 -:1078A0002222032D44F80C8023F8092006F101065A -:1078B00004F104047FF45AAF05B0BDE8F08F00BFB7 -:1078C000FA12002028100020EA20010800002041C0 -:1078D00023220020E80F0020700F00200000E0FFAE -:1078E000840F0020580F0020322100204C2200205D -:1078F000180D0020A40F00200128054B03D00228FA -:1079000003D0044A02E0044A00E0044A1A607047C7 -:1079100018000020C972000859770008397500085E +:1055B00038B5194B194C5D7D637CFDB153BBA378A5 +:1055C0009BB101F001FC164D08B92B781BB101F01D +:1055D00073FD00232B70134810F8041C01F08AFDA2 +:1055E0000123114A6374137038BD01F033FE88B192 +:1055F000FFF7A6FABDE8384001F05EBD13B101F037 +:10560000E7FD6574A3782BB9074B1B7813B1044BE6 +:1056100001221A7038BD00BF35220020232200204D +:10562000200D0020DC1F0020060D002008B5022000 +:1056300004F07EFE18B900F031FE28B90AE000F04F +:105640004BFF0028F7D108BD01F0DAF880F0010027 +:10565000C0B205E0022004F06BFE0028F4D0012067 +:1056600000F0010008BD0000054B1A683AB900F5CA +:10567000F42000F590701860024B08225A617047C0 +:105680001C0D0020000C0140034B00221A60034B4C +:1056900008221A61704700BF1C0D0020000C014059 +:1056A000084A136863B1C01A002809DB064903F5EC +:1056B000F423C86803F5907380F00800C860136095 +:1056C000704700BF1C0D0020000C0140A94B2DE9C4 +:1056D000F04FB3F90600A84B85B0B3F858209042BC +:1056E0000FDBB0F5FA6F93F8564007DA811A4C4396 +:1056F000A2F5FA6294FBF2F4643403E0C4F16404AA +:1057000000E064249D4A93F85410B2F812C192F953 +:10571000EC2093F8A25093F8A360524293F85530CE +:1057200092B201910021029203930A46914B40F2FA +:10573000E637CB5E0093CCEB030303F2F31EBE45CA +:1057400003D8002BB8BF5B4201E04FF4FA73022A82 +:10575000DFF834822CD025B1AB42CCBFC5EB0303BC +:1057600000236427DFF848A293FBF7FE6FF0630B7A +:105770003AF81E900BFB0E3B0EF1010E3AF91EA0FB +:105780000FFA89FECEEB0A0E0EFB0BFE9EFBF7FE18 +:10579000CE4428F801E0DDF8048003FB08FE784BD6 +:1057A0009EFBF3F33B449BB2634393FBF7F714E098 +:1057B00026B1B342CCBFC6EB03030023DDF808E0FB +:1057C00003FB0EF7A8F80470039F002BB8BF5B42E1 +:1057D0007B436B4F93FBF7F76437674BDFF8D4815C +:1057E00002EB030E9EF80490642307FB09F999FB72 +:1057F000F3F902F808909EF80E909EF818E007FB67 +:1058000009F907FB0EF7DFF8B08199FBF3F902F80D +:105810000890DDF8008097FBF3F35A4FE045D3552D +:10582000594F02DA7B5A5B427B520132032A01F163 +:1058300002017FF47BAF514C4FF4FA62B4F81411BB +:10584000FFF792F9B4F814314FF47A74C01A444354 +:10585000C3F5FA63B4FBF3F464214C4894FBF1F311 +:105860006FF0630630F8132006FB0344013330F970 +:10587000130013B2C31A5C4394FBF1F1444C0A4485 +:10588000637A414DFA80002B38D0424B1888424B46 +:105890001B88C01A00B2FFF7CFF9064609F018F9C5 +:1058A0000746304609F088F90646B5F90200FBF7CD +:1058B000B5F98046B5F90000FBF7B0F939468146E5 +:1058C000FBF700FA314682464046FBF7FBF90146FA +:1058D0005046FBF7EDF8FBF7BBFB39462880404606 +:1058E000FBF7F0F9314607464846FBF7EBF901466E +:1058F0003846FBF7DFF8FBF7ABFB68800220FEF7CA +:10590000C7FE264D88B1264A13780133DBB21370E7 +:105910000622B3FBF2F102FB113313F0FF0F04D1A7 +:10592000FEF7F8FAFEF718FB28702878003018BF49 +:105930000120FEF717FDA3781BB11A4B08225A610C +:1059400042E0FFF773FE20B1164BDA6882F00802DE +:10595000DA6001232370637B0BB90D4A1370124B7D +:105960005B7D0BB1002323702378104D33B3FFF719 +:105970008BFE26E07E220020D81F00208C1B0020FA +:105980000CFEFFFF3B2100204C220020542200206F +:105990002322002042210020EA200020EC0C0020DD +:1059A000FC0C0020000C014035220020F00C0020EF +:1059B0006C2200203E210020382100202868FFF7BB +:1059C00053FE2868FFF76CFE05F03AFA8020FEF7D8 +:1059D0005FFEA8B1134B144A1B681168591A0029BD +:1059E0000EDB03F543435033A07813600F4B0030B8 +:1059F00018BF0120B3F90210B3F90020FDF768F9D0 +:105A000006F0ACF8202004F093FC18B1054B1868A0 +:105A100004F01AFC064B9B680BB10648984705B08A +:105A2000BDE8F08FF00C0020000D002028100020B1 +:105A30001C210020E0200020024B9A780AB10022AD +:105A40009A707047232200200B4B19781A4651B1E7 +:105A5000997879B9597831B901229A70074B1A8827 +:105A6000074B1A807047937823B90220FF21012247 +:105A700007F026BF704700BF2322002042210020EC +:105A8000EA2000202DE9F84F904F04F069FD3868B6 +:105A900004F08EFD8E4C002800F03F82386804F040 +:105AA00037FE4FF48040FEF7F3FD20B1894B1B78A1 +:105AB0000BB9FFF7C1FF386804F0CEFE4FF4007059 +:105AC000FEF7E6FD90B1814B834D1A68834B9A42F5 +:105AD00008D92B681B681B6A984718B92B681B6884 +:105AE0005B6A98472B681B685B6998470022B4F88B +:105AF0001451B4F81661134679489B08115E0232BE +:105B0000A942C4BF63F07F03DBB2B142B8BF43F028 +:105B10004003082A8146EFD1724EDFF8E4813278E3 +:105B20009A4205D198F80020F92A04D8013200E001 +:105B3000002288F800204FF480403370FEF7A8FD63 +:105B400058B1B4F81211B4F8DC20B9F90630881A4B +:105B5000834202DD0A4493420ADB4FF48040FEF7A1 +:105B600097FDC8B9B9F90620B4F814319A4213DA8E +:105B700001F084FB01F08AFB5B4BB3F876305BB13C +:105B8000544B1A78594B002A00F03B831A78002AAC +:105B900000F03783FFF758FF98F80030142B40F0DF +:105BA000C380524B504D93F802B09A46BBF1000FA0 +:105BB00018D0B5F8763023B933785F2B01D1FFF7D1 +:105BC0003BFF94F81A31002B00F0AE80B5F8763028 +:105BD000002B40F0A98033787D2B40F0A580FFF7A3 +:105BE0002BFFA1E03378572B18D14FF47A7000F0D7 +:105BF00001FE4FF48070FEF74BFD08B103F08EFA02 +:105C0000042004F095FB10B10A2000F06FFC08207E +:105C100004F08EFBF0B9364B18801BE00420FEF731 +:105C200037FDB8B12F4B1B785A2B13D1314B1A7853 +:105C30002AB183F800B0304B01221A700AE02F4AD3 +:105C4000137883F0010313700BB1022000E00320EE +:105C5000FEF71EFC33785D2B00F0DA825B2B00F040 +:105C6000D9825E2B00F00083B5F876302BB93278FC +:105C70006F2A02D1FFF7E8FE13E094F81A211AB157 +:105C800013B933787E2BF5D03378972B04D14FF4AA +:105C9000C87000F0FDFA04E0A72B04BF01238AF8C6 +:105CA0000E303378BB2B03D1B5F85E30023304E0FD +:105CB000B72B05D1B5F85E30023BA5F85E3028E081 +:105CC000BE2B1FD1B5F85C30023320E0F00C002071 +:105CD0008C1B002035220020DC200020404B4C0093 +:105CE0007E220020040D0020D81F00202322002047 +:105CF00042210020210D0020100D0020F50C002075 +:105D0000220D0020BD2B0FD1B5F85C30023BA5F869 +:105D10005C3094F84804FEF755FCFEF763FCFEF790 +:105D200005FF002388F800300420FEF7B1FC48B3DB +:105D30007E4A7F4B117871B17E49897859B1B9F9A2 +:105D40000600B4F81411884205DD197819B97A48AB +:105D50003225058011705B7C53B1784B1A782AB9D3 +:105D6000774A127812B9744A32211180012208E070 +:105D7000734B1A7832B16F4A92781AB91A70714B14 +:105D800001221A7070480123002230F8021F5E1EA3 +:105D9000A1F21555B5F5C77F8CBF002501259D40A3 +:105DA00009B22A4340F21355A942CCBF0025012570 +:105DB000B5402A4340F2A465A942D4BF0021012185 +:105DC0005D1CA94003330A430D2B92B2DDD10023A1 +:105DD0005E49574E01EB4301B1F876100A420CBF01 +:105DE0000021012199550133162BF1D17378514DC2 +:105DF00023B1022004F09CFA68B914E04FF400705B +:105E0000FEF746FC78B1524B1B681B689B689847AD +:105E10000028EED107E0EB783BB901F02FFA454BB3 +:105E20000122DA7001E00023EB70B3784BB100235C +:105E3000EB702B7933B901F021FA3E4B01221A7134 +:105E400000E02B71EA78434B12B93A4A127912B149 +:105E500010225A6101E010221A61042004F068FA4D +:105E600010B3F3788BB1AB7983B9324A01219171C8 +:105E7000394A1168394A1160394AD188394A118042 +:105E8000394A1360394A136000E0AB714FF4005097 +:105E9000FEF7FEFB40B133792BB1EB7B23B9254BE9 +:105EA0000122DA7300E0EB73022004F041FA10B132 +:105EB000737933B90FE0082004F03AFA0028F7D1DB +:105EC00019E06B7943B91B4B01225A71284B1A8890 +:105ED000284B1A8000E06B71B3792BB16B7A23B930 +:105EE000144B01225A7200E06B72F3791BB1204B04 +:105EF0001A88214B1A80202004F01AFA08B104F005 +:105F000047F9337B03B10123AB726379082B01D0CE +:105F10000E2B6BD100236B7268E0184D2B68042B9D +:105F200064D8DFE803F02D37424C5700F50C002011 +:105F30003522002023220020240D0020050D002002 +:105F4000210D0020100D002084220020D81F0020E9 +:105F5000DC200020000C014064210020682100208A +:105F60004C2200200C0D002014100020C00F002037 +:105F70004221002030210020EA200020140D0020C2 +:105F8000012308202B6004F0D3F918B1A24800F0D7 +:105F9000A5FB58BB2B68042001332B6004F0C8F923 +:105FA00018B1386800F0A8FA00BB2B680420013350 +:105FB0002B6004F0BDF910B102F0E0F9B0B92B6824 +:105FC0004FF4807001332B60FEF762FB10B103F0D9 +:105FD000CBF80BE0002310202B6004F0A9F908B1E6 +:105FE00000F08CFD4FF40050FEF752FB00F0F2FD84 +:105FF000A2893860894B22B11968411A0029C0F280 +:10600000F2801044186001F02FFFFFF75FFB00F0F3 +:10601000E1FD834B83491A683860821A18600A8050 +:10602000FFF7C6FA082004F083F97F4E002830D02D +:106030007E4A9188154601F145039BB28A2B7C4A22 +:106040007C4B24D87C4847790FB31F881388407B4A +:10605000FA1A92B293B21FB2B337BCBF02F5B4734F +:106060009BB21AB2B32AC4BFA3F5B4739BB294F81F +:10607000EC2070B152B252425343327B1BB25343B5 +:106080006FF01D0293FBF2F31944A98001E01B8815 +:106090001380042004F04CF9002879D0664B9A79DB +:1060A000002A75D01F7C614D002F69D196F8A5108C +:1060B000624896F8A420624BB5F806E029B3B0F91F +:1060C00000000FFA8EF1C0EB010CBCF1000FB8BF5D +:1060D000CCF1000C94450FDD8142C8BF5242DFF87D +:1060E00084C11FFA8EFEC8BF92B2CCF80070724411 +:1060F00001271F70EA804BE01A78002A34D0514AF9 +:106100001F701168504A11602EE007880FFA8EFC4C +:1061100038B2C0EB0C0CBCF1000FB8BFCCF1000CD6 +:10612000944518DD494ADFF82081B2F800C0F444F4 +:10613000C7EB0C0C0FFA8CFC4FF4FA6ED8F8007019 +:106140009CFBFEF10F440EFB11C111800122C8F827 +:1061500000701A7008E01A7832B13A4A197017685C +:10616000394A1760394A1180394BB4F8D0101B688E +:1061700064311844B4F8D220FEF7F6FCE88007E05A +:10618000334B6A8894F91C111B6801FB03236B8055 +:1061900096F8A83053B1284BDA780AB91B792BB19D +:1061A000224B2C4A1188DA880A44DA80202004F035 +:1061B000BFF840B1204BDA790AB91A7A1AB11B7BC1 +:1061C0000BB103F043FF2448244B00F14C01B4F819 +:1061D000F6201D6800F15803A84702F065FB02F0A5 +:1061E000E1FA02F03BFB1E4B1B78002B4DD14FF424 +:1061F0000060FEF74DFA002847D0BDE8F84F04F0E4 +:1062000069BE9B78002B3FF4C7ACFFF715FCC3E4D5 +:1062100001222AE0022228E08A1C0020080D00202A +:10622000F80C0020180D0020D81F00204C22002060 +:106230003021002042210020232200200C0D0020CC +:10624000F40C002064210020682100200E0D0020A5 +:10625000C00F0020C80F0020DC1F00201800002005 +:10626000401600201410002003225FFA82FB0BF17D +:10627000FF3384F84834FEF7B5F9FEF729FC022015 +:1062800028215A4607F01CFBEEE4BDE8F88F00BF5A +:10629000014B1880704700BF320D0020034B188857 +:1062A000D0F1010038BF0020704700BF320D002040 +:1062B000204B00222DE9F0411968804613461E4C00 +:1062C0001E4E25881E4FB5F5C87F04BF0025F5502A +:1062D000F05832F907C0194D844446F803C004331E +:1062E00000260C2BD6538E5202F10202E7D12388EE +:1062F000012B19D12B68404603F1C8024FF4C87333 +:1063000092FBF3F20A806A68C83292FBF3F24A8089 +:10631000AA68C83292FBF3F30A4A12889B1A8B8050 +:1063200000F0A8FFFEF70CFC2388013B2380BDE8AA +:10633000F08100BF340D0020320D0020380D002008 +:106340005C210020120000202DE9F041354D04466B +:106350002B88322B0ED1344B1A68344B118819809C +:106360005188928859809A80314B02881A804288DD +:106370005A8001E0002B34D02B490022D1F800C014 +:1063800013460F46298832292A4904BF0020C850E5 +:106390002948CE5832F900804644CE5004330021BB +:1063A0000C2B11522CF8021002F10202EAD12B88B8 +:1063B000012B13D1214A02201170214A1370FEF7DC +:1063C00067F81A4A3B681188198051889288598069 +:1063D0009A80174B1A885B88228063802B88013B48 +:1063E0002B80184B1A78DAB1124900221A700E4B22 +:1063F00008681B68322290FBF2F01880486890FB16 +:10640000F2F058808968204691FBF2F20E49098823 +:10641000521A9A8000F02EFFBDE8F041FEF790BBC3 +:10642000BDE8F081240D0020340D0020260D002051 +:106430002E0D0020440D00205C210020050D0020C1 +:10644000210D0020100D002012000020064B0288B4 +:1064500019888A1A1A80598842888A1A5A80998813 +:1064600082888A1A9A8070475C2100200F4B10B5F1 +:106470005B6804460E4898470E4B0D481A78014653 +:10648000FDF740FE0C4B1B8813B12046FFF710FFB1 +:106490000420FEF7FDF810B12046FFF755FFBDE8D8 +:1064A0001040064B1868FFF7D1BF00BFEC2000205A +:1064B0005C2100202C0D0020320D0020340D002026 +:1064C000014B1860704700BF340D0020014B18606D +:1064D000704700BF10210020034B1888D0F1010045 +:1064E00038BF0020704700BF600D0020014B1880AE +:1064F000704700BF600D00202DE9F041224D2B6850 +:10650000C31A002B3CDB214E28603378204C012B32 +:1065100010D123699847636898472B6822881D48E3 +:1065200013442B601C496369984700233370022091 +:10653000BDE8F081A3689847E36898471748184971 +:106540000068D1F80080134B0078D3F800C008F140 +:106550000103834208BF0023124A1348176840F81A +:1065600028C050F82300BC44C0EB0C070B60176038 +:106570002B6862880120134430702B60BDE8F081E5 +:106580000020BDE8F08100BF580D00206C0D0020F8 +:10659000F82000205C0D0020640D00201021002058 +:1065A000540D0020740D00207C0D0020F8B51E4C09 +:1065B0001E4A236810681B781D4D013BB0FBF3F0A9 +:1065C000FAF728FB1B49FAF731FC1B4908F084FB5A +:1065D00001464FF07E50FAF76BFA1849FAF772FB52 +:1065E00008F0ACFA236807465C682868FAF716FBDF +:1065F0002146FAF767FB124B06461868381AFAF775 +:106600000DFB214607464FF07E50FAF751FA01463E +:106610003846FAF757FB01463046FAF74BFA08F0CE +:106620008DFA2860F8BD00BF10210020740D0020F5 +:10663000700D002080E6C547B1DC423ED048874A55 +:10664000680D002010B5154B154A1B6811681878A5 +:10665000144B01381B68B3FBF0F0082391FBF3F4F3 +:10666000091B0844106090FBF3F0FAF7D7FA0E49C3 +:10667000FAF7DCFB0D4908F02FFB01464FF07E5086 +:10668000FAF716FA0A49FAF71DFBFAF7E1FC094B8B +:106690001860094B1A88013A1A8010BD1021002099 +:1066A000780D0020740D002080E6C547B1DC423E25 +:1066B000D048874A680D0020600D002038B5054C91 +:1066C00010256561FCF7DCF9034B012225611A7086 +:1066D00038BD00BF000C0140530E0020F8B5374B09 +:1066E000374D1B682A6804469A1A002A63DB03F5B3 +:1066F000C333A03333482B60FCF788F93148324B61 +:1067000001461A78FDF7FEFC304B314A997B18465A +:1067100079B12968002311600021E1520E46294910 +:106720002C4F595AD9532C4FD9530233062BF3D13E +:1067300086732A4B1B7863B1224B21881888411A33 +:10674000198058886188411A59809888A188411A0F +:1067500099801368002B2CD02A681E48D31A204A2F +:106760001D49934216D81F4BDA6882F00802DA609E +:106770000023144AC55E9A5A14B2A542C4BF154DEF +:106780005A53CD5EA542BCBF134C1A530233062B9D +:10679000EFD10EE00E4A00231360C55ECA5E2A44A4 +:1067A000022592FBF5F2E2522B44062BF5D1FEF7BF +:1067B000C7F90120F8BD0020F8BD00BFF00C002093 +:1067C000440E002014210020520E0020232200201D +:1067D000480E00203C0E00204C0E0020530E0020DE +:1067E0007FC3C901000C0140014B1860704700BF16 +:1067F000540E0020014B1880704700BF580E002037 +:10680000034B1888D0F1010038BF0020704700BF4B +:10681000580E00203C4B2DE9F74F5B683B489847EA +:106820003B4B3A481A780146FDF76CFC394B374F21 +:106830001A889846DFF8E8A0002A3CD0364B00259D +:106840001B68364E93F800B02C46B8F80030DFF8DD +:10685000D490B3F57A7F05D10023304649F804304F +:10686000FEF79CF9785F59F80430034449F8043086 +:10687000FAF7D4F901463046FEF793F900237B532B +:106880002AF80530B8F80030012B25D13046FEF744 +:10689000CAF90346BBF1000F0FD058460193FAF72F +:1068A000BDF9019B01461846FAF7C8FB28B1194B00 +:1068B0004FF47A721A8000231BE059F804304FF429 +:1068C0007A7203F5FA7393FBF2F30A200F21012287 +:1068D0002AF8053006F0F4FF04340C2C05F102050B +:1068E00006F11406B1D1B8F80030013BA8F8003029 +:1068F000E1E7F95A3AF803208A1AFA520233062BD2 +:10690000F7D103B0BDE8F08F1C2100204421002006 +:10691000A40E0020580E0020540E0020680E002007 +:10692000EE0F00205C0E002038B505460A4C00230F +:106930000A4829462370FBF75BF848B907482946FF +:10694000FAF7E6FD20B905482946FAF70FFF08B126 +:106950000123237038BD00BFA40E00201C2100209D +:1069600003780BB1054A137043780BB1044A1370D6 +:1069700083780BB1034A1370704700BFA40E002048 +:106980002C0D0020520E00202DE9F74381460846C9 +:1069900014469846FFF7C8FF0746002800F08A8093 +:1069A000464E00233370464D072C38D8DFE804F0FC +:1069B000080819242F373704022003F0CBFC2EE0FF +:1069C0008DF8043001A84FF448733E49ADF8063005 +:1069D000FAF7E2FC18B101232B7004233370012C69 +:1069E0001DD03848FAF7B4FF30B102232B70022CC7 +:1069F0004FF00103337012D03248FAF729FE30B15C +:106A000003232B70032C4FF00203337007D02D4863 +:106A1000FAF724FD18B104232B70012333702B786F +:106A20002BB90CB11C46BBE7022003F093FC2648AF +:106A3000FBF768FB30B92448FBF79CF910B9042038 +:106A400003F088FC4846FFF78BFF022003F070FC40 +:106A500010B11C4B1B6898471C4B1B689847FBF7F1 +:106A6000C1FF18B11A4B03221A7002E0082003F08C +:106A700071FC082003F05CFC164C0546C0B164278D +:106A800098FBF7F63046FAF7C9F8814607FB1680FF +:106A900000B2FAF7C3F81049FAF714F9014648466C +:106AA000FAF708F80D49FAF70DF92F46206001E0D2 +:106AB00000232360384603B0BDE8F0832C0D00208E +:106AC000500D0020EC200020F82000201C21002088 +:106AD000520E0020241000208988883C00002041AC +:106AE00008B50120FCF776F9102003F02BFC024BCF +:106AF00000221A6008BD00BF2C2100200148FCF7CD +:106B0000D3B900BF2C21002008B503681B68984743 +:106B100008BD38B505460C4614F8011B19B12846C6 +:106B2000FFF7F2FFF8E738BD08B503685B689847E0 +:106B300008BD08B503689B68984708BD08B5036899 +:106B4000DB68984708BD08B503681B69984708BD0E +:106B500008B503685B69984708BD0000034B4FF414 +:106B6000805208B15A6170471A61704700080140AD +:106B7000034B4FF4805208B11A6170475A61704755 +:106B80000008014008B5024B1B68984708BD00BFCC +:106B9000A80E0020064B00201A68064B9A4208BF38 +:106BA000054A064B18BF064A1A60FFF7EBBF00BF45 +:106BB00094010020001BB700716B0008A80E002094 +:106BC0005D6B0008024B1A6801321A60704700BF03 +:106BD000AC0E002010B5094A094913688C68126888 +:106BE0009342F8D1074A106811684FF47A72504303 +:106BF000001BB0FBF1F002FB030010BDAC0E002047 +:106C000010E000E0B00E0020014B1868704700BF94 +:106C1000AC0E002038B50446FFF7DCFF0546FFF751 +:106C2000D9FF401BA042FAD338BD10B504462CB1A1 +:106C30004FF47A70FFF7EEFF013CF8E710BD00005B +:106C400070B53A4D8CB006AC06460FCD0FC495E832 +:106C5000030084E80300304606F0B4FE3448012106 +:106C600007F068FD44F61D20012107F057FD0120C3 +:106C7000014607F047FD2F4D07F080FD00238DF8FA +:106C800002300CAC4FF6FF732B48694624F8303DB8 +:106C9000FBF7D0FF28466946FBF7CCFF274869463B +:106CA000FBF7C8FF264B07AC5A6842F000725A60E7 +:106CB000FFF770FF08232B6110232B610DAD214BD3 +:106CC0001A68214B9A4204D1A378142B04BF1023D5 +:106CD000A37054F8040C21460834FBF7ABFFAC4218 +:106CE000EDD101A807F0C2FC019B184AF021B3FBCB +:106CF000F2F3174A17481360174B1A684FF47A7368 +:106D0000B2FBF3F2154B013A5A60154A82F8231090 +:106D100000229A6007221A60FBF7B6FCFBF7B8FA6C +:106D20006420FFF782FF0CB070BD00BFC01E0108D9 +:106D300007004000000C0140000801400010014025 +:106D40000000014094010020001BB70040420F00EA +:106D5000B00E0020005800409801002010E000E034 +:106D600000ED00E040F2DB14604308B50D4B10224B +:106D70005A6108221A61841E0A4B2046DA6882F0A2 +:106D80001002DA60DA6882F00802DA60FFF74DFF7D +:106D90000120FFF7F7FE1920FFF747FF0020FFF75C +:106DA000F1FEE9E7000C014010B1034A034B1A6001 +:106DB000034A044BDA607047EFBEADDEF04F0020AF +:106DC0000400FA0500ED00E0034B1878D0F1010053 +:106DD00038BF0020704700BFCC0E00202DE9F04FD7 +:106DE0009F4B87B01B780591013B012B00F233814B +:106DF0009C4B1E78864240F02E819B4B1B78022BC9 +:106E000000F02981994D00232B80994B31F9160010 +:106E10009B5D0493049A974B1A70974A12780392D9 +:106E20002AB9964B40421A6802F100421A60F9F7FB +:106E3000F5FE9349F9F7FAFF91490446F9F742FF45 +:106E4000FAF706F98D4F80B2D7F800B08C4902905E +:106E500068805846F9F736FFFAF7FAF8894AA880A9 +:106E60001368002118460193FAF7C0F8DFF808927A +:106E7000DFF810A24FF00008834F019B002855D087 +:106E80003B68204619460193FAF7D8F8019B38B1C0 +:106E90007E4B029AC3F800B0744B3C60DA80C0E0CD +:106EA00018464146FAF7CAF8002800F0BA80784F31 +:106EB0003B78002B32D120465946F9F7F9FD4FF0C7 +:106EC0007C51FAF79DF8734C28B160687249F9F764 +:106ED000F9FE60600FE060687049F9F7F3FEDFF8D3 +:106EE000D4B101905946FAF78BF8019B08B9636059 +:106EF00001E0C4F804B001233B70694B049A1B689D +:106F0000CAF80080134400229A72039A82F00103A7 +:106F100089F800305C4BC3F8008082E0594B1C605C +:106F2000FFF772FE5F4BFA3018607AE02046194690 +:106F3000FAF766F820B1029B4C4ACAF80040D380A9 +:106F40003868DAF80010F9F7B3FD8346FFF75CFE06 +:106F5000544B1B68C01A00280DDA58464FF07C517C +:106F6000FAF76CF800285CD0464B20461968FAF70F +:106F700065F8002855D0454B38681968FAF75EF86F +:106F8000444C48B10123206844492B80F9F79AFE0C +:106F900041492060A06809E0022358464FF07E5125 +:106FA0002B80FAF74BF828B1A0683C49F9F78AFE24 +:106FB000A06004E020683849F9F784FE2060384B6F +:106FC0002C4A1B682E49206892F800B00193F9F70B +:106FD00079FEFAF763F8019B03F80B00A0689B4465 +:106FE000FAF75CF899F800308BF8140083F001038D +:106FF00089F80030264BCAF800801A78C7F800805C +:107000000132D2B2032A01D01A700AE000221A70AB +:10701000204B25495868F9F755FEFAF73FF88BF8E9 +:107020000A0016B92B8864332B8099F800300BB115 +:107030001E4B00E01E4B114A1360059B33F91600EE +:10704000F9F7ECFD0E49F9F7F1FE0C4A014610681C +:10705000F9F72EFD00E0104607B0BDE8F08F00BF45 +:10706000CC0E0020280F0020D50E0020E2200020AA +:10707000E8200108CD0E0020300F0020240F002052 +:1070800000002041B80E0020B40E0020C80E0020E1 +:10709000D40E0020BC0E00200AD7833FEC51783F6D +:1070A000D00E00202C0F002000007A440000A041E8 +:1070B0000000A0C16F12833A044B00221A60044BF7 +:1070C00000221A70034B01221A707047240F00200F +:1070D000CC0E00201400002001464C220148F9F794 +:1070E000FDBF00BFD80E002001494C22F9F7F6BFC2 +:1070F000D80E0020254B264A1B7870B5032B04467A +:107100000E46137003D1BDE87040FFF7EDBF012BB1 +:10711000204D03D1FFF7E0FF002302E0022B01D155 +:1071200001232B701C4A012313701C4A13701C4A44 +:10713000002313601B4A13601B4B1C4A1C601C4B32 +:107140001E702B781B4DD65C1B4B1C4A1E701C4BB3 +:10715000A05D1A60F9F762FD1A49F9F767FE344439 +:107160002860A07AF9F75AFD1749F9F75FFE6860C1 +:10717000207DF9F753FD1549F9F7A4FDA860F9F74B +:107180008DFF00232075A37270BD00BF1400002086 +:10719000CC0E0020280F0020300F0020D40E00203D +:1071A000B80E0020B40E0020D00E0020E820010808 +:1071B000D50E0020BC0E0020CD0E00200000A04106 +:1071C000240F00200000204100007A445555553F0F +:1071D000F8B5194B194D1A78511E012921D8184BB1 +:1071E000184F1C68184B194978681E78F9F76AFD22 +:1071F000F9F754FF26441649B072B868F9F762FDF2 +:10720000F9F74CFF30752078F9F708FD0146F9F7DA +:1072100051FCF9F743FFA37AA0702373237DA37574 +:1072200005E0032A03D100221A70012301E02B7824 +:1072300001332B70F8BD00BFCC0E002014000020DD +:10724000D00E0020BC0E0020CD0E002000007A449D +:107250009A99993F064B10B5186800214FF0010428 +:10726000F9F7C4FE08B14FF0000404F0010010BDAE +:10727000240F00200023038043807047024B00222C +:107280001A605A60704700BF7C0F0020054B002237 +:107290001A605A609A60044B00221A605A609A6021 +:1072A000704700BF700F0020340F0020044B987807 +:1072B00018B1587C003018BF012000F00100704761 +:1072C000232200202DE9F04F87B00593884B0492CC +:1072D000B3F90220B3F90030002AB8BF5242002BA4 +:1072E000B8BF5B4200249A42B8BF1A468046039258 +:1072F0002546A14627460294019426467D4BDA781E +:1073000012B91B79002B54D0022E52D0784BDDF8E5 +:1073100010C0E85E784BCCF10001EB5E624603EBF7 +:107320004000FDF721FCDFF8F8A1DDF814C035F9C5 +:107330000AB03CF90530CBEB000000EB030BFFF784 +:10734000B5FFA0B16D4B5846F35C0093F9F766FCAE +:107350006B49F9F76BFD009B024651461846FFF753 +:107360003DFD6749F9F7AEFCF9F772FE834698F8E0 +:10737000070098F81B2000FB0BF064236FF004015A +:1073800090FBF3F0514302EB8202FDF7EDFBDFF8D7 +:1073900094A1019054F80A005A49584442F21072DC +:1073A000FDF7E2FB98F8113044F80A005843001347 +:1073B0000290504BDA781AB11B790BB9022E33D1F7 +:1073C0004B4B5020EF5EDFF844A1784318F80630AD +:1073D00035F90A20DFF8509190FBF3F0042392FB7B +:1073E000F3F3C01A54F809304FF47A52184446495E +:1073F000FDF7BAFB35F90A3049F80400002BB8BF95 +:107400005B42B3F5206FC4BF002349F8043059F83C +:1074100004207D2392FBF3F908EB06039B7A03FB20 +:1074200009F9402399FBF3F9324B1A79D2B1022EB4 +:1074300018D0DDF80CC04FF4FA710CFB07F2CCF554 +:10744000FA73DDF804C003FB0C22DDF80CC092FBDC +:10745000F1F20CFB09F0DDF808C003FB0C0393FB11 +:10746000F1F308E0DB780BB1022E02D14B463A462D +:1074700001E0029B019A2549DFF8B0B0695A042067 +:107480000FFA81FC16F80BB09CFBF0FA0BFB0AFB21 +:107490006FF04F0A9BFBFAFA02EB0A0B1C4A35F914 +:1074A00002A0A952CAEB0C0C9CFBF0F0194ADFF8C1 +:1074B00080C054F802A054F80C10A050164A514451 +:1074C000B25C01445143202291FBF2F15B1A134854 +:1074D00001369B44032E44F80CA025F800B004F1BB +:1074E000040405F102057FF409AF07B0BDE8F08F91 +:1074F0004C22002023220020FA120020EA2001085A +:1075000000002041F0D8FFFF80C1FFFFE80F0020FE +:10751000900F0020B00F00203B21002032210020DE +:10752000281000207C0F0020700F00203E2100203A +:107530004C0F00202DE9F04F89B006936E4B80462A +:1075400018880591F9F766FB6C49F9F7BBFB002435 +:107550000490474625462646022EDFF8E4910BD1DB +:10756000059AB9F9040053790A335843F9F756FBE1 +:107570006349F9F75BFC44E0624B39F90500EB5EC7 +:10758000614918444FF4FA72FDF7EEFADFF8B4A13E +:10759000069B35F90A20595F801A0844F9F73EFB2B +:1075A0005A49F9F743FC8346FFF780FE30B1584A49 +:1075B0005146905D5A46FFF711FC8346DFF888A1DB +:1075C0009AF803202AB15846D8F84410F9F77AFB04 +:1075D00017E0059B39F905001A7914325043F9F781 +:1075E0001DFB4749F9F722FC9AF8043081464BB15C +:1075F000D8F848105846F9F765FB01464846F9F7B0 +:1076000059FA8146434B0136585FF9F707FB424B65 +:107610000437D968F9F756FB824651464846F9F7D0 +:1076200047FAF9698346F9F74DFBDFF82091049991 +:1076300007905846F9F746FBB96AF9F743FB54F847 +:107640000910F9F737FA354A3549FDF795FA44F844 +:107650000900DFF8FC90834654F809105046F9F70A +:1076600027FA44F809A0024604994FF07E5001928F +:10767000F9F7DCFB019A01461046F9F723FB294B89 +:10768000294A54F803C0A1588146604601920293EA +:10769000CDF80CC0F9F70EFA4946F9F70BFADDF808 +:1076A0000CC0029B019A214944F8039044F802C09F +:1076B000F9F7BCFB796BF9F705FB1D4A1D49FDF78E +:1076C0005BFA594681460798F9F7F4F94946F9F704 +:1076D000EFF907F033FA18494FF47A72FDF744FADC +:1076E000164B032E585304F1040405F102057FF4F0 +:1076F00033AF09B0BDE8F08F180D0020BD378635D7 +:1077000000004842FA1200200CFEFFFF000020415A +:10771000EA200108E80F00201C21002000007A4325 +:1077200000007AC3640F0020400F0020000040409A +:1077300000009643000096C318FCFFFF3221002092 +:107740004C2200202810002023220020340F00208B +:10775000980F00202DE9F04F002485B007468A4697 +:107760009346039306462546022DDFF87C814FEAB7 +:10777000450907D19AF80520B8F904301B32534364 +:107780005B1144E04D4A38F9150032F91520CBF170 +:10779000000102EB40005A46FDF7E6F9484B33F989 +:1077A0001520039B801A33F9151042180192FFF738 +:1077B0007DFD019AB8B14349104615F801C0CDF8D6 +:1077C00000C0F9F72BFA4049F9F730FBDDF800C0AB +:1077D00002463B496046FFF701FB3B49F9F772FA65 +:1077E000F9F736FC02463949C87868B99AF80400B6 +:1077F00038F909301B30434309791B1139B1797CC1 +:107800004A4303EB222302E0FB795A431311304A27 +:10781000785D32F90980042298FBF2F8C8EB03087E +:1078200000FB08F0DFF8C4C0C0110290BCF80000F3 +:10783000284B00FB08F0E258B17AC01201FB00208F +:107840002549E0504FF400120193CDF800C0FDF738 +:107850008BF9019BDDF800C0E050204B4FF6FF7222 +:10786000E15844F80380BCF80030C1EB08011B0963 +:10787000B2FBF3F35943DFF878C0194B891154F880 +:10788000038054F80C20E150029B424403EB60302B +:10789000337D0A445A430135124B00EB2222032D5B +:1078A00044F80C8023F8092006F1010604F10404D1 +:1078B0007FF45AAF05B0BDE8F08F00BFFA12002088 +:1078C00028100020EA200108000020412322002087 +:1078D000E80F0020700F00200000E0FF840F002060 +:1078E000580F0020322100204C220020180D0020CB +:1078F000A40F00200128054B03D0022803D0044A1E +:1079000002E0044A00E0044A1A60704718000020B0 +:10791000C5720008557700083575000800000000A2 :107920002DE9F84F384E04463768384607F0D0F84E :107930000546384607F040F976688046304607F03D :10794000C7F88346304607F037F9D4F80490064666 @@ -1961,7 +1961,7 @@ :107A70001C4BD868F8F7DAFC0DA3D3E90023F8F71C :107A800029FD0DA3D3E90023F8F724FDF8F7BCFF87 :107A9000154B1860082002F04BFC18B1BDE81040EF -:107AA000FEF70EBE10BD00BF3B597E90A9E7814096 +:107AA000FEF70CBE10BD00BF3B597E90A9E7814098 :107AB000399D52A246DF913F000000A0F7C6B03EBC :107AC00012000020C903683FD80F00200AE81C41BB :107AD00000401C4658210020D81F002000006144AF @@ -2022,8 +2022,8 @@ :107E40006C210020D81F00202322002000100020D9 :107E5000120000203661823C4C210020FC0F0020E3 :107E6000BC0F0020181000202DE9F04F89B0FEF75C -:107E7000D3FC022002F05CFA9B4D9C4F002800F0DE -:107E8000B2819B48FEF7F4FAFEF7A6FE994C06462F +:107E7000D1FC022002F05CFA9B4D9C4F002800F0E0 +:107E8000B2819B48FEF7F2FAFEF7A4FE994C064633 :107E90002368C3EB00094846F8F7BCFE964B196807 :107EA000F8F710FF954A266092F86030002603909C :107EB00002933446B246285FF8F7B0FE0399F8F70C @@ -2103,9 +2103,9 @@ :1083500096FBF3F6301A5044BDE8F0872810002051 :1083600068210020642100200CFEFFFFD81F0020A0 :10837000D4FEFFFF1410002000E0FCFF2DE9F04FB9 -:1083800085B0FEF729FC674B46F2A7121E68861BD4 -:10839000964240F2C2801860FEF7A0F8624C28B9FD -:1083A000FEF752F9614A002323601360FEF700F9DB +:1083800085B0FEF727FC674B46F2A7121E68861BD6 +:10839000964240F2C2801860FEF79EF8624C28B9FF +:1083A000FEF750F9614A002323601360FEF7FEF8E0 :1083B0005F4B604918600246086800930192F8F725 :1083C00029FC5D490746F8F77DFC5C4982468868D0 :1083D000F8F724FC5A4905460868F8F71FFC0146DF @@ -2285,7 +2285,7 @@ :108EB000003018BF012070471811002044F25063A1 :108EC000984203DDA0F50C40A0387047034B984250 :108ED000BCBF00F50C40A030704700BFB0B9FFFF29 -:108EE00010B5044C002320702361FDF78FFE6061F4 +:108EE00010B5044C002320702361FDF78DFE6061F6 :108EF00010BD00BF5813002010B5F7F78FFE0021FA :108F00000446F8F79BF808B1204601E004F1004060 :108F10000549F7F78BFF0549F7F7D4FE05F0D8FDB3 @@ -2310,15 +2310,15 @@ :1090400030BD002030BD00BFFF120020014B186072 :10905000704700BFCC120020F8B52B4B2B4C1B786F :1090600013B1012B0AD04CE06278294B03EB0213B9 -:10907000284A59681068FDF763FD3FE0254D2868D0 -:10908000FDF763FD2E4600283BD02378012B1ED12F -:10909000FDF7BCFD63690646C31A632B33D9236908 +:10907000284A59681068FDF761FD3FE0254D2868D2 +:10908000FDF761FD2E4600283BD02378012B1ED131 +:10909000FDF7BAFD63690646C31A632B33D923690A :1090A000042B12D81A4F286807EB03135968FDF7F1 -:1090B00047FD6378286807EB0317B968FDF72BFDB8 +:1090B00045FD6378286807EB0317B968FDF729FDBC :1090C00023696661013323611BE0022017E02369F5 :1090D0003BB962780E4B286803EB02135968FDF721 -:1090E0002FFD2369094D8B2B08D80B4A3068D15CC2 -:1090F000FDF70CFD2B6901332B6102E00320FFF724 +:1090E0002DFD2369094D8B2B08D80B4A3068D15CC4 +:1090F000FDF70AFD2B6901332B6102E00320FFF726 :10910000EFFE00236360F8BDF91200205813002021 :109110007C270108C4120020EE26010810B50B4C74 :10912000E37A8BB10A4B1B78042B0DD9094A0A4B01 @@ -2328,8 +2328,8 @@ :10916000E4120020000000002DE9F04F994B8BB075 :109170001B68BBB9984C2378013B032B00F2CB85CD :10918000DFE813F08F058F05A90592052068FDF72C -:10919000D2FC924B04461B78012B00F0DD8008D3F3 -:1091A000022B06D08B4C2068FDF7C0FC0028EDD1C7 +:10919000D0FC924B04461B78012B00F0DD8008D3F5 +:1091A000022B06D08B4C2068FDF7BEFC0028EDD1C9 :1091B000E0E7242C07D18A4A00231370894A1370F0 :1091C000894A1370C4E02C2C02D02A2C40F08380F2 :1091D000844E864B3278824D002098542A788449F8 @@ -2400,7 +2400,7 @@ :1095E00023220020D412002010220020CE210020AF :1095F000AC12002055130020B8210020E6210020E5 :1096000000220020122200200023002B3FF4CAADCC -:109610008B4CA368E360FDF7F9FAA060202000F00E +:109610008B4CA368E360FDF7F7FAA060202000F010 :1096200091FE884B884C1A78012A0CBF0022012237 :109630001A70E37A002B3FF4B5AD844B1B78042BF2 :109640007FF6B0ADA37803B92373227B12B90BB1B7 @@ -2414,8 +2414,8 @@ :1096C000F6F008FB01016A481FFA8CFC1950059856 :1096D00003EB020B012825F802CF164606D1ACF1A8 :1096E000020CBCF5797F98BFCBF800100433082B2F -:1096F000C5D1FDF78BFA5F4F5F4D3B68C01AF7F796 -:1097000089FA5E49F7F792FB2860FDF77FFA386027 +:1096F000C5D1FDF789FA5F4F5F4D3B68C01AF7F798 +:1097000089FA5E49F7F792FB2860FDF77DFA386029 :109710002F684FF07E513846F7F772FC08B94FF0CA :109720007E5706AA2F60564B009207AA019296E830 :1097300003000CCBFFF7FEFB069A64235149B2FBF2 @@ -2507,8 +2507,8 @@ :109C9000334B01221A70334B1A882D4B1A80FFF771 :109CA00081BAFFF7D9F936E06368052201336360B2 :109CB00063780133DBB2B3FBF2F202EB82029B1A50 -:109CC0006370FCF7A3FF284A00231370274AA060A3 -:109CD000D37201200BE0FCF799FFA36840F6C41291 +:109CC0006370FCF7A1FF284A00231370274AA060A5 +:109CD000D37201200BE0FCF797FFA36840F6C41293 :109CE000C01A904217D9202000F034FB0420FFF75F :109CF000F7F810E09B781E4A522B7FF4DFAAD37846 :109D00004D2B7FF4DBAA1379432B7FF4D7AA0223D0 @@ -2538,7 +2538,7 @@ :109E8000214C18600025C3686570204E06EB051054 :109E90004068B046984206D00135EDB2042DF4D9A1 :109EA0000023637000E06570194B1A4E002031707A -:109EB0001A60FFF715F8FCF7A9FE33780025AB42CE +:109EB0001A60FFF715F8FCF7A7FE33780025AB42D0 :109EC000A06048460CBF012703276560FFF784FFA9 :109ED00066783B4608EB0616009510202946726806 :109EE00001F0C4FD0C4B186030B94FF4807003B022 @@ -2546,13 +2546,13 @@ :109F0000FEF7EEBF80130020581300207C270108C5 :109F1000CC120020F9120020C4120020F7B5244B07 :109F20001D78032D3ED1202001F074FC214E044603 -:109F300038B101F01DFE336820461969FCF700FEB8 +:109F300038B101F01DFE336820461969FCF7FEFDBB :109F400009E03368009021461A6920202B4601F071 :109F50008DFD044640B3184B08221A6110221A6185 -:109F6000164D2868FCF7E2FD50B1134E08277761C3 -:109F70002868FCF7E0FD01462046FCF7C7FD376185 -:109F80002046FCF7D3FD0028EAD00B4E102777615E -:109F900020462D68FCF7CFFD01462846FCF7B6FDAC +:109F6000164D2868FCF7E0FD50B1134E08277761C5 +:109F70002868FCF7DEFD01462046FCF7C5FD376189 +:109F80002046FCF7D1FD0028EAD00B4E1027776160 +:109F900020462D68FCF7CDFD01462846FCF7B4FDB0 :109FA0003761DDE7022000E0284603B0F0BD00BFC6 :109FB0005813002080130020000C0140C412002020 :109FC000F7B50368174C184D23600B68174E636094 @@ -2704,7 +2704,7 @@ :10A8E0004FF40040F9F7D4FE08B10823237001208B :10A8F000F9F7CEFE08B10C23237010BDD1A80008D3 :10A90000034B53F82100400800F5777080B2704780 -:10A910004C14002038B50446FCF75EF90F4B40F6A6 +:10A910004C14002038B50446FCF75CF90F4B40F6A8 :10A92000C4111A681860821A8A420D4A84BF002135 :10A93000117013780BB90F2C0FD10A480021017048 :10A940004BB1094D182B1D4405F8014C03D10123CF @@ -2731,7 +2731,7 @@ :10AA90001B7C01F0010403F00F03DB0140EA84207A :10AAA00043EA51019062D162012010BD4914002097 :10AAB0007C1400204C140020024B53F82100C0F3FA -:10AAC000CF007047CC14002010B50446FCF784F882 +:10AAC000CF007047CC14002010B50446FCF782F884 :10AAD000144B1A681860821AB2F57A6F124A84BF52 :10AAE00000211170137823B9A82C1AD10F490B70CB :10AAF00006E0022B02D10E490C7001E0242B01D894 @@ -2750,7 +2750,7 @@ :10ABC00012F8024C40EA0424074840F823400133BD :10ABD000EFE7012010BD00BFC21400209D1400202B :10ABE0009C140020A0140020CC140020114B10B5A0 -:10ABF00001221A700446FBF7EFFF0F4A0146136863 +:10ABF00001221A700446FBF7EDFF0F4A0146136865 :10AC00001160C31A0D4841F28832934203600C4B25 :10AC100084BF00221A701B780A4AE4B20F2BD45466 :10AC200003D1094B01221A7010BD054A013313707C @@ -2800,27 +2800,27 @@ :10AEE00080B1FFF74BFF08B100F0ACF8FFF750FF5F :10AEF00008B100F02BFBFFF755FF18B1BDE8084083 :10AF000000F0E0BB08BD00BF7015002038B5064C4E -:10AF100005465E212068FBF7F9FD20682946BDE85B -:10AF20003840FBF7F3BD00BF84150020024B5E21C3 -:10AF30001868FBF7EBBD00BF8415002010B50A4C64 -:10AF40005E280146206805D15D21FBF7DFFD206802 -:10AF50003E2105E05D2903D1FBF7D8FD20683D21A6 -:10AF6000BDE81040FBF7D2BD8415002010B50446A3 +:10AF100005465E212068FBF7F7FD20682946BDE85D +:10AF20003840FBF7F1BD00BF84150020024B5E21C5 +:10AF30001868FBF7E9BD00BF8415002010B50A4C66 +:10AF40005E280146206805D15D21FBF7DDFD206804 +:10AF50003E2105E05D2903D1FBF7D6FD20683D21A8 +:10AF6000BDE81040FBF7D0BD8415002010B50446A5 :10AF7000C0B2FFF7E3FFC4F30720BDE81040FFF7BE :10AF8000DDBF0000014B1860704700BF7C1500203A -:10AF900010B5084B084C19782068FBF7DBFD074B10 -:10AFA00020681968FBF7CCFD20680421BDE810403B +:10AF900010B5084B084C19782068FBF7D9FD074B12 +:10AFA00020681968FBF7CAFD20680421BDE810403D :10AFB00000F05CBC7B150020841500207415002077 :10AFC00073B5042000F026FC144C01462060144E9A :10AFD000144D90B143794FF41651337083682B6050 -:10AFE000FBF7AEFD20680221FBF7B4FD20680421C9 +:10AFE000FBF7ACFD20680221FBF7B2FD20680421CD :10AFF00002B0BDE8704000F029BC0B4B4FF4165274 :10B000001B6804209B780093022300F02FFD4379F6 :10B010002060337083682B6002B070BD84150020FF :10B020007B150020741500207C15002008B5044B0A -:10B030001868FBF77BFDD0F1010038BF002008BD88 +:10B030001868FBF779FDD0F1010038BF002008BD8A :10B04000841500202DE9F843FFF7F0FF002800F0F9 -:10B050004481FBF7DBFDA24B1A68821A7C2A40F27E +:10B050004481FBF7D9FDA24B1A68821A7C2A40F280 :10B060003C81A04E1860337800240133337004F122 :10B070002400C0B2FFF74AFF9B4B33F91400F5F7E9 :10B08000CDFD9A4B05461888F5F7C8FD01462846C0 @@ -2856,7 +2856,7 @@ :10B26000B8BF5B4293FBF7F797FBF5F305FB137051 :10B2700000B2FFF77BFE2220FFF748FE6368002B39 :10B28000ACBF45205720FFF771FEFFF74FFE337824 -:10B29000282B22D1134B00221A70FBF7B7FC4FF476 +:10B29000282B22D1134B00221A70FBF7B5FC4FF478 :10B2A0007A763C24B0FBF6F61720FFF72FFEB6FBAC :10B2B000F4F5B5FBF4F004FB1050000200B2FFF708 :10B2C00055FE1820FFF722FE04FB156000B2FFF7C1 @@ -2865,8 +2865,8 @@ :10B2F00000007A44F80F0020700D00204221002049 :10B30000E0200020881B002078150020F821002074 :10B3100010000020A08601004FF416507047000076 -:10B3200010B5054C2068FBF701FC18B12068FBF74D -:10B3300002FCF6E710BD00BFCC150020DFF890C07E +:10B3200010B5054C2068FBF7FFFB18B12068FBF750 +:10B3300000FCF6E710BD00BFCC150020DFF890C080 :10B340002DE9F043204E91FBFCF406FB0418062780 :10B35000C90F07FB08F8417292FBFCF106FB0126BE :10B360001A4B04EB840498FBF3F903FB19887E4322 @@ -2886,7 +2886,7 @@ :10B44000CE210020D8210020CA210020E4210020A4 :10B45000044A00231278837003718277C3770275E0 :10B4600043757047881B002010B5084B084C1978AD -:10B470002068FBF76FFB074B20681968FBF760FB40 +:10B470002068FBF76DFB074B20681968FBF75EFB44 :10B4800020680421BDE8104000F0F0B9D21500207A :10B49000CC150020BC150020F8B5104C104B2C2703 :10B4A0001860002120463A4605F068FC8E23637040 @@ -2895,27 +2895,27 @@ :10B4D0002670E37084F82B50F8BD00BF9015002053 :10B4E000D8150020DC15002073B5042000F092F977 :10B4F000134C01462060134E134D90B143794FF425 -:10B500009641337083682B60FBF71AFB206801219A -:10B51000FBF720FB2068042102B0BDE8704000F07A +:10B500009641337083682B60FBF718FB206801219C +:10B51000FBF71EFB2068042102B0BDE8704000F07C :10B5200095B900904FF496420123042000F09EFA52 :10B5300043792060337083682B6002B070BD00BF18 :10B54000CC150020D2150020BC1500202DE9F843B1 -:10B55000FBF742FB4C4D4D4A2B680446C31A9342FD +:10B55000FBF740FB4C4D4D4A2B680446C31A9342FF :10B5600006D94B48FFF774FF4A48FFF733FF2C60BA :10B57000494E4A4F96F80090B9F1000F0ED1DFF80E -:10B580002881D8F80000FBF7D1FA012806D9022853 +:10B580002881D8F80000FBF7CFFA012806D9022855 :10B59000434D46D0FFF7C4FE01232B703D68DFF812 :10B5A000FCC0002D6ED037783B4A3E4E3FB1336829 :10B5B00040F6B731E31A8B420BD8BDE8F88301237C -:10B5C0001370394B02211868FBF7C4FA374B1F7010 +:10B5C0001370394B02211868FBF7C2FA374B1F7012 :10B5D00024E0374F34483B784BB900680121CCF860 -:10B5E00000301370FBF7B6FAFFF79AFE16E0013B46 +:10B5E00000301370FBF7B4FAFFF79AFE16E0013B48 :10B5F000D9B239702D4A2F4B19B911784D1C1570DD :10B6000006E015F8011B1778CCF800500F441770AE -:10B610001A78006801321A70FBF778FA3460BDE8D6 +:10B610001A78006801321A70FBF776FA3460BDE8D8 :10B62000F8832A78244B1AB11C6085F80090B5E79E :10B630001B68E31AB3F57A6FB0D30123D8F8000082 -:10B640002B70FBF778FA0546D8F80000FBF773FA81 +:10B640002B70FBF776FA0546D8F80000FBF771FA85 :10B65000802DA3D18A2802D08E280AD09EE72020F0 :10B66000FEF766FE002899D03378002B96D1094B5F :10B6700003E03378002B91D1054B3B600C4B2D221E @@ -2991,23 +2991,23 @@ :10BAD000B9F1030F28D8DFE809F002050E10009431 :10BAE000134801E013480094394632464346F7F7BD :10BAF000E5FE04460BE0002000E001203946234625 -:10BB00003246F7F7C9FC41460446FBF723F854B127 +:10BB00003246F7F7C9FC41460446FBF721F854B129 :10BB1000094B84F8049043F82B406B6820465C6026 :10BB20005146FFF793FE204607B0BDE8F08F00BFF7 :10BB300000380140004400401C16002038B5064C77 :10BB400005462060FFF768FF284601F095FD206854 :10BB5000BDE8384000F0E6BE2C160020034B1B78F1 :10BB60000BB100F0E7BD01F021BE00BF4016002080 -:10BB700010B504462046FAF7E8FF18B90A20FBF78B -:10BB800056F8F7E710BD0000232801D100F0D2BD20 -:10BB9000044B1B681B7D834202D10120FBF706B9D1 +:10BB700010B504462046FAF7E6FF18B90A20FBF78D +:10BB800054F8F7E710BD0000232801D100F0D2BD22 +:10BB9000044B1B681B7D834202D10120FBF704B9D3 :10BBA000704700BF2C16002010B5441E14F8011F6A -:10BBB00021B1034B1868FAF7A9FFF7E710BD00BFE2 +:10BBB00021B1034B1868FAF7A7FFF7E710BD00BFE4 :10BBC000781600200148FFF7EFBF00BF142A0108D4 :10BBD00010B50748FFF7E8FF0024064B06481A197E :10BBE000E15852680C34F9F7FFF8C02CF5D110BDBC :10BBF000522A010830290108682A010870B5FBF7AC -:10BC000005F8244B4FF47A711A78234BB0FBF1F10D +:10BC000003F8244B4FF47A711A78234BB0FBF1F10F :10BC10001B782248F9F7E8F8FEF7A4FB204B05460D :10BC20001968204B2048B1FBF3F1F9F7DDF8002447 :10BC30001E4AE3B252F8231049B1012202FA03F37B @@ -3033,7 +3033,7 @@ :10BD70000648E1682269F9F737F803B030BD00BF23 :10BD8000D72A0108D62A0108142B0108102B010814 :10BD900008B50648FFF708FF054B1868FFF7E8FEEF -:10BDA000BDE808400020FBF701B800BF172B0108D1 +:10BDA000BDE808400020FAF7FFBF00BF172B0108CD :10BDB0007816002008B50748FFF7F6FE064B93F803 :10BDC0004804F8F7FFFBF8F70DFCBDE80840FFF763 :10BDD000DFBF00BF262B01088C1B00207FB5044667 @@ -3189,8 +3189,8 @@ :10C73000402D01082DE9F0476C4B86B01A789946D8 :10C740006B4F7AB901233868022189F80030FFF76E :10C750007DF83868F8F774FB6648FFF725FA6648F5 -:10C76000FFF722FA3868FAF7E1F9002800F0BB80F9 -:10C770005F4B624C1868FAF7DEF90928014601D0D0 +:10C76000FFF722FA3868FAF7DFF9002800F0BB80FB +:10C770005F4B624C1868FAF7DCF90928014601D0D2 :10C780003F2852D14FF00008D4F800A05C4E454637 :10C79000BAF1000F05D05B483168524604F014FF2F :10C7A00010B9B04605B93546574B0C369E42EFD30B @@ -3199,9 +3199,9 @@ :10C7D00030B92D2B04D82026CE542260885402E094 :10C7E000CE541346EAE723681BB1454501D15546AF :10C7F00011E04648FFF7D8F9454508D855F80C0B25 -:10C80000FFF7D2F938680921FAF780F9F4E73A48D6 +:10C80000FFF7D2F938680921FAF77EF9F4E73A48D8 :10C81000FFF7CAF9002523689D42A3D2394B386837 -:10C82000595DFAF773F90135F5E723682BB9042848 +:10C82000595DFAF771F90135F5E723682BB904284A :10C8300036D13448FFF7AAFB55E00C2801D1344823 :10C840008BE70A2901D00D2944D13248FFF7ACF912 :10C850002C4D22680023AB5404932F4B03A8009364 @@ -3212,7 +3212,7 @@ :10C8A0000C28CCD07F2903D15CE72F2B3FF65AAF61 :10C8B000A1F12002D2B25E2A3FF654AF13B920296B :10C8C0003FF450AF5A1C22600E4A3868D154FAF730 -:10C8D0001DF947E77F29E8D10A4A013B002123607F +:10C8D0001BF947E77F29E8D10A4A013B0021236081 :10C8E000D1540F483CE706B0BDE8F0874016002061 :10C8F000781600200E2F0108462F0108741600201C :10C900003029010841160020F02901084B2F0108A9 @@ -3220,17 +3220,17 @@ :10C920007C2F010837B505460220FEF773FF064C41 :10C930000146206030B90090AA6802200323FFF767 :10C9400095F8206003B030BD78160020F8B5154E7C -:10C95000154C164D0746C1B230682170FAF7D6F86B +:10C95000154C164D0746C1B230682170FAF7D4F86D :10C9600022782B78C7F30721534030682B70217051 -:10C97000FAF7CCF822782B78C7F307415340306898 -:10C980002B702170FAF7C2F822782B78390E5340B9 -:10C9900030682B702170FAF7B9F82B782278534061 +:10C97000FAF7CAF822782B78C7F30741534030689A +:10C980002B702170FAF7C0F822782B78390E5340BB +:10C9900030682B702170FAF7B7F82B782278534063 :10C9A0002B70F8BD84160020E51600207C160020B0 :10C9B000F8B50C4E0C4D0D4CC1B2074630682970CD -:10C9C000FAF7A4F82A782378C7F307215340306890 -:10C9D00023702970FAF79AF823782A785340237045 +:10C9C000FAF7A2F82A782378C7F307215340306892 +:10C9D00023702970FAF798F823782A785340237047 :10C9E000F8BD00BF84160020E41600207C1600204D -:10C9F000054B10B5044621461868FAF787F8034B33 +:10C9F000054B10B5044621461868FAF785F8034B35 :10CA00001A7854401C7010BD841600207C1600203B :10CA1000034A1378591C1170024AD05C704700BF5A :10CA20007E1600209F16002010B5FFF7F1FF044688 @@ -3412,7 +3412,7 @@ :10D520000CB1214B1C601F48214B0222011D1A70B7 :10D53000FCF746FD4BE01D4B9B78002B47D1F7F7DE :10D54000B9F842E0194B9B78002B40D14FF4C870DA -:10D55000F8F7A0FE3BE0154B9A78002A37D101225C +:10D55000F8F79EFE3BE0154B9A78002A37D101225E :10D560009A7334E07A2200207E220020D821002005 :10D57000E42100207C1300202810002042210020FC :10D58000881B00207C220020D81F002000002041A2 @@ -3450,7 +3450,7 @@ :10D780000124F3E72A68002AEED1074B1860EBE783 :10D7900002B0BDE8F041FDF7BDBF00BF8916002013 :10D7A0008C1B00207F1600208416002010B5304C02 -:10D7B0002068F9F7BBF9002858D02068F9F7BBF9C1 +:10D7B0002068F9F7B9F9002858D02068F9F7B9F9C5 :10D7C0002C4C034622786AB9B0F1240253425341EB :10D7D0002370002BEBD1284B9B78002BE7D1FEF771 :10D7E000D3F9E4E7012A04D14D2814BF0023022312 @@ -3469,8 +3469,8 @@ :10D8B000236010BDE0160020DC420108881600201D :10D8C0002DE9F04106460F4690460025EBB2434550 :10D8D00018D20024E3B2B3420FD20B4B0120DA6816 -:10D8E000013482F00802DA60F9F74EF93846F9F7A8 -:10D8F0009EF90020F9F748F9ECE73C20F9F797F991 +:10D8E000013482F00802DA60F9F74CF93846F9F7AA +:10D8F0009CF90020F9F746F9ECE73C20F9F795F997 :10D900000135E3E7BDE8F081000C01400F4B1A68D8 :10D9100042F001021A6059680D4A0A405A601A68BA :10D9200022F0847222F480321A601A6822F4802273 @@ -4771,8 +4771,8 @@ :102A0000753701087C370108873701088C370108C2 :102A1000000000004166726F333220434C4920763B :102A2000657273696F6E20322E32204D61792032CB -:102A3000382032303134202F2032303A30353A319C -:102A400034202D2028636C65616E666C696768743C +:102A3000382032303134202F2032303A30363A319B +:102A400036202D2028636C65616E666C696768743A :102A50002900417661696C61626C6520636F6D6D00 :102A6000616E64733A0D0A0025730925730D0A001F :102A700053797374656D20557074696D653A2025BE @@ -5270,7 +5270,7 @@ :08492C00C51C0108350100085B :044934001101000865 :10493800030300000000803F0000803F0000803F2C -:104948000301000101000000C97200080000803F57 +:104948000301000101000000C57200080000803F5B :104958000000000000000000DC05DC05DC05DC05CB :10496800DC05DC05DC05DC050000803F01010000FA :10497800000000000000000000000000010000002E From 5913266ce0d34d2438384a0c791a697785d5f18f Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Wed, 28 May 2014 20:36:53 +0100 Subject: [PATCH 15/16] Update autotune comments, defaults and functional description. Add reference to sources. --- src/flight_autotune.c | 59 +++++++++++++++++++++++++++++++++++-------- 1 file changed, 48 insertions(+), 11 deletions(-) diff --git a/src/flight_autotune.c b/src/flight_autotune.c index a90dab720c..4da107fd6f 100644 --- a/src/flight_autotune.c +++ b/src/flight_autotune.c @@ -12,14 +12,51 @@ extern int16_t debug[4]; -// To adjust how aggressive the tuning is, adjust the AUTOTUNEMAXOSCILLATION value. A larger -// value will result in more aggressive tuning. A lower value will result in softer tuning. -// It will rock back and forth between -AUTOTUNE_TARGET_ANGLE and AUTOTUNE_TARGET_ANGLE degrees -// AUTOTUNE_D_MULTIPLIER is a multiplier that puts in a little extra D when autotuning is done. This helps damp -// the wobbles after a quick angle change. -// Always autotune on a full battery. +/* + * Authors + * Brad Quick - initial implementation in BradWii + * Dominic Clifton - baseflight port & cleanup. + * + * Autotune in BradWii thread here: http://www.rcgroups.com/forums/showthread.php?t=1922423 + * + * We start with two input parameters. The first is our target angle. By default it's 20 degrees, so we will bank to 20 degrees, + * see how the system reacts, then bank to -20 degrees and evaluate again. We repeat this over and over. The second input is + * how much oscillation we can tolerate. This can range from 2 degrees to 5 or more degrees. This defaults to 4 degrees. The + * higher this value is, the more agressive the result of the tuning will be. + * + * First, we turn the I gain down to zero so that we don't have to try to figure out how much overshoot is caused by the I term + * vs. the P term. + * + * Then, we move to the target of 20 degrees and analyze the results. Our goal is to have no overshoot and to keep the bounce + * back within the 4 degrees. By working to get zero overshoot, we can isolate the effects of the P and D terms. If we don't + * overshoot, then the P term never works in the opposite direction, so we know that any bounce we get is caused by the D term. + * + * If we overshoot the target 20 degrees, then we know our P term is too high or our D term is too low. We can determine + * which one to change by looking at how much bounce back (or the amplitude of the oscillation) we get. If it bounces back + * more than the 4 degrees, then our D is already too high, so we can't increase it, so instead we decrease P. + * + * If we undershoot, then either our P is too low or our D is too high. Again, we can determine which to change by looking at + * how much bounce we get. + * + * Once we have the P and D terms set, we then set the I term by repeating the same test above and measuring the overshoot. + * If our maximum oscillation is set to 4 degrees, then we keep increasing the I until we get an overshoot of 2 degrees, so + * that our oscillations are now centered around our target (in theory). + * + * In the BradWii software, it alternates between doing the P and D step and doing the I step so you can quit whenever you + * want without having to tell it specifically to do the I term. The sequence is actually P&D, P&D, I, P&D, P&D, I... + * + * Note: The 4 degrees mentioned above is the value of AUTOTUNE_MAX_OSCILLATION. In the BradWii code at the time of writing + * the default value was 1.0f instead of 4.0f. + * + * To adjust how aggressive the tuning is, adjust the AUTOTUNEMAXOSCILLATION value. A larger value will result in more + * aggressive tuning. A lower value will result in softer tuning. It will rock back and forth between -AUTOTUNE_TARGET_ANGLE + * and AUTOTUNE_TARGET_ANGLE degrees + * AUTOTUNE_D_MULTIPLIER is a multiplier that puts in a little extra D when autotuning is done. This helps damp the wobbles + * after a quick angle change. + * Always autotune on a full battery. + */ -#define AUTOTUNE_MAX_OSCILLATION 1.0f +#define AUTOTUNE_MAX_OSCILLATION_ANGLE 4.0f #define AUTOTUNE_TARGET_ANGLE 20.0f #define AUTOTUNE_D_MULTIPLIER 1.2f #define AUTOTUNE_SETTLING_DELAY_MS 250 // 1/4 of a second. @@ -154,7 +191,7 @@ float autotune(angle_index_t angleIndex, const rollAndPitchInclination_t *inclin } else if (secondPeakAngle > 0) { if (cycleCount == 0) { // when checking the I value, we would like to overshoot the target position by half of the max oscillation. - if (currentAngle - targetAngle < AUTOTUNE_MAX_OSCILLATION / 2) { + if (currentAngle - targetAngle < AUTOTUNE_MAX_OSCILLATION_ANGLE / 2) { pid.i *= AUTOTUNE_INCREASE_MULTIPLIER; } else { pid.i *= AUTOTUNE_DECREASE_MULTIPLIER; @@ -189,7 +226,7 @@ float autotune(angle_index_t angleIndex, const rollAndPitchInclination_t *inclin bool timedOut = signedDiff >= 0L; // stop looking for the 2nd peak if we time out or if we change direction again after moving by more than half the maximum oscillation - if (timedOut || (oscillationAmplitude > AUTOTUNE_MAX_OSCILLATION / 2 && currentAngle > firstPeakAngle)) { + if (timedOut || (oscillationAmplitude > AUTOTUNE_MAX_OSCILLATION_ANGLE / 2 && currentAngle > firstPeakAngle)) { // analyze the data // Our goal is to have zero overshoot and to have AUTOTUNEMAXOSCILLATION amplitude @@ -198,7 +235,7 @@ float autotune(angle_index_t angleIndex, const rollAndPitchInclination_t *inclin debug[0] = 1; #ifdef PREFER_HIGH_GAIN_SOLUTION - if (oscillationAmplitude > AUTOTUNE_MAX_OSCILLATION) { + if (oscillationAmplitude > AUTOTUNE_MAX_OSCILLATION_ANGLE) { // we have too much oscillation, so we can't increase D, so decrease P #endif pid.p *= AUTOTUNE_DECREASE_MULTIPLIER; @@ -214,7 +251,7 @@ float autotune(angle_index_t angleIndex, const rollAndPitchInclination_t *inclin // undershot debug[0] = 2; - if (oscillationAmplitude > AUTOTUNE_MAX_OSCILLATION) { + if (oscillationAmplitude > AUTOTUNE_MAX_OSCILLATION_ANGLE) { // we have too much oscillation pid.d *= AUTOTUNE_DECREASE_MULTIPLIER; } else { From e083a3266d33d6566d36b8270a5c28f8be4ce586 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Fri, 30 May 2014 09:01:37 +0100 Subject: [PATCH 16/16] Decreasing autotune max oscillation value since a value of 4 was found to always cause P to increase. --- src/flight_autotune.c | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/src/flight_autotune.c b/src/flight_autotune.c index 4da107fd6f..96e9c98d5a 100644 --- a/src/flight_autotune.c +++ b/src/flight_autotune.c @@ -56,7 +56,7 @@ extern int16_t debug[4]; * Always autotune on a full battery. */ -#define AUTOTUNE_MAX_OSCILLATION_ANGLE 4.0f +#define AUTOTUNE_MAX_OSCILLATION_ANGLE 2.0f #define AUTOTUNE_TARGET_ANGLE 20.0f #define AUTOTUNE_D_MULTIPLIER 1.2f #define AUTOTUNE_SETTLING_DELAY_MS 250 // 1/4 of a second. @@ -237,15 +237,14 @@ float autotune(angle_index_t angleIndex, const rollAndPitchInclination_t *inclin #ifdef PREFER_HIGH_GAIN_SOLUTION if (oscillationAmplitude > AUTOTUNE_MAX_OSCILLATION_ANGLE) { // we have too much oscillation, so we can't increase D, so decrease P -#endif pid.p *= AUTOTUNE_DECREASE_MULTIPLIER; -#ifdef PREFER_HIGH_GAIN_SOLUTION } else { // we don't have too much oscillation, so we can increase D -#endif pid.d *= AUTOTUNE_INCREASE_MULTIPLIER; -#ifdef PREFER_HIGH_GAIN_SOLUTION } +#else + pid.p *= AUTOTUNE_DECREASE_MULTIPLIER; + pid.d *= AUTOTUNE_INCREASE_MULTIPLIER; #endif } else { // undershot