From a9b094dca6c9543b3f0d84a23e781af2a8d1402e Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Sat, 12 Oct 2013 02:04:08 +0000 Subject: [PATCH 01/56] fixing buzzer related compilation errors on OLIMEXINO target [by Dominic Clifton] moved alignSensors from drv_system to utils updating uvproj to keil5 git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@431 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- baseflight.uvproj | 35 ++++++++++++++++++++++++++++ src/drv_system.c | 59 ++++++++--------------------------------------- src/drv_system.h | 3 --- src/utils.c | 48 ++++++++++++++++++++++++++++++++++++++ src/utils.h | 2 ++ 5 files changed, 94 insertions(+), 53 deletions(-) diff --git a/baseflight.uvproj b/baseflight.uvproj index e9deda99e..a6d0cd2ce 100755 --- a/baseflight.uvproj +++ b/baseflight.uvproj @@ -30,6 +30,7 @@ SFD\ST\STM32F1xx\STM32F103xx.sfr + 0 0 @@ -97,6 +98,7 @@ 3 + 1 SARMCM3.DLL @@ -169,6 +171,10 @@ BIN\UL2CM3.DLL "" () + + + + 0 @@ -551,6 +557,7 @@ 11 + 1 @@ -596,6 +603,7 @@ 11 + 1 @@ -696,6 +704,7 @@ 11 + 0 @@ -822,6 +831,7 @@ 11 + 1 @@ -881,6 +891,7 @@ SFD\ST\STM32F1xx\STM32F103xx.sfr + 0 0 @@ -948,6 +959,7 @@ 3 + 1 SARMCM3.DLL @@ -1020,6 +1032,10 @@ BIN\UL2CM3.DLL "" () + + + + 0 @@ -1402,6 +1418,7 @@ 11 + 1 @@ -1447,6 +1464,7 @@ 11 + 1 @@ -1617,6 +1635,7 @@ 11 + 1 @@ -1676,6 +1695,7 @@ SFD\ST\STM32F10xx\STM32F10xxB.sfr + 0 0 @@ -1743,6 +1763,7 @@ 3 + 1 SARMCM3.DLL @@ -1815,6 +1836,10 @@ BIN\UL2CM3.DLL "" () + + + + 0 @@ -2142,6 +2167,7 @@ 11 + 1 @@ -2187,6 +2213,7 @@ 11 + 1 @@ -2232,6 +2259,7 @@ 11 + 1 @@ -2277,6 +2305,7 @@ 11 + 1 @@ -2327,6 +2356,7 @@ 11 + 1 @@ -2372,6 +2402,7 @@ 11 + 1 @@ -2427,6 +2458,7 @@ 11 + 1 @@ -2472,6 +2504,7 @@ 11 + 1 @@ -2582,6 +2615,7 @@ 11 + 0 @@ -2703,6 +2737,7 @@ 11 + 1 diff --git a/src/drv_system.c b/src/drv_system.c index b8285d655..2209ebd22 100755 --- a/src/drv_system.c +++ b/src/drv_system.c @@ -6,10 +6,12 @@ static volatile uint32_t usTicks = 0; static volatile uint32_t sysTickUptime = 0; // from system_stm32f10x.c void SetSysClock(void); +#ifdef BUZZER void systemBeep(bool onoff); static void beepRev4(bool onoff); static void beepRev5(bool onoff); void (* systemBeepPtr)(bool onoff) = NULL; +#endif static void cycleCounterInit(void) { @@ -87,16 +89,17 @@ void systemInit(void) #define AFIO_MAPR_SWJ_CFG_NO_JTAG_SW (0x2 << 24) AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_NO_JTAG_SW; +#ifdef BUZZER // Configure gpio // rev5 needs inverted beeper. oops. if (hse_value == 12000000) systemBeepPtr = beepRev5; else systemBeepPtr = beepRev4; - + BEEP_OFF; +#endif LED0_OFF; LED1_OFF; - BEEP_OFF; for (i = 0; i < gpio_count; i++) { if (hse_value == 12000000 && gpio_setup[i].cfg.mode == Mode_Out_OD) @@ -188,6 +191,7 @@ void systemReset(bool toBootloader) SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04; } +#ifdef BUZZER static void beepRev4(bool onoff) { if (onoff) { @@ -205,56 +209,11 @@ static void beepRev5(bool onoff) digitalLo(BEEP_GPIO, BEEP_PIN); } } +#endif void systemBeep(bool onoff) { +#ifdef BUZZER systemBeepPtr(onoff); -} - -void alignSensors(int16_t *src, int16_t *dest, uint8_t rotation) -{ - switch (rotation) { - case CW0_DEG: - dest[X] = src[X]; - dest[Y] = src[Y]; - dest[Z] = src[Z]; - break; - case CW90_DEG: - dest[X] = src[Y]; - dest[Y] = -src[X]; - dest[Z] = src[Z]; - break; - case CW180_DEG: - dest[X] = -src[X]; - dest[Y] = -src[Y]; - dest[Z] = src[Z]; - break; - case CW270_DEG: - dest[X] = -src[Y]; - dest[Y] = src[X]; - dest[Z] = src[Z]; - break; - case CW0_DEG_FLIP: - dest[X] = -src[X]; - dest[Y] = src[Y]; - dest[Z] = -src[Z]; - break; - case CW90_DEG_FLIP: - dest[X] = src[Y]; - dest[Y] = src[X]; - dest[Z] = -src[Z]; - break; - case CW180_DEG_FLIP: - dest[X] = src[X]; - dest[Y] = -src[Y]; - dest[Z] = -src[Z]; - break; - case CW270_DEG_FLIP: - dest[X] = -src[Y]; - dest[Y] = -src[X]; - dest[Z] = -src[Z]; - break; - default: - break; - } +#endif } diff --git a/src/drv_system.h b/src/drv_system.h index be5f889db..ca2871a5d 100755 --- a/src/drv_system.h +++ b/src/drv_system.h @@ -15,6 +15,3 @@ void systemReset(bool toBootloader); // current crystal frequency - 8 or 12MHz extern uint32_t hse_value; - -// sensor orientation -void alignSensors(int16_t *src, int16_t *dest, uint8_t rotation); diff --git a/src/utils.c b/src/utils.c index 2de9f351b..e755c9c57 100644 --- a/src/utils.c +++ b/src/utils.c @@ -10,3 +10,51 @@ int constrain(int amt, int low, int high) else return amt; } + +void alignSensors(int16_t *src, int16_t *dest, uint8_t rotation) +{ + switch (rotation) { + case CW0_DEG: + dest[X] = src[X]; + dest[Y] = src[Y]; + dest[Z] = src[Z]; + break; + case CW90_DEG: + dest[X] = src[Y]; + dest[Y] = -src[X]; + dest[Z] = src[Z]; + break; + case CW180_DEG: + dest[X] = -src[X]; + dest[Y] = -src[Y]; + dest[Z] = src[Z]; + break; + case CW270_DEG: + dest[X] = -src[Y]; + dest[Y] = src[X]; + dest[Z] = src[Z]; + break; + case CW0_DEG_FLIP: + dest[X] = -src[X]; + dest[Y] = src[Y]; + dest[Z] = -src[Z]; + break; + case CW90_DEG_FLIP: + dest[X] = src[Y]; + dest[Y] = src[X]; + dest[Z] = -src[Z]; + break; + case CW180_DEG_FLIP: + dest[X] = src[X]; + dest[Y] = -src[Y]; + dest[Z] = -src[Z]; + break; + case CW270_DEG_FLIP: + dest[X] = -src[Y]; + dest[Y] = -src[X]; + dest[Z] = -src[Z]; + break; + default: + break; + } +} diff --git a/src/utils.h b/src/utils.h index 4fca60f8c..aca00681b 100644 --- a/src/utils.h +++ b/src/utils.h @@ -1,3 +1,5 @@ #pragma once int constrain(int amt, int low, int high); +// sensor orientation +void alignSensors(int16_t *src, int16_t *dest, uint8_t rotation); From 6bbc8fdb2287bac9017bfd2976ce7f61921f895c Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Sat, 12 Oct 2013 06:57:31 +0000 Subject: [PATCH 02/56] fix accZ/shake detection when copter upside down. oops. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@432 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/imu.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/imu.c b/src/imu.c index c8c56ac10..91928e8f3 100755 --- a/src/imu.c +++ b/src/imu.c @@ -288,7 +288,7 @@ static void getEstimatedAttitude(void) EstM.A[axis] = (EstM.A[axis] * (float)mcfg.gyro_cmpfm_factor + magADC[axis]) * INV_GYR_CMPFM_FACTOR; } - if (abs(EstG.A[Z]) > accZ_25deg) + if (EstG.A[Z] > accZ_25deg) f.SMALL_ANGLES_25 = 1; else f.SMALL_ANGLES_25 = 0; From 37b73a057bf5484122aa86f097515728da7bc3be Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Sat, 12 Oct 2013 06:58:28 +0000 Subject: [PATCH 03/56] core.numRCChannels now set by RC drivers to show max inputs available. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@433 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/drv_pwm.c | 2 +- src/main.c | 3 ++- src/sbus.c | 1 + src/spektrum.c | 1 + 4 files changed, 5 insertions(+), 2 deletions(-) diff --git a/src/drv_pwm.c b/src/drv_pwm.c index 77dfc20aa..c833b9dcf 100755 --- a/src/drv_pwm.c +++ b/src/drv_pwm.c @@ -254,7 +254,7 @@ static void ppmCallback(uint8_t port, uint16_t capture) if (diff > 2700) { // Per http://www.rcgroups.com/forums/showpost.php?p=21996147&postcount=3960 "So, if you use 2.5ms or higher as being the reset for the PPM stream start, you will be fine. I use 2.7ms just to be safe." chan = 0; } else { - if (diff > 750 && diff < 2250 && chan < 8) { // 750 to 2250 ms is our 'valid' channel range + if (diff > 750 && diff < 2250 && chan < MAX_INPUTS) { // 750 to 2250 ms is our 'valid' channel range captures[chan] = diff; if (chan < 4 && diff > failsafeThreshold) GoodPulses |= (1 << chan); // if signal is valid - mark channel as OK diff --git a/src/main.c b/src/main.c index fe84b1cc5..36f369a84 100755 --- a/src/main.c +++ b/src/main.c @@ -80,8 +80,9 @@ int main(void) pwmInit(&pwm_params); - // configure PWM/CPPM read function. spektrum or sbus below will override that + // configure PWM/CPPM read function and max number of channels. spektrum or sbus below will override both of these, if enabled rcReadRawFunc = pwmReadRawRC; + core.numRCChannels = MAX_INPUTS; if (feature(FEATURE_SERIALRX)) { switch (mcfg.serialrx_type) { diff --git a/src/sbus.c b/src/sbus.c index e37ea25af..f9afd77e9 100644 --- a/src/sbus.c +++ b/src/sbus.c @@ -26,6 +26,7 @@ void sbusInit(rcReadRawDataPtr *callback) core.rcvrport = uartOpen(USART2, sbusDataReceive, 100000, MODE_RX); if (callback) *callback = sbusReadRawRC; + core.numRCChannels = SBUS_MAX_CHANNEL; } struct sbus_dat diff --git a/src/spektrum.c b/src/spektrum.c index 21388c28d..f5655dcef 100644 --- a/src/spektrum.c +++ b/src/spektrum.c @@ -37,6 +37,7 @@ void spektrumInit(rcReadRawDataPtr *callback) core.rcvrport = uartOpen(USART2, spektrumDataReceive, 115200, MODE_RX); if (callback) *callback = spektrumReadRawRC; + core.numRCChannels = SPEK_MAX_CHANNEL; } // Receive ISR callback From 9ebd82c5ef8ee593374d504f09a920709f652f7e Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Sat, 12 Oct 2013 07:03:01 +0000 Subject: [PATCH 04/56] merged in mwii2.3 generic servo handler. completely untested. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@434 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/cli.c | 21 -------------- src/config.c | 26 +---------------- src/main.c | 2 ++ src/mixer.c | 82 +++++++++++++++++++++++++++++++++------------------- src/mw.c | 5 +--- src/mw.h | 39 +++++-------------------- src/serial.c | 27 +++++++++++------ 7 files changed, 83 insertions(+), 119 deletions(-) diff --git a/src/cli.c b/src/cli.c index bcc7b0102..b65d79220 100644 --- a/src/cli.c +++ b/src/cli.c @@ -150,28 +150,7 @@ const clivalue_t valueTable[] = { { "rssi_aux_channel", VAR_INT8, &mcfg.rssi_aux_channel, 0, 4 }, { "yaw_direction", VAR_INT8, &cfg.yaw_direction, -1, 1 }, { "tri_unarmed_servo", VAR_INT8, &cfg.tri_unarmed_servo, 0, 1 }, - { "tri_yaw_middle", VAR_UINT16, &cfg.tri_yaw_middle, 0, 2000 }, - { "tri_yaw_min", VAR_UINT16, &cfg.tri_yaw_min, 0, 2000 }, - { "tri_yaw_max", VAR_UINT16, &cfg.tri_yaw_max, 0, 2000 }, - { "wing_left_min", VAR_UINT16, &cfg.wing_left_min, 0, 2000 }, - { "wing_left_mid", VAR_UINT16, &cfg.wing_left_mid, 0, 2000 }, - { "wing_left_max", VAR_UINT16, &cfg.wing_left_max, 0, 2000 }, - { "wing_right_min", VAR_UINT16, &cfg.wing_right_min, 0, 2000 }, - { "wing_right_mid", VAR_UINT16, &cfg.wing_right_mid, 0, 2000 }, - { "wing_right_max", VAR_UINT16, &cfg.wing_right_max, 0, 2000 }, - { "pitch_direction_l", VAR_INT8, &cfg.pitch_direction_l, -1, 1 }, - { "pitch_direction_r", VAR_INT8, &cfg.pitch_direction_r, -1, 1 }, - { "roll_direction_l", VAR_INT8, &cfg.roll_direction_l, -1, 1 }, - { "roll_direction_r", VAR_INT8, &cfg.roll_direction_r, -1, 1 }, { "gimbal_flags", VAR_UINT8, &cfg.gimbal_flags, 0, 255}, - { "gimbal_pitch_gain", VAR_INT8, &cfg.gimbal_pitch_gain, -100, 100 }, - { "gimbal_roll_gain", VAR_INT8, &cfg.gimbal_roll_gain, -100, 100 }, - { "gimbal_pitch_min", VAR_UINT16, &cfg.gimbal_pitch_min, 100, 3000 }, - { "gimbal_pitch_max", VAR_UINT16, &cfg.gimbal_pitch_max, 100, 3000 }, - { "gimbal_pitch_mid", VAR_UINT16, &cfg.gimbal_pitch_mid, 100, 3000 }, - { "gimbal_roll_min", VAR_UINT16, &cfg.gimbal_roll_min, 100, 3000 }, - { "gimbal_roll_max", VAR_UINT16, &cfg.gimbal_roll_max, 100, 3000 }, - { "gimbal_roll_mid", VAR_UINT16, &cfg.gimbal_roll_mid, 100, 3000 }, { "acc_lpf_factor", VAR_UINT8, &cfg.acc_lpf_factor, 0, 250 }, { "accxy_deadband", VAR_UINT8, &cfg.accxy_deadband, 0, 100 }, { "accz_deadband", VAR_UINT8, &cfg.accz_deadband, 0, 100 }, diff --git a/src/config.c b/src/config.c index 2cbbc2272..d9091c9c6 100755 --- a/src/config.c +++ b/src/config.c @@ -13,7 +13,7 @@ master_t mcfg; // master config struct with data independent from profiles config_t cfg; // profile config struct const char rcChannelLetters[] = "AERT1234"; -static const uint8_t EEPROM_CONF_VERSION = 51; +static const uint8_t EEPROM_CONF_VERSION = 52; static uint32_t enabledSensors = 0; static void resetConf(void); @@ -83,7 +83,6 @@ void readEEPROM(void) lookupThrottleRC[i] = mcfg.minthrottle + (int32_t) (mcfg.maxthrottle - mcfg.minthrottle) * lookupThrottleRC[i] / 1000; // [0;1000] -> [MINTHROTTLE;MAXTHROTTLE] } - cfg.tri_yaw_middle = constrain(cfg.tri_yaw_middle, cfg.tri_yaw_min, cfg.tri_yaw_max); //REAR setPIDController(cfg.pidController); GPS_set_pids(); } @@ -286,32 +285,9 @@ static void resetConf(void) cfg.yaw_direction = 1; cfg.tri_unarmed_servo = 1; - cfg.tri_yaw_middle = 1500; - cfg.tri_yaw_min = 1020; - cfg.tri_yaw_max = 2000; - - // flying wing - cfg.wing_left_min = 1020; - cfg.wing_left_mid = 1500; - cfg.wing_left_max = 2000; - cfg.wing_right_min = 1020; - cfg.wing_right_mid = 1500; - cfg.wing_right_max = 2000; - cfg.pitch_direction_l = 1; - cfg.pitch_direction_r = -1; - cfg.roll_direction_l = 1; - cfg.roll_direction_r = 1; // gimbal - cfg.gimbal_pitch_gain = 10; - cfg.gimbal_roll_gain = 10; cfg.gimbal_flags = GIMBAL_NORMAL; - cfg.gimbal_pitch_min = 1020; - cfg.gimbal_pitch_max = 2000; - cfg.gimbal_pitch_mid = 1500; - cfg.gimbal_roll_min = 1020; - cfg.gimbal_roll_max = 2000; - cfg.gimbal_roll_mid = 1500; // gps/nav stuff cfg.gps_wp_radius = 200; diff --git a/src/main.c b/src/main.c index 36f369a84..e9b582204 100755 --- a/src/main.c +++ b/src/main.c @@ -81,6 +81,8 @@ int main(void) pwmInit(&pwm_params); // configure PWM/CPPM read function and max number of channels. spektrum or sbus below will override both of these, if enabled + for (i = 0; i < RC_CHANS; i++) + rcData[i] = 1502; rcReadRawFunc = pwmReadRawRC; core.numRCChannels = MAX_INPUTS; diff --git a/src/mixer.c b/src/mixer.c index 25ceabeda..1b1e6bb52 100755 --- a/src/mixer.c +++ b/src/mixer.c @@ -3,7 +3,7 @@ static uint8_t numberMotor = 0; int16_t motor[MAX_MOTORS]; -int16_t servo[8] = { 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500 }; +int16_t servo[MAX_SERVOS] = { 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500 }; static motorMixer_t currentMixer[MAX_MOTORS]; @@ -130,6 +130,30 @@ const mixer_t mixers[] = { { 0, 0, NULL }, // MULTITYPE_CUSTOM }; +int16_t servoMiddle(int nr) +{ + // Normally, servo.middle is a value between 1000..2000, but for the purposes of stupid, if it's less than + // the number of RC channels, it means the center value is taken FROM that RC channel (by its index) + if (cfg.servoConf[nr].middle < RC_CHANS && nr < MAX_SERVOS) + return rcData[cfg.servoConf[nr].middle]; + else + return cfg.servoConf[nr].middle; +} + +int servoDirection(int nr, int lr) +{ + // servo.rate is overloaded for servos that don't have a rate, but only need direction + // bit set = negative, clear = positive + // rate[2] = ???_direction + // rate[1] = roll_direction + // rate[0] = pitch_direction + // servo.rate is also used as gimbal gain multiplier (yeah) + if (cfg.servoConf[nr].rate & lr) + return -1; + else + return 1; +} + void mixerInit(void) { int i; @@ -319,17 +343,17 @@ void mixTable(void) // airplane / servo mixes switch (mcfg.mixerConfiguration) { case MULTITYPE_BI: - servo[4] = constrain(1500 + (-cfg.yaw_direction * axisPID[YAW]) + axisPID[PITCH], 1020, 2000); //LEFT - servo[5] = constrain(1500 + (-cfg.yaw_direction * axisPID[YAW]) - axisPID[PITCH], 1020, 2000); //RIGHT + servo[4] = (servoDirection(4, 2) * axisPID[YAW]) + (servoDirection(4, 1) * axisPID[PITCH]) + servoMiddle(4); // LEFT + servo[5] = (servoDirection(5, 2) * axisPID[YAW]) + (servoDirection(5, 1) * axisPID[PITCH]) + servoMiddle(5); // RIGHT break; case MULTITYPE_TRI: - servo[5] = constrain(cfg.tri_yaw_middle + -cfg.yaw_direction * axisPID[YAW], cfg.tri_yaw_min, cfg.tri_yaw_max); //REAR + servo[5] = (servoDirection(5, 1) * axisPID[YAW]) + servoMiddle(5); // REAR break; case MULTITYPE_GIMBAL: - servo[0] = constrain(cfg.gimbal_pitch_mid + cfg.gimbal_pitch_gain * angle[PITCH] / 16 + rcCommand[PITCH], cfg.gimbal_pitch_min, cfg.gimbal_pitch_max); - servo[1] = constrain(cfg.gimbal_roll_mid + cfg.gimbal_roll_gain * angle[ROLL] / 16 + rcCommand[ROLL], cfg.gimbal_roll_min, cfg.gimbal_roll_max); + servo[0] = (((int32_t)cfg.servoConf[0].rate * angle[PITCH]) / 50) + servoMiddle(0); + servo[1] = (((int32_t)cfg.servoConf[1].rate * angle[ROLL]) / 50) + servoMiddle(1); break; case MULTITYPE_AIRPLANE: @@ -337,47 +361,47 @@ void mixTable(void) break; case MULTITYPE_FLYING_WING: - motor[0] = rcCommand[THROTTLE]; + if (!f.ARMED) + servo[7] = mcfg.mincommand; + else + servo[7] = constrain(rcCommand[THROTTLE], mcfg.minthrottle, mcfg.maxthrottle); + motor[0] = servo[7]; if (f.PASSTHRU_MODE) { // do not use sensors for correction, simple 2 channel mixing - servo[0] = cfg.pitch_direction_l * (rcData[PITCH] - mcfg.midrc) + cfg.roll_direction_l * (rcData[ROLL] - mcfg.midrc); - servo[1] = cfg.pitch_direction_r * (rcData[PITCH] - mcfg.midrc) + cfg.roll_direction_r * (rcData[ROLL] - mcfg.midrc); + servo[3] = (servoDirection(3, 1) * rcCommand[PITCH]) + (servoDirection(3, 2) * rcCommand[ROLL]); + servo[4] = (servoDirection(4, 1) * rcCommand[PITCH]) + (servoDirection(4, 2) * rcCommand[ROLL]); } else { // use sensors to correct (gyro only or gyro + acc) - servo[0] = cfg.pitch_direction_l * axisPID[PITCH] + cfg.roll_direction_l * axisPID[ROLL]; - servo[1] = cfg.pitch_direction_r * axisPID[PITCH] + cfg.roll_direction_r * axisPID[ROLL]; + servo[3] = (servoDirection(3, 1) * axisPID[PITCH]) + (servoDirection(3, 2) * axisPID[ROLL]); + servo[4] = (servoDirection(4, 1) * axisPID[PITCH]) + (servoDirection(4, 2) * axisPID[ROLL]); } - servo[0] = constrain(servo[0] + cfg.wing_left_mid, cfg.wing_left_min, cfg.wing_left_max); - servo[1] = constrain(servo[1] + cfg.wing_right_mid, cfg.wing_right_min, cfg.wing_right_max); + servo[3] += servoMiddle(3); + servo[4] += servoMiddle(4); break; } // do camstab if (feature(FEATURE_SERVO_TILT)) { - uint16_t aux[2] = { 0, 0 }; - - if ((cfg.gimbal_flags & GIMBAL_NORMAL) || (cfg.gimbal_flags & GIMBAL_TILTONLY)) - aux[0] = rcData[AUX3] - mcfg.midrc; - if (!(cfg.gimbal_flags & GIMBAL_DISABLEAUX34)) - aux[1] = rcData[AUX4] - mcfg.midrc; - - servo[0] = cfg.gimbal_pitch_mid + aux[0]; - servo[1] = cfg.gimbal_roll_mid + aux[1]; + // center at fixed position, or vary either pitch or roll by RC channel + servo[0] = servoMiddle(0); + servo[1] = servoMiddle(1); if (rcOptions[BOXCAMSTAB]) { if (cfg.gimbal_flags & GIMBAL_MIXTILT) { - servo[0] -= (-cfg.gimbal_pitch_gain) * angle[PITCH] / 16 - cfg.gimbal_roll_gain * angle[ROLL] / 16; - servo[1] += (-cfg.gimbal_pitch_gain) * angle[PITCH] / 16 + cfg.gimbal_roll_gain * angle[ROLL] / 16; + servo[0] -= (-(int32_t)cfg.servoConf[0].rate) * angle[PITCH] / 50 - (int32_t)cfg.servoConf[1].rate * angle[ROLL] / 50; + servo[1] += (-(int32_t)cfg.servoConf[0].rate) * angle[PITCH] / 50 + (int32_t)cfg.servoConf[1].rate * angle[ROLL] / 50; } else { - servo[0] += cfg.gimbal_pitch_gain * angle[PITCH] / 16; - servo[1] += cfg.gimbal_roll_gain * angle[ROLL] / 16; + servo[0] += (int32_t)cfg.servoConf[0].rate * angle[PITCH] / 50; + servo[1] += (int32_t)cfg.servoConf[0].rate * angle[ROLL] / 50; } } - - servo[0] = constrain(servo[0], cfg.gimbal_pitch_min, cfg.gimbal_pitch_max); - servo[1] = constrain(servo[1], cfg.gimbal_roll_min, cfg.gimbal_roll_max); } + // constrain servos + for (i = 0; i < MAX_SERVOS; i++) + servo[i] = constrain(servo[i], cfg.servoConf[i].min, cfg.servoConf[i].max); // limit the values + + // forward AUX1-4 to servo outputs (not constrained) if (cfg.gimbal_flags & GIMBAL_FORWARDAUX) { int offset = 0; if (feature(FEATURE_SERVO_TILT)) diff --git a/src/mw.c b/src/mw.c index 8d4ea51e2..97a2442cb 100755 --- a/src/mw.c +++ b/src/mw.c @@ -16,7 +16,7 @@ int16_t telemTemperature1; // gyro sensor temperature int16_t failsafeCnt = 0; int16_t failsafeEvents = 0; -int16_t rcData[8] = { 1502, 1502, 1502, 1502, 1502, 1502, 1502, 1502 }; // interval [1000;2000] +int16_t rcData[RC_CHANS]; // interval [1000;2000] int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW int16_t lookupPitchRollRC[6]; // lookup table for expo & RC rate PITCH+ROLL int16_t lookupThrottleRC[11]; // lookup table for expo & mid THROTTLE @@ -802,9 +802,6 @@ void loop(void) currentTime = micros(); cycleTime = (int32_t)(currentTime - previousTime); previousTime = currentTime; -#ifdef MPU6050_DMP - mpu6050DmpLoop(); -#endif #ifdef MAG if (sensors(SENSOR_MAG)) { diff --git a/src/mw.h b/src/mw.h index df724a994..ad8dd31e3 100755 --- a/src/mw.h +++ b/src/mw.h @@ -4,11 +4,13 @@ #define VBATFREQ 6 // to read battery voltage - nth number of loop iterations #define BARO_TAB_SIZE_MAX 48 -#define VERSION 220 +#define VERSION 230 #define LAT 0 #define LON 1 +#define RC_CHANS (18) + // Serial GPS only variables // navigation mode typedef enum NavigationMode @@ -44,10 +46,8 @@ typedef enum MultiType typedef enum GimbalFlags { GIMBAL_NORMAL = 1 << 0, - GIMBAL_TILTONLY = 1 << 1, - GIMBAL_DISABLEAUX34 = 1 << 2, - GIMBAL_FORWARDAUX = 1 << 3, - GIMBAL_MIXTILT = 1 << 4, + GIMBAL_MIXTILT = 1 << 1, + GIMBAL_FORWARDAUX = 1 << 2, } GimbalFlags; /*********** RC alias *****************/ @@ -194,33 +194,9 @@ typedef struct config_t { // mixer-related configuration int8_t yaw_direction; uint8_t tri_unarmed_servo; // send tail servo correction pulses even when unarmed - uint16_t tri_yaw_middle; // tail servo center pos. - use this for initial trim - uint16_t tri_yaw_min; // tail servo min - uint16_t tri_yaw_max; // tail servo max - - // flying wing related configuration - uint16_t wing_left_min; // min/mid/max servo travel - uint16_t wing_left_mid; - uint16_t wing_left_max; - uint16_t wing_right_min; - uint16_t wing_right_mid; - uint16_t wing_right_max; - - int8_t pitch_direction_l; // left servo - pitch orientation - int8_t pitch_direction_r; // right servo - pitch orientation (opposite sign to pitch_direction_l if servos are mounted mirrored) - int8_t roll_direction_l; // left servo - roll orientation - int8_t roll_direction_r; // right servo - roll orientation (same sign as ROLL_DIRECTION_L, if servos are mounted in mirrored orientation) // gimbal-related configuration - int8_t gimbal_pitch_gain; // gimbal pitch servo gain (tied to angle) can be negative to invert movement - int8_t gimbal_roll_gain; // gimbal roll servo gain (tied to angle) can be negative to invert movement uint8_t gimbal_flags; // in servotilt mode, various things that affect stuff - uint16_t gimbal_pitch_min; // gimbal pitch servo min travel - uint16_t gimbal_pitch_max; // gimbal pitch servo max travel - uint16_t gimbal_pitch_mid; // gimbal pitch servo neutral value - uint16_t gimbal_roll_min; // gimbal roll servo min travel - uint16_t gimbal_roll_max; // gimbal roll servo max travel - uint16_t gimbal_roll_mid; // gimbal roll servo neutral value // gps-related stuff uint16_t gps_wp_radius; // if we are within this distance to a waypoint then we consider it reached (distance is in cm) @@ -305,6 +281,7 @@ typedef struct core_t { serialPort_t *telemport; serialPort_t *rcvrport; bool useServo; + uint8_t numRCChannels; } core_t; @@ -362,8 +339,8 @@ extern int16_t throttleAngleCorrection; extern int16_t headFreeModeHold; extern int16_t heading, magHold; extern int16_t motor[MAX_MOTORS]; -extern int16_t servo[8]; -extern int16_t rcData[8]; +extern int16_t servo[MAX_SERVOS]; +extern int16_t rcData[RC_CHANS]; extern uint16_t rssi; // range: [0;1023] extern uint8_t vbat; extern int16_t telemTemperature1; // gyro sensor temperature diff --git a/src/serial.c b/src/serial.c index 4da63d505..07a1ce4bc 100755 --- a/src/serial.c +++ b/src/serial.c @@ -149,7 +149,6 @@ static const char pidnames[] = static uint8_t checksum, indRX, inBuf[INBUF_SIZE]; static uint8_t cmdMSP; -static bool guiConnected = false; // signal that we're in cli mode uint8_t cliMode = 0; @@ -468,17 +467,28 @@ static void evaluateCommand(void) serialize16(magADC[i]); break; case MSP_SERVO: - headSerialReply(16); - for (i = 0; i < 8; i++) - serialize16(servo[i]); + s_struct((uint8_t *)&servo, 16); break; case MSP_SERVO_CONF: - s_struct((uint8_t *)&cfg.servoConf, 56); // struct servoConf is 7 bytes length: min:2 / max:2 / middle:2 / rate:1 ---- 8 servo => 8x7 = 56 + headSerialReply(56); + for (i = 0; i < MAX_SERVOS; i++) { + serialize16(cfg.servoConf[i].min); + serialize16(cfg.servoConf[i].max); + serialize16(cfg.servoConf[i].middle); + serialize8(cfg.servoConf[i].rate); + } + break; + case MSP_SET_SERVO_CONF: + headSerialReply(0); + for (i = 0; i < MAX_SERVOS; i++) { + cfg.servoConf[i].min = read16(); + cfg.servoConf[i].max = read16(); + cfg.servoConf[i].middle = read16(); + cfg.servoConf[i].rate = read8(); + } break; case MSP_MOTOR: - headSerialReply(16); - for (i = 0; i < 8; i++) - serialize16(motor[i]); + s_struct((uint8_t *)motor, 16); break; case MSP_RC: headSerialReply(16); @@ -718,7 +728,6 @@ void serialCom(void) indRX = 0; checksum ^= c; c_state = HEADER_SIZE; // the command is to follow - guiConnected = true; } else if (c_state == HEADER_SIZE) { cmdMSP = c; checksum ^= c; From c682f1f21e82fde06f443f910f2cecf2de61af6e Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Sat, 12 Oct 2013 07:46:55 +0000 Subject: [PATCH 05/56] Softserial can now be enabled/disabled via the SOFTSERIAL feature switch in the command line. Softserial baud rate can be set via softserial_baudrate setting. Added input & output inversion support, use softserial_inverted setting by Dominic Clifton git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@435 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/board.h | 1 + src/cli.c | 4 +++- src/config.c | 2 ++ src/drv_pwm.c | 4 +--- src/drv_pwm.h | 1 + src/drv_softserial.c | 11 ++++++++--- src/drv_softserial.h | 3 ++- src/main.c | 29 ++++++++++++++++++----------- src/mw.h | 3 +++ 9 files changed, 39 insertions(+), 19 deletions(-) diff --git a/src/board.h b/src/board.h index c76fb1903..a026015c1 100755 --- a/src/board.h +++ b/src/board.h @@ -74,6 +74,7 @@ typedef enum { FEATURE_POWERMETER = 1 << 12, FEATURE_VARIO = 1 << 13, FEATURE_3D = 1 << 14, + FEATURE_SOFTSERIAL = 1 << 15, } AvailableFeatures; typedef enum { diff --git a/src/cli.c b/src/cli.c index b65d79220..0502e924c 100644 --- a/src/cli.c +++ b/src/cli.c @@ -44,7 +44,7 @@ static const char * const mixerNames[] = { static const char * const featureNames[] = { "PPM", "VBAT", "INFLIGHT_ACC_CAL", "SERIALRX", "MOTOR_STOP", "SERVO_TILT", "GYRO_SMOOTHING", "LED_RING", "GPS", - "FAILSAFE", "SONAR", "TELEMETRY", "POWERMETER", "VARIO", "3D", + "FAILSAFE", "SONAR", "TELEMETRY", "POWERMETER", "VARIO", "3D", "SOFTSERIAL", NULL }; @@ -115,6 +115,8 @@ const clivalue_t valueTable[] = { { "servo_pwm_rate", VAR_UINT16, &mcfg.servo_pwm_rate, 50, 498 }, { "retarded_arm", VAR_UINT8, &mcfg.retarded_arm, 0, 1 }, { "serial_baudrate", VAR_UINT32, &mcfg.serial_baudrate, 1200, 115200 }, + { "softserial_baudrate", VAR_UINT32, &mcfg.softserial_baudrate, 9600, 19200 }, + { "softserial_inverted", VAR_UINT8, &mcfg.softserial_inverted, 0, 1 }, { "gps_baudrate", VAR_UINT32, &mcfg.gps_baudrate, 1200, 115200 }, { "serialrx_type", VAR_UINT8, &mcfg.serialrx_type, 0, 2 }, { "vbatscale", VAR_UINT8, &mcfg.vbatscale, 10, 200 }, diff --git a/src/config.c b/src/config.c index d9091c9c6..977d92b00 100755 --- a/src/config.c +++ b/src/config.c @@ -208,6 +208,8 @@ static void resetConf(void) mcfg.gps_baudrate = 115200; // serial (USART1) baudrate mcfg.serial_baudrate = 115200; + mcfg.softserial_baudrate = 19200; + mcfg.softserial_inverted = 0; mcfg.looptime = 3500; mcfg.rssi_aux_channel = 0; diff --git a/src/drv_pwm.c b/src/drv_pwm.c index c833b9dcf..6a0c7e2c8 100755 --- a/src/drv_pwm.c +++ b/src/drv_pwm.c @@ -323,11 +323,9 @@ bool pwmInit(drv_pwm_config_t *init) if (init->useUART && (port == PWM3 || port == PWM4)) continue; -#ifdef SOFTSERIAL_19200_LOOPBACK // skip softSerial ports - if ((port == PWM5 || port == PWM6 || port == PWM7 || port == PWM8)) + if (init->useSoftSerial && (port == PWM5 || port == PWM6 || port == PWM7 || port == PWM8)) continue; -#endif // skip ADC for powerMeter if configured if (init->adcChannel && (init->adcChannel == port)) diff --git a/src/drv_pwm.h b/src/drv_pwm.h index a56e281a2..728ac8eec 100755 --- a/src/drv_pwm.h +++ b/src/drv_pwm.h @@ -8,6 +8,7 @@ typedef struct drv_pwm_config_t { bool enableInput; bool usePPM; bool useUART; + bool useSoftSerial; bool useServos; bool extraServos; // configure additional 4 channels in PPM mode as servos, not motors bool airplane; // fixed wing hardware config, lots of servos etc diff --git a/src/drv_softserial.c b/src/drv_softserial.c index cf0e1030f..2cae1f281 100644 --- a/src/drv_softserial.c +++ b/src/drv_softserial.c @@ -17,12 +17,16 @@ void onSerialTimer(uint8_t portIndex, uint16_t capture); uint8_t readRxSignal(softSerial_t *softSerial) { - return !(digitalIn(softSerial->rxTimerHardware->gpio, softSerial->rxTimerHardware->pin) == 0); + uint8_t invertedSignal = (digitalIn(softSerial->rxTimerHardware->gpio, softSerial->rxTimerHardware->pin) == 0); + if (softSerial->isInverted) { + return invertedSignal; + } + return !invertedSignal; } void setTxSignal(softSerial_t *softSerial, uint8_t state) { - if (state) { + if ((state == 1 && softSerial->isInverted == false) || (state == 0 && softSerial->isInverted == true)) { digitalHi(softSerial->txTimerHardware->gpio, softSerial->txTimerHardware->pin); } else { digitalLo(softSerial->txTimerHardware->gpio, softSerial->txTimerHardware->pin); @@ -82,7 +86,7 @@ void serialOutputPortConfig(const timerHardware_t *timerHardwarePtr) softSerialGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, Mode_Out_PP); } -void setupSoftSerial1(uint32_t baud) +void setupSoftSerial1(uint32_t baud, uint8_t inverted) { int portIndex = 0; softSerial_t *softSerial = &(softSerialPorts[portIndex]); @@ -90,6 +94,7 @@ void setupSoftSerial1(uint32_t baud) softSerial->port.vTable = softSerialVTable; softSerial->port.mode = MODE_RXTX; softSerial->port.baudRate = baud; + softSerial->isInverted = inverted; softSerial->rxTimerHardware = &(timerHardware[SOFT_SERIAL_1_TIMER_RX_HARDWARE]); softSerial->txTimerHardware = &(timerHardware[SOFT_SERIAL_1_TIMER_TX_HARDWARE]); diff --git a/src/drv_softserial.h b/src/drv_softserial.h index ad2b60dc4..c16135c4f 100644 --- a/src/drv_softserial.h +++ b/src/drv_softserial.h @@ -29,6 +29,7 @@ typedef struct softSerial_s { uint16_t internalRxBuffer; // excluding start/stop bits uint16_t internalTxBuffer; // includes start and stop bits + uint8_t isInverted; } softSerial_t; extern timerHardware_t* serialTimerHardware; @@ -36,7 +37,7 @@ extern softSerial_t softSerialPorts[]; extern const struct serialPortVTable softSerialVTable[]; -void setupSoftSerial1(uint32_t baud); +void setupSoftSerial1(uint32_t baud, uint8_t inverted); // serialPort API void softSerialWriteByte(serialPort_t *instance, uint8_t ch); diff --git a/src/main.c b/src/main.c index e9b582204..9aff7b721 100755 --- a/src/main.c +++ b/src/main.c @@ -30,6 +30,7 @@ int main(void) uint8_t i; drv_pwm_config_t pwm_params; drv_adc_config_t adc_params; + serialPort_t* loopbackPort = NULL; systemInit(); #ifdef USE_LAME_PRINTF @@ -59,6 +60,7 @@ int main(void) else pwm_params.airplane = false; pwm_params.useUART = feature(FEATURE_GPS) || feature(FEATURE_SERIALRX); // spektrum/sbus support uses UART too + pwm_params.useSoftSerial = feature(FEATURE_SOFTSERIAL); pwm_params.usePPM = feature(FEATURE_PPM); pwm_params.enableInput = !feature(FEATURE_SERIALRX); // disable inputs if using spektrum pwm_params.useServos = core.useServo; @@ -133,11 +135,14 @@ int main(void) batteryInit(); serialInit(mcfg.serial_baudrate); -#ifdef SOFTSERIAL_19200_LOOPBACK - setupSoftSerial1(19200); - serialPort_t* loopbackPort = (serialPort_t*)&(softSerialPorts[0]); - serialPrint(loopbackPort, "LOOPBACK 19200 ENABLED\r\n"); + + if (feature(FEATURE_SOFTSERIAL)) { + setupSoftSerial1(mcfg.softserial_baudrate, mcfg.softserial_inverted); +#ifdef SOFTSERIAL_LOOPBACK + loopbackPort = (serialPort_t*)&(softSerialPorts[0]); + serialPrint(loopbackPort, "LOOPBACK ENABLED\r\n"); #endif + } previousTime = micros(); if (mcfg.mixerConfiguration == MULTITYPE_GIMBAL) @@ -149,13 +154,15 @@ int main(void) // loopy while (1) { loop(); -#ifdef SOFTSERIAL_19200_LOOPBACK - while (serialTotalBytesWaiting(loopbackPort)) { - - uint8_t b = serialRead(loopbackPort); - serialWrite(loopbackPort, b); - //serialWrite(core.mainport, b); - }; +#ifdef SOFTSERIAL_LOOPBACK + if (loopbackPort) { + while (serialTotalBytesWaiting(loopbackPort)) { + + uint8_t b = serialRead(loopbackPort); + serialWrite(loopbackPort, b); + //serialWrite(core.mainport, b); + }; + } #endif } } diff --git a/src/mw.h b/src/mw.h index ad8dd31e3..1c3cafbfd 100755 --- a/src/mw.h +++ b/src/mw.h @@ -266,6 +266,9 @@ typedef struct master_t { uint32_t gps_baudrate; // GPS baudrate uint32_t serial_baudrate; + + uint32_t softserial_baudrate; + uint8_t softserial_inverted; // use inverted softserial input and output signals config_t profile[3]; // 3 separate profiles uint8_t current_profile; // currently loaded profile From 07055c887202ee6498ad162a35de15cdd348c21a Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Sat, 12 Oct 2013 08:07:08 +0000 Subject: [PATCH 06/56] fixing initializion for anglesrad[] add drv_softserial to common drivers in Makefile git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@436 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- Makefile | 2 +- src/imu.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Makefile b/Makefile index 5eb6b862d..380bff52a 100644 --- a/Makefile +++ b/Makefile @@ -60,6 +60,7 @@ COMMON_SRC = startup_stm32f10x_md_gcc.S \ drv_i2c_soft.c \ drv_system.c \ drv_serial.c \ + drv_softserial.c \ drv_uart.c \ printf.c \ utils.c \ @@ -98,7 +99,6 @@ OLIMEXINO_SRC = drv_spi.c \ drv_l3g4200d.c \ drv_pwm.c \ drv_timer.c \ - drv_softserial.c \ $(COMMON_SRC) # Search path for baseflight sources diff --git a/src/imu.c b/src/imu.c index 91928e8f3..e0bd39626 100755 --- a/src/imu.c +++ b/src/imu.c @@ -26,7 +26,7 @@ float accVelScale; int16_t gyroData[3] = { 0, 0, 0 }; int16_t gyroZero[3] = { 0, 0, 0 }; int16_t angle[2] = { 0, 0 }; // absolute angle inclination in multiple of 0.1 degree 180 deg = 1800 -float anglerad[2] = { 0, 0 }; // absolute angle inclination in radians +float anglerad[2] = { 0.0f, 0.0f }; // absolute angle inclination in radians static void getEstimatedAttitude(void); From 04560808e730b9aec46ee70e2a7fc0d0c4d5bb96 Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Sun, 13 Oct 2013 08:58:47 +0000 Subject: [PATCH 07/56] implemented MSP_MISC get/set to support 'SETTINGS' tab of mwcgui git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@437 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/serial.c | 26 ++++++++++++++++++++++++-- 1 file changed, 24 insertions(+), 2 deletions(-) diff --git a/src/serial.c b/src/serial.c index 07a1ce4bc..f24d30907 100755 --- a/src/serial.c +++ b/src/serial.c @@ -362,6 +362,17 @@ static void evaluateCommand(void) headSerialReply(0); break; case MSP_SET_MISC: + read16(); // powerfailmeter + mcfg.minthrottle = read16(); + read32(); // mcfg.maxthrottle, mcfg.mincommand + cfg.failsafe_throttle = read16(); + read16(); + read32(); + cfg.mag_declination = read16() * 10; + mcfg.vbatscale = read8(); // actual vbatscale as intended + mcfg.vbatmincellvoltage = read8(); // vbatlevel_warn1 in MWC2.3 GUI + mcfg.vbatmaxcellvoltage = read8(); // vbatlevel_warn2 in MWC2.3 GUI + read8(); // vbatlevel_crit (unused) headSerialReply(0); break; case MSP_SELECT_SETTING: @@ -566,8 +577,19 @@ static void evaluateCommand(void) serialize8(availableBoxes[i]); break; case MSP_MISC: - headSerialReply(2); - serialize16(0); // intPowerTrigger1 + headSerialReply(2 * 6 + 4 + 2 + 8 * 4); + serialize16(0); // intPowerTrigger1 (aka useless trash) + serialize16(mcfg.minthrottle); + serialize16(mcfg.maxthrottle); + serialize16(mcfg.mincommand); + serialize16(cfg.failsafe_throttle); + serialize16(0); // plog useless shit + serialize32(0); // plog useless shit + serialize16(cfg.mag_declination / 10); // TODO check this shit + serialize8(mcfg.vbatscale); + serialize8(mcfg.vbatmincellvoltage); + serialize8(mcfg.vbatmaxcellvoltage); + serialize8(0); break; case MSP_MOTOR_PINS: headSerialReply(8); From 30ded7ff04b18632182137073b7a4f8b9ce49a3a Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Sun, 13 Oct 2013 15:25:45 +0000 Subject: [PATCH 08/56] Beginning of the great GPS unfucking. * Proper initialization sequence framework for various supported GPS types. NMEA will now auto-detect its baud rate based on received frames. * As a result of the above, gps_baudrate has been changed to enum, to only allow fixed rates. (GPS baudrate, -1: autodetect (NMEA only), 0: 115200, 1: 57600, 2: 38400, 3: 19200, 4: 9600) * UBX binary initialization at any specified baudrate with auto-reconnect on signal loss. * GPS thread to handle initialization, signal loss and configuration. No longer does GPS need to be powered before FC, and on GPS reconnect, it will be re-initialized if needed. MTK NMEA/binary initialization is omitted for now, as I can't find my MTK GPS GPS deltaTime can be calculated to display update rate. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@438 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/board.h | 3 +- src/cli.c | 4 +- src/config.c | 6 +- src/gps.c | 288 ++++++++++++++++++++++++++++++++------------------- src/main.c | 10 +- src/mw.c | 11 +- src/mw.h | 11 +- src/serial.c | 2 +- 8 files changed, 209 insertions(+), 126 deletions(-) diff --git a/src/board.h b/src/board.h index a026015c1..757a847a1 100755 --- a/src/board.h +++ b/src/board.h @@ -86,7 +86,8 @@ typedef enum { typedef enum { GPS_NMEA = 0, GPS_UBLOX, - GPS_MTK, + GPS_MTK_NMEA, + GPS_MTK_BINARY, } GPSHardware; typedef enum { diff --git a/src/cli.c b/src/cli.c index 0502e924c..f28e2d515 100644 --- a/src/cli.c +++ b/src/cli.c @@ -117,7 +117,8 @@ const clivalue_t valueTable[] = { { "serial_baudrate", VAR_UINT32, &mcfg.serial_baudrate, 1200, 115200 }, { "softserial_baudrate", VAR_UINT32, &mcfg.softserial_baudrate, 9600, 19200 }, { "softserial_inverted", VAR_UINT8, &mcfg.softserial_inverted, 0, 1 }, - { "gps_baudrate", VAR_UINT32, &mcfg.gps_baudrate, 1200, 115200 }, + { "gps_type", VAR_UINT8, &mcfg.gps_type, 0, 3 }, + { "gps_baudrate", VAR_INT8, &mcfg.gps_baudrate, -1, 4 }, { "serialrx_type", VAR_UINT8, &mcfg.serialrx_type, 0, 2 }, { "vbatscale", VAR_UINT8, &mcfg.vbatscale, 10, 200 }, { "vbatmaxcellvoltage", VAR_UINT8, &mcfg.vbatmaxcellvoltage, 10, 50 }, @@ -132,7 +133,6 @@ const clivalue_t valueTable[] = { { "gyro_lpf", VAR_UINT16, &mcfg.gyro_lpf, 0, 256 }, { "gyro_cmpf_factor", VAR_UINT16, &mcfg.gyro_cmpf_factor, 100, 1000 }, { "gyro_cmpfm_factor", VAR_UINT16, &mcfg.gyro_cmpfm_factor, 100, 1000 }, - { "gps_type", VAR_UINT8, &mcfg.gps_type, 0, 3 }, { "pid_controller", VAR_UINT8, &cfg.pidController, 0, 1 }, { "deadband", VAR_UINT8, &cfg.deadband, 0, 32 }, { "yawdeadband", VAR_UINT8, &cfg.yawdeadband, 0, 100 }, diff --git a/src/config.c b/src/config.c index 977d92b00..c7b069190 100755 --- a/src/config.c +++ b/src/config.c @@ -13,7 +13,7 @@ master_t mcfg; // master config struct with data independent from profiles config_t cfg; // profile config struct const char rcChannelLetters[] = "AERT1234"; -static const uint8_t EEPROM_CONF_VERSION = 52; +static const uint8_t EEPROM_CONF_VERSION = 53; static uint32_t enabledSensors = 0; static void resetConf(void); @@ -84,7 +84,7 @@ void readEEPROM(void) } setPIDController(cfg.pidController); - GPS_set_pids(); + gpsSetPIDs(); } void writeEEPROM(uint8_t b, uint8_t updateProfile) @@ -205,7 +205,7 @@ static void resetConf(void) mcfg.servo_pwm_rate = 50; // gps/nav stuff mcfg.gps_type = GPS_NMEA; - mcfg.gps_baudrate = 115200; + mcfg.gps_baudrate = 0; // serial (USART1) baudrate mcfg.serial_baudrate = 115200; mcfg.softserial_baudrate = 19200; diff --git a/src/gps.c b/src/gps.c index 287193a62..51f265e5c 100644 --- a/src/gps.c +++ b/src/gps.c @@ -5,106 +5,198 @@ #define sq(x) ((x)*(x)) #endif -const uint32_t init_speed[5] = { 9600, 19200, 38400, 57600, 115200 }; +// GPS timeout for wrong baud rate/disconnection/etc in milliseconds (default 2.5second) +#define GPS_TIMEOUT (2500) +// How many entries in gpsInitData array below +#define GPS_INIT_ENTRIES (5) -static void GPS_NewData(uint16_t c); -static void gpsPrint(const char *str); +typedef struct gpsInitData_t { + uint32_t baudrate; + const char *ubx; + const char *mtk; +} gpsInitData_t; -#define UBX_INIT_STRING_INDEX 0 -#define MTK_INIT_STRING_INDEX 4 - -static const char * const gpsInitStrings[] = { - "$PUBX,41,1,0003,0001,19200,0*23\r\n", // UBX0..3 - "$PUBX,41,1,0003,0001,38400,0*26\r\n", - "$PUBX,41,1,0003,0001,57600,0*2D\r\n", - "$PUBX,41,1,0003,0001,115200,0*1E\r\n", - "$PMTK251,19200*22\r\n", // MTK4..7 - "$PMTK251,38400*27\r\n", - "$PMTK251,57600*2C\r\n", - "$PMTK251,115200*1F\r\n", +static const gpsInitData_t gpsInitData[] = { + { 115200, "$PUBX,41,1,0003,0001,115200,0*1E\r\n", "$PMTK251,115200*1F\r\n" }, + { 57600, "$PUBX,41,1,0003,0001,57600,0*2D\r\n", "$PMTK251,57600*2C\r\n" }, + { 38400, "$PUBX,41,1,0003,0001,38400,0*26\r\n", "$PMTK251,38400*27\r\n" }, + { 19200, "$PUBX,41,1,0003,0001,19200,0*23\r\n", "$PMTK251,19200*22\r\n" }, + // 9600 is not enough for 5Hz updates - leave for compatibility to dumb NMEA that only runs at this speed + { 9600, "", "" } }; static const uint8_t ubloxInit[] = { - 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x05, 0x00, 0xFF, 0x19, // disable all default NMEA messages - 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x03, 0x00, 0xFD, 0x15, - 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x01, 0x00, 0xFB, 0x11, - 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x00, 0x00, 0xFA, 0x0F, - 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x02, 0x00, 0xFC, 0x13, - 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x04, 0x00, 0xFE, 0x17, - 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x02, 0x01, 0x0E, 0x47, // set POSLLH MSG rate - 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x03, 0x01, 0x0F, 0x49, // set STATUS MSG rate - 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x06, 0x01, 0x12, 0x4F, // set SOL MSG rate - 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x12, 0x01, 0x1E, 0x67, // set VELNED MSG rate - 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00, 0x51, 0x08, 0x00, 0x00, 0x8A, 0x41, // set WAAS to EGNOS - 0xB5, 0x62, 0x06, 0x08, 0x06, 0x00, 0xC8, 0x00, 0x01, 0x00, 0x01, 0x00, 0xDE, 0x6A // set rate to 5Hz + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x05, 0x00, 0xFF, 0x19, // VGS: Course over ground and Ground speed + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x03, 0x00, 0xFD, 0x15, // GSV: GNSS Satellites in View + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x01, 0x00, 0xFB, 0x11, // GLL: Latitude and longitude, with time of position fix and status + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x00, 0x00, 0xFA, 0x0F, // GGA: Global positioning system fix data + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x02, 0x00, 0xFC, 0x13, // GSA: GNSS DOP and Active Satellites + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x04, 0x00, 0xFE, 0x17, // RMC: Recommended Minimum data + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x02, 0x01, 0x0E, 0x47, // set POSLLH MSG rate + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x03, 0x01, 0x0F, 0x49, // set STATUS MSG rate + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x06, 0x01, 0x12, 0x4F, // set SOL MSG rate + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x12, 0x01, 0x1E, 0x67, // set VELNED MSG rate + 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00, 0x51, 0x08, 0x00, 0x00, 0x8A, 0x41, // set WAAS to EGNOS + 0xB5, 0x62, 0x06, 0x08, 0x06, 0x00, 0xC8, 0x00, 0x01, 0x00, 0x01, 0x00, 0xDE, 0x6A, // set rate to 5Hz }; -void gpsInit(uint32_t baudrate) +static const char *mtkNMEAInit[] = { + "$PMTK314,0,1,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*28\r\n", // only GGA and RMC sentence + "$PMTK220,200*2C\r\n" // 5 Hz update rate +}; + +static const char *mtkBinaryInit[] = { + "$PMTK319,1*24\r\n", // SBAS Integrity Mode + "$PMTK220,200*2C\r\n", // 5 Hz update rate + "$PMTK397,0*23\r\n", // NAVTHRES_OFF + "$PMTK313,1*2E\r\n", // SBAS_ON + "$PMTK301,2*2E\r\n", // WAAS_ON + "$PGCMD,16,0,0,0,0,0*6A\r\n" // Binary ON +}; + +enum { + GPS_UNKNOWN, + GPS_INITIALIZING, + GPS_INITDONE, + GPS_RECEIVINGDATA, + GPS_LOSTCOMMS, +}; + +typedef struct gpsData_t { + uint8_t state; // GPS thread state. Used for detecting cable disconnects and configuring attached devices + uint8_t baudrateIndex; // index into auto-detecting or current baudrate + int errors; // gps error counter - crc error/lost of data/sync etc. reset on each reinit. + uint32_t lastMessage; // last time valid GPS data was received (millis) + uint32_t lastLastMessage; // last-last valid GPS message. Used to calculate delta. + + + +} gpsData_t; + +gpsData_t gpsData; + +static void gpsNewData(uint16_t c); +static bool gpsNewFrameNMEA(char c); +static bool gpsNewFrameUBLOX(uint8_t data); + +void gpsInit(uint8_t baudrate) +{ + portMode_t mode = MODE_RXTX; + + // init gpsData structure. if we're not actually enabled, don't bother doing anything else + gpsData.state = GPS_UNKNOWN; + if (!feature(FEATURE_GPS)) + return; + + gpsData.baudrateIndex = baudrate; + gpsData.lastMessage = millis(); + gpsData.errors = 0; + // only RX is needed for NMEA-style GPS + if (mcfg.gps_type == GPS_NMEA) + mode = MODE_RX; + + gpsSetPIDs(); + core.gpsport = uartOpen(USART2, gpsNewData, gpsInitData[baudrate].baudrate, mode); + // signal GPS "thread" to initialize when it gets to it + gpsData.state = GPS_INITIALIZING; +} + +void gpsInitHardware(void) { int i; - int offset = 0; - GPS_set_pids(); - core.gpsport = uartOpen(USART2, GPS_NewData, baudrate, MODE_RXTX); + switch (mcfg.gps_type) { + case GPS_NMEA: + // nothing to do, just set baud rate and try receiving some stuff and see if it parses + serialSetBaudRate(core.gpsport, gpsInitData[gpsData.baudrateIndex].baudrate); + gpsData.state = GPS_RECEIVINGDATA; + return; - if (mcfg.gps_type == GPS_UBLOX) - offset = UBX_INIT_STRING_INDEX; - else if (mcfg.gps_type == GPS_MTK) - offset = MTK_INIT_STRING_INDEX; - - if (mcfg.gps_type != GPS_NMEA) { - for (i = 0; i < 5; i++) { - serialSetBaudRate(core.gpsport, init_speed[i]); - // verify the requested change took effect. - baudrate = serialGetBaudRate(core.gpsport); - switch (baudrate) { - case 19200: - gpsPrint(gpsInitStrings[offset]); - break; - case 38400: - gpsPrint(gpsInitStrings[offset + 1]); - break; - case 57600: - gpsPrint(gpsInitStrings[offset + 2]); - break; - case 115200: - gpsPrint(gpsInitStrings[offset + 3]); - break; + case GPS_UBLOX: + // UBX will run at mcfg.baudrate, it shouldn't be "autodetected". So here we force it to that rate + if (gpsData.state == GPS_INITIALIZING) { + for (i = 0; i < GPS_INIT_ENTRIES; i++) { + // try different speed to INIT + serialSetBaudRate(core.gpsport, gpsInitData[i].baudrate); + // but print our FIXED init string for the baudrate we want to be at + serialPrint(core.gpsport, gpsInitData[mcfg.gps_baudrate].ubx); + delay(200); + } + // we're now (hopefully) at the correct rate, next state will switch to it + gpsData.baudrateIndex = mcfg.gps_baudrate; + gpsData.state = GPS_INITDONE; + } else { + // GPS_INITDONE, set our real baud rate and push some ublox config strings + serialSetBaudRate(core.gpsport, gpsInitData[gpsData.baudrateIndex].baudrate); + for (i = 0; i < sizeof(ubloxInit); i++) { + serialWrite(core.gpsport, ubloxInit[i]); // send ubx init binary + delay(4); + } + // ublox should be init'd, time to try receiving some junk + gpsData.state = GPS_RECEIVINGDATA; } - delay(10); - } + break; + case GPS_MTK_NMEA: + case GPS_MTK_BINARY: + // TODO. need to find my old piece of shit MTK GPS. + break; } - serialSetBaudRate(core.gpsport, baudrate); - if (mcfg.gps_type == GPS_UBLOX) { - for (i = 0; i < sizeof(ubloxInit); i++) { - serialWrite(core.gpsport, ubloxInit[i]); // send ubx init binary - delay(4); - } - } else if (mcfg.gps_type == GPS_MTK) { - gpsPrint("$PMTK314,0,1,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*28\r\n"); // only GGA and RMC sentence - gpsPrint("$PMTK220,200*2C\r\n"); // 5 Hz update rate - } - - // catch some GPS frames. TODO check this - delay(1000); - if (GPS_Present) - sensorsSet(SENSOR_GPS); + // clear error counter + gpsData.errors = 0; } -static void gpsPrint(const char *str) +void gpsThread(void) { - while (*str) { - serialWrite(core.gpsport, *str); - if (mcfg.gps_type == GPS_UBLOX) - delay(4); - str++; + switch (gpsData.state) { + case GPS_UNKNOWN: + break; + + case GPS_INITIALIZING: + case GPS_INITDONE: + gpsInitHardware(); + break; + + case GPS_LOSTCOMMS: + gpsData.errors++; + // try another rate + gpsData.baudrateIndex++; + gpsData.baudrateIndex %= GPS_INIT_ENTRIES; + gpsData.lastMessage = millis(); + // TODO - move some / all of these into gpsData + GPS_numSat = 0; + f.GPS_FIX = 0; + gpsData.state = GPS_INITIALIZING; + break; + + case GPS_RECEIVINGDATA: + // check for no data/gps timeout/cable disconnection etc + if (millis() - gpsData.lastMessage > GPS_TIMEOUT) { + // remove GPS from capability + sensorsClear(SENSOR_GPS); + gpsData.state = GPS_LOSTCOMMS; + } + break; } - // wait to send all - while (!isSerialTransmitBufferEmpty(core.gpsport)); - delay(30); } +static bool gpsNewFrame(uint8_t c) +{ + switch (mcfg.gps_type) { + case GPS_NMEA: // NMEA + case GPS_MTK_NMEA: // MTK in NMEA mode + return gpsNewFrameNMEA(c); + case GPS_UBLOX: // UBX binary + return gpsNewFrameUBLOX(c); + case GPS_MTK_BINARY: // MTK in BINARY mode (TODO) + return false; + } + + return false; +} + + + /*----------------------------------------------------------- * * Multiwii GPS code - revision: 1097 @@ -130,9 +222,6 @@ static void GPS_calc_location_error(int32_t * target_lat, int32_t * target_lng, static void GPS_calc_poshold(void); static void GPS_calc_nav_rate(int max_speed); static void GPS_update_crosstrack(void); -static bool GPS_newFrame(char c); -static bool GPS_NMEA_newFrame(char c); -static bool GPS_UBLOX_newFrame(uint8_t data); static bool UBLOX_parse_gps(void); static int16_t GPS_calc_desired_speed(int16_t max_speed, bool _slow); int32_t wrap_18000(int32_t error); @@ -285,7 +374,7 @@ static int32_t nav_bearing; // saves the bearing at takeof (1deg = 1) used to rotate to takeoff direction when arrives at home static int16_t nav_takeoff_bearing; -void GPS_NewData(uint16_t c) +static void gpsNewData(uint16_t c) { int axis; static uint32_t nav_loopTimer; @@ -293,7 +382,11 @@ void GPS_NewData(uint16_t c) int32_t dir; int16_t speed; - if (GPS_newFrame(c)) { + if (gpsNewFrame(c)) { + // new data received and parsed, we're in business + gpsData.lastLastMessage = gpsData.lastMessage; + gpsData.lastMessage = millis(); + sensorsSet(SENSOR_GPS); if (GPS_update == 1) GPS_update = 0; else @@ -411,7 +504,7 @@ void GPS_reset_nav(void) } // Get the relevant P I D values and set the PID controllers -void GPS_set_pids(void) +void gpsSetPIDs(void) { posholdPID_PARAM.kP = (float)cfg.P8[PIDPOS] / 100.0f; posholdPID_PARAM.kI = (float)cfg.I8[PIDPOS] / 100.0f; @@ -777,19 +870,6 @@ static uint8_t hex_c(uint8_t n) return n; } -static bool GPS_newFrame(char c) -{ - switch (mcfg.gps_type) { - case GPS_NMEA: // NMEA - case GPS_MTK: // MTK outputs NMEA too - return GPS_NMEA_newFrame(c); - case GPS_UBLOX: // UBX - return GPS_UBLOX_newFrame(c); - } - - return false; -} - /* This is a light implementation of a GPS frame decoding This should work with most of modern GPS devices configured to output NMEA frames. It assumes there are some NMEA GGA frames to decode on the serial bus @@ -805,7 +885,7 @@ static bool GPS_newFrame(char c) #define FRAME_GGA 1 #define FRAME_RMC 2 -static bool GPS_NMEA_newFrame(char c) +static bool gpsNewFrameNMEA(char c) { uint8_t frameOK = 0; static uint8_t param = 0, offset = 0, parity = 0; @@ -868,8 +948,6 @@ static bool GPS_NMEA_newFrame(char c) if (!checksum_param) parity ^= c; } - if (frame) - GPS_Present = 1; return frameOK && (frame == FRAME_GGA); } @@ -1026,7 +1104,7 @@ void _update_checksum(uint8_t *data, uint8_t len, uint8_t *ck_a, uint8_t *ck_b) } } -static bool GPS_UBLOX_newFrame(uint8_t data) +static bool gpsNewFrameUBLOX(uint8_t data) { bool parsed = false; @@ -1083,10 +1161,8 @@ static bool GPS_UBLOX_newFrame(uint8_t data) _step = 0; if (_ck_b != data) break; // bad checksum - GPS_Present = 1; - if (UBLOX_parse_gps()) { + if (UBLOX_parse_gps()) parsed = true; - } } //end switch return parsed; } diff --git a/src/main.c b/src/main.c index 9aff7b721..3b471e3c3 100755 --- a/src/main.c +++ b/src/main.c @@ -99,11 +99,13 @@ int main(void) sbusInit(&rcReadRawFunc); break; } - } else { - // spektrum and GPS are mutually exclusive + } else { // spektrum and GPS are mutually exclusive // Optional GPS - available in both PPM and PWM input mode, in PWM input, reduces number of available channels by 2. - if (feature(FEATURE_GPS)) - gpsInit(mcfg.gps_baudrate); + // gpsInit will return if FEATURE_GPS is not enabled. + // Sanity check below - protocols other than NMEA do not support baud rate autodetection + if (mcfg.gps_type > 0 && mcfg.gps_baudrate < 0) + mcfg.gps_baudrate = 0; + gpsInit(mcfg.gps_baudrate); } #ifdef SONAR // sonar stuff only works with PPM diff --git a/src/mw.c b/src/mw.c index 97a2442cb..e93e59c73 100755 --- a/src/mw.c +++ b/src/mw.c @@ -45,8 +45,6 @@ uint16_t GPS_altitude, GPS_speed; // altitude in 0.1m and speed in 0.1m/s uint8_t GPS_update = 0; // it's a binary toogle to distinct a GPS position update int16_t GPS_angle[2] = { 0, 0 }; // it's the angles that must be applied for GPS correction uint16_t GPS_ground_course = 0; // degrees * 10 -uint8_t GPS_Present = 0; // Checksum from Gps serial -uint8_t GPS_Enable = 0; int16_t nav[2]; int16_t nav_rated[2]; // Adding a rate controller to the navigation to make it smoother int8_t nav_mode = NAV_MODE_NONE; // Navigation mode @@ -777,9 +775,16 @@ void loop(void) taskOrder++; #ifdef BARO if (sensors(SENSOR_BARO) && getEstimatedAltitude()) - break; + break; #endif case 3: + // if GPS feature is enabled, gpsThread() will be called at some intervals to check for stuck + // hardware, wrong baud rates, init GPS if needed, etc. Don't use SENSOR_GPS here as gpsThread() can and will + // change this based on available hardware + if (feature(FEATURE_GPS)) + gpsThread(); + break; + case 4: taskOrder++; #ifdef SONAR if (sensors(SENSOR_SONAR)) { diff --git a/src/mw.h b/src/mw.h index 1c3cafbfd..7f79d2804 100755 --- a/src/mw.h +++ b/src/mw.h @@ -262,8 +262,8 @@ typedef struct master_t { uint8_t rssi_aux_channel; // Read rssi from channel. 1+ = AUX1+, 0 to disable. // gps-related stuff - uint8_t gps_type; // Type of GPS hardware. 0: NMEA 1: UBX 2+ ?? - uint32_t gps_baudrate; // GPS baudrate + uint8_t gps_type; // Type of GPS hardware. 0: NMEA 1: UBX 2: MTK + int8_t gps_baudrate; // GPS baudrate, -1: autodetect (NMEA only), 0: 115200, 1: 57600, 2: 38400, 3: 19200, 4: 9600 uint32_t serial_baudrate; @@ -362,8 +362,6 @@ extern uint16_t GPS_altitude,GPS_speed; // altitude in 0.1m extern uint8_t GPS_update; // it's a binary toogle to distinct a GPS position update extern int16_t GPS_angle[2]; // it's the angles that must be applied for GPS correction extern uint16_t GPS_ground_course; // degrees*10 -extern uint8_t GPS_Present; // Checksum from Gps serial -extern uint8_t GPS_Enable; extern int16_t nav[2]; extern int8_t nav_mode; // Navigation mode extern int16_t nav_rated[2]; // Adding a rate controller to the navigation to make it smoother @@ -447,10 +445,11 @@ void systemBeep(bool onoff); void cliProcess(void); // gps -void gpsInit(uint32_t baudrate); +void gpsInit(uint8_t baudrate); +void gpsThread(void); +void gpsSetPIDs(void); void GPS_reset_home_position(void); void GPS_reset_nav(void); -void GPS_set_pids(void); void GPS_set_next_wp(int32_t* lat, int32_t* lon); int32_t wrap_18000(int32_t error); diff --git a/src/serial.c b/src/serial.c index f24d30907..b20dc7a3d 100755 --- a/src/serial.c +++ b/src/serial.c @@ -299,7 +299,7 @@ void serialInit(uint32_t baudrate) } if (feature(FEATURE_SERVO_TILT)) availableBoxes[idx++] = BOXCAMSTAB; - if (feature(FEATURE_GPS) && sensors(SENSOR_GPS)) { + if (feature(FEATURE_GPS)) { availableBoxes[idx++] = BOXGPSHOME; availableBoxes[idx++] = BOXGPSHOLD; } From ca7d7e32f6f240d2b86283226aa8a03b87be6793 Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Sun, 13 Oct 2013 16:19:46 +0000 Subject: [PATCH 09/56] removed some double promotions that sneaked in, as well as replaced fabs() with float-only fabsf() version. trashed doubles from _atof(). Considering trashing that whole function for KEIL builds. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@439 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/cli.c | 27 ++++++++++++++------------- src/drv_hmc5883l.c | 6 +++--- src/imu.c | 2 +- 3 files changed, 18 insertions(+), 17 deletions(-) diff --git a/src/cli.c b/src/cli.c index f28e2d515..b3e84fdb6 100644 --- a/src/cli.c +++ b/src/cli.c @@ -258,7 +258,7 @@ char *itoa(int i, char *a, int r) static float _atof(const char *p) { int frac = 0; - double sign, value, scale; + float sign, value, scale; // Skip leading white space, if any. while (white_space(*p) ) { @@ -266,9 +266,9 @@ static float _atof(const char *p) } // Get sign, if any. - sign = 1.0; + sign = 1.0f; if (*p == '-') { - sign = -1.0; + sign = -1.0f; p += 1; } else if (*p == '+') { @@ -276,26 +276,26 @@ static float _atof(const char *p) } // Get digits before decimal point or exponent, if any. - value = 0.0; + value = 0.0f; while (valid_digit(*p)) { - value = value * 10.0 + (*p - '0'); + value = value * 10.0f + (*p - '0'); p += 1; } // Get digits after decimal point, if any. if (*p == '.') { - double pow10 = 10.0; + float pow10 = 10.0f; p += 1; while (valid_digit(*p)) { value += (*p - '0') / pow10; - pow10 *= 10.0; + pow10 *= 10.0f; p += 1; } } // Handle exponent, if any. - scale = 1.0; + scale = 1.0f; if ((*p == 'e') || (*p == 'E')) { unsigned int expon; p += 1; @@ -316,12 +316,13 @@ static float _atof(const char *p) expon = expon * 10 + (*p - '0'); p += 1; } - if (expon > 308) expon = 308; + if (expon > 308) + expon = 308; // Calculate scaling factor. - while (expon >= 50) { scale *= 1E50; expon -= 50; } - while (expon >= 8) { scale *= 1E8; expon -= 8; } - while (expon > 0) { scale *= 10.0; expon -= 1; } + // while (expon >= 50) { scale *= 1E50f; expon -= 50; } + while (expon >= 8) { scale *= 1E8f; expon -= 8; } + while (expon > 0) { scale *= 10.0f; expon -= 1; } } // Return signed and scaled floating point result. @@ -445,7 +446,7 @@ static void cliCMix(char *cmdline) } cliPrint("Sanity check:\t"); for (i = 0; i < 3; i++) - cliPrint(fabs(mixsum[i]) > 0.01f ? "NG\t" : "OK\t"); + cliPrint(fabsf(mixsum[i]) > 0.01f ? "NG\t" : "OK\t"); cliPrint("\r\n"); return; } else if (strncasecmp(cmdline, "reset", 5) == 0) { diff --git a/src/drv_hmc5883l.c b/src/drv_hmc5883l.c index d7817df8b..227719f74 100755 --- a/src/drv_hmc5883l.c +++ b/src/drv_hmc5883l.c @@ -157,9 +157,9 @@ void hmc5883lInit(void) LED1_TOGGLE; } - magGain[X] = fabs(660.0f * HMC58X3_X_SELF_TEST_GAUSS * 2.0f * 10.0f / xyz_total[X]); - magGain[Y] = fabs(660.0f * HMC58X3_Y_SELF_TEST_GAUSS * 2.0f * 10.0f / xyz_total[Y]); - magGain[Z] = fabs(660.0f * HMC58X3_Z_SELF_TEST_GAUSS * 2.0f * 10.0f / xyz_total[Z]); + magGain[X] = fabsf(660.0f * HMC58X3_X_SELF_TEST_GAUSS * 2.0f * 10.0f / xyz_total[X]); + magGain[Y] = fabsf(660.0f * HMC58X3_Y_SELF_TEST_GAUSS * 2.0f * 10.0f / xyz_total[Y]); + magGain[Z] = fabsf(660.0f * HMC58X3_Z_SELF_TEST_GAUSS * 2.0f * 10.0f / xyz_total[Z]); // leave test mode i2cWrite(MAG_ADDRESS, HMC58X3_R_CONFA, 0x70); // Configuration Register A -- 0 11 100 00 num samples: 8 ; output rate: 15Hz ; normal measurement mode diff --git a/src/imu.c b/src/imu.c index e0bd39626..13c73d13e 100755 --- a/src/imu.c +++ b/src/imu.c @@ -350,7 +350,7 @@ int getEstimatedAltitude(void) BaroAlt_tmp = 153.8462f * (baroTemperature + 27315) * (1.0f - expf(0.190259f * logf(PressureScaling))); // in cm BaroAlt = (float)BaroAlt * cfg.baro_noise_lpf + (float)BaroAlt_tmp * (1.0f - cfg.baro_noise_lpf); // additional LPF to reduce baro noise - dt = accTimeSum * 1e-6; // delta acc reading time in seconds + dt = accTimeSum * 1e-6f; // delta acc reading time in seconds // Integrator - velocity, cm/sec vel_acc = (float)accSum[2] * accVelScale * (float)accTimeSum / (float)accSumCount; From c1d82bcf46e441b3ba1699389e3a16b3894d9876 Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Mon, 14 Oct 2013 22:42:32 +0000 Subject: [PATCH 10/56] fixed bug in task state machine introduced by re-adding gps thread. thanks to alu for catching it. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@441 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/mw.c | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/mw.c b/src/mw.c index e93e59c73..09ac3b79d 100755 --- a/src/mw.c +++ b/src/mw.c @@ -781,9 +781,11 @@ void loop(void) // if GPS feature is enabled, gpsThread() will be called at some intervals to check for stuck // hardware, wrong baud rates, init GPS if needed, etc. Don't use SENSOR_GPS here as gpsThread() can and will // change this based on available hardware - if (feature(FEATURE_GPS)) + taskOrder++; + if (feature(FEATURE_GPS)) { gpsThread(); - break; + break; + } case 4: taskOrder++; #ifdef SONAR From 134a37d81122aed7c974199e9361738cc417e163 Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Fri, 18 Oct 2013 15:38:39 +0000 Subject: [PATCH 11/56] corrected a bug that would cause motors to spin up after saving parameters in 3D mode, thx englishman. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@443 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/drv_pwm.c | 2 +- src/drv_pwm.h | 2 ++ src/main.c | 1 + 3 files changed, 4 insertions(+), 1 deletion(-) diff --git a/src/drv_pwm.c b/src/drv_pwm.c index 6a0c7e2c8..5ff9d8b31 100755 --- a/src/drv_pwm.c +++ b/src/drv_pwm.c @@ -354,7 +354,7 @@ bool pwmInit(drv_pwm_config_t *init) pwmInConfig(port, pwmCallback, numInputs); numInputs++; } else if (mask & TYPE_M) { - motors[numMotors++] = pwmOutConfig(port, 1000000 / init->motorPwmRate, PULSE_1MS); + motors[numMotors++] = pwmOutConfig(port, 1000000 / init->motorPwmRate, init->idlePulse > 0 ? init->idlePulse : PULSE_1MS); } else if (mask & TYPE_S) { servos[numServos++] = pwmOutConfig(port, 1000000 / init->servoPwmRate, PULSE_1MS); } diff --git a/src/drv_pwm.h b/src/drv_pwm.h index 728ac8eec..491ee93b8 100755 --- a/src/drv_pwm.h +++ b/src/drv_pwm.h @@ -15,6 +15,8 @@ typedef struct drv_pwm_config_t { uint8_t adcChannel; // steal one RC input for current sensor uint16_t motorPwmRate; uint16_t servoPwmRate; + uint16_t idlePulse; // PWM value to use when initializing the driver; + // default of zero means PULSE_1MS, otherwise set to given value. Used by 3D mode. uint16_t failsafeThreshold; } drv_pwm_config_t; diff --git a/src/main.c b/src/main.c index 3b471e3c3..d5f8f5f45 100755 --- a/src/main.c +++ b/src/main.c @@ -67,6 +67,7 @@ int main(void) pwm_params.extraServos = cfg.gimbal_flags & GIMBAL_FORWARDAUX; pwm_params.motorPwmRate = mcfg.motor_pwm_rate; pwm_params.servoPwmRate = mcfg.servo_pwm_rate; + pwm_params.idlePulse = feature(FEATURE_3D) ? mcfg.neutral3d : 0; pwm_params.failsafeThreshold = cfg.failsafe_detect_threshold; switch (mcfg.power_adc_channel) { case 1: From 6b93f06e499ecd01b34bb9909c8ac96cc7e15e57 Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Sat, 19 Oct 2013 09:53:52 +0000 Subject: [PATCH 12/56] corrected mag task switcher for good this time git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@444 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/mw.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/mw.c b/src/mw.c index 09ac3b79d..77b646c0d 100755 --- a/src/mw.c +++ b/src/mw.c @@ -756,8 +756,8 @@ void loop(void) } } else { // not in rc loop static int taskOrder = 0; // never call all function in the same loop, to avoid high delay spikes - if (taskOrder > 3) - taskOrder -= 4; + if (taskOrder > 4) + taskOrder -= 5; switch (taskOrder) { case 0: taskOrder++; From 8d7f82dc7532d1652c8376a915465249ca3b0b68 Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Sat, 19 Oct 2013 09:56:29 +0000 Subject: [PATCH 13/56] added ability to specify arbitrary roll/pitch/yaw translation for board mounting by alu. this allows to mount FC vertically/upside down/etc easily. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@445 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/cli.c | 3 +++ src/config.c | 5 ++++- src/main.c | 1 + src/mw.h | 4 +++- src/utils.c | 46 ++++++++++++++++++++++++++++++++++++++++++++++ src/utils.h | 1 + 6 files changed, 58 insertions(+), 2 deletions(-) diff --git a/src/cli.c b/src/cli.c index b3e84fdb6..0715b1c7f 100644 --- a/src/cli.c +++ b/src/cli.c @@ -127,6 +127,9 @@ const clivalue_t valueTable[] = { { "align_gyro", VAR_UINT8, &mcfg.gyro_align, 0, 8 }, { "align_acc", VAR_UINT8, &mcfg.acc_align, 0, 8 }, { "align_mag", VAR_UINT8, &mcfg.mag_align, 0, 8 }, + { "align_board_roll", VAR_INT16, &mcfg.board_align_roll, -180, 360 }, + { "align_board_pitch", VAR_INT16, &mcfg.board_align_pitch, -180, 360 }, + { "align_board_yaw", VAR_INT16, &mcfg.board_align_yaw, -180, 360 }, { "yaw_control_direction", VAR_INT8, &mcfg.yaw_control_direction, -1, 1 }, { "acc_hardware", VAR_UINT8, &mcfg.acc_hardware, 0, 5 }, { "moron_threshold", VAR_UINT8, &mcfg.moron_threshold, 0, 128 }, diff --git a/src/config.c b/src/config.c index c7b069190..5eba07abe 100755 --- a/src/config.c +++ b/src/config.c @@ -13,7 +13,7 @@ master_t mcfg; // master config struct with data independent from profiles config_t cfg; // profile config struct const char rcChannelLetters[] = "AERT1234"; -static const uint8_t EEPROM_CONF_VERSION = 53; +static const uint8_t EEPROM_CONF_VERSION = 54; static uint32_t enabledSensors = 0; static void resetConf(void); @@ -180,6 +180,9 @@ static void resetConf(void) mcfg.gyro_align = ALIGN_DEFAULT; mcfg.acc_align = ALIGN_DEFAULT; mcfg.mag_align = ALIGN_DEFAULT; + mcfg.board_align_roll = 0; + mcfg.board_align_pitch = 0; + mcfg.board_align_yaw = 0; mcfg.acc_hardware = ACC_DEFAULT; // default/autodetect mcfg.yaw_control_direction = 1; mcfg.moron_threshold = 32; diff --git a/src/main.c b/src/main.c index d5f8f5f45..3a84734b1 100755 --- a/src/main.c +++ b/src/main.c @@ -49,6 +49,7 @@ int main(void) } adcInit(&adc_params); + initBoardAlignment(); // We have these sensors; SENSORS_SET defined in board.h depending on hardware platform sensorsSet(SENSORS_SET); diff --git a/src/mw.h b/src/mw.h index 7f79d2804..88ba2dcd7 100755 --- a/src/mw.h +++ b/src/mw.h @@ -234,6 +234,9 @@ typedef struct master_t { sensor_align_e gyro_align; // gyro alignment sensor_align_e acc_align; // acc alignment sensor_align_e mag_align; // mag alignment + int16_t board_align_roll; // board alignment correction in roll (deg) + int16_t board_align_pitch; // board alignment correction in pitch (deg) + int16_t board_align_yaw; // board alignment correction in yaw (deg) int8_t yaw_control_direction; // change control direction of yaw (inverted, normal) uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device uint16_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen. @@ -285,7 +288,6 @@ typedef struct core_t { serialPort_t *rcvrport; bool useServo; uint8_t numRCChannels; - } core_t; typedef struct flags_t { diff --git a/src/utils.c b/src/utils.c index e755c9c57..0b31b002e 100644 --- a/src/utils.c +++ b/src/utils.c @@ -1,6 +1,9 @@ #include "board.h" #include "mw.h" +static bool standardBoardAlignment = true; // board orientation correction +static float boardRotation[3][3]; // matrix + int constrain(int amt, int low, int high) { if (amt < low) @@ -11,6 +14,46 @@ int constrain(int amt, int low, int high) return amt; } +void initBoardAlignment(void) +{ + float roll, pitch, yaw; + + // standard alignment, nothing to calculate + if (!mcfg.board_align_roll && !mcfg.board_align_pitch && !mcfg.board_align_yaw) + return; + + standardBoardAlignment = false; + + // deg2rad + roll = mcfg.board_align_roll * M_PI / 180.0f; + pitch = mcfg.board_align_pitch * M_PI / 180.0f; + yaw = mcfg.board_align_yaw * M_PI / 180.0f; + + // define rotation matrix + boardRotation[0][0] = cosf(roll) * cosf(pitch); + boardRotation[0][1] = cosf(roll) * sinf(pitch) * sinf(yaw) - sinf(roll) * cosf(yaw); + boardRotation[0][2] = cosf(roll) * sinf(pitch) * cosf(yaw) + sinf(roll) * sinf(yaw); + + boardRotation[1][0] = sinf(roll) * cosf(pitch); + boardRotation[1][1] = sinf(roll) * sinf(pitch) * sinf(yaw) + cosf(roll) * cosf(yaw); + boardRotation[1][2] = sinf(roll) * sinf(pitch) * cosf(yaw) - cosf(roll) * sinf(yaw); + + boardRotation[2][0] = -sinf(pitch); + boardRotation[2][1] = cosf(pitch) * sinf(yaw); + boardRotation[2][2] = cosf(pitch) * cosf(yaw); +} + +void alignBoard(int16_t *vec) +{ + int16_t x = vec[X]; + int16_t y = vec[Y]; + int16_t z = vec[Z]; + + vec[X] = boardRotation[0][0] * x + boardRotation[0][1] * y + boardRotation[0][2] * z; + vec[Y] = boardRotation[1][0] * x + boardRotation[1][1] * y + boardRotation[1][2] * z; + vec[Z] = boardRotation[2][0] * x + boardRotation[2][1] * y + boardRotation[2][2] * z; +} + void alignSensors(int16_t *src, int16_t *dest, uint8_t rotation) { switch (rotation) { @@ -57,4 +100,7 @@ void alignSensors(int16_t *src, int16_t *dest, uint8_t rotation) default: break; } + + if (!standardBoardAlignment) + alignBoard(dest); } diff --git a/src/utils.h b/src/utils.h index aca00681b..c6ef6b8cb 100644 --- a/src/utils.h +++ b/src/utils.h @@ -3,3 +3,4 @@ int constrain(int amt, int low, int high); // sensor orientation void alignSensors(int16_t *src, int16_t *dest, uint8_t rotation); +void initBoardAlignment(void); From 47a4d30358d8c5b8502e14b70198dc23c399c7be Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Mon, 21 Oct 2013 00:22:33 +0000 Subject: [PATCH 14/56] fixed cli status command (thx alexk) moved mpuscale into core struct since it's not a changeable setting git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@447 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/cli.c | 4 ++-- src/mw.h | 10 +++++----- src/sensors.c | 4 ++-- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/cli.c b/src/cli.c index 0715b1c7f..0947e16bf 100644 --- a/src/cli.c +++ b/src/cli.c @@ -50,7 +50,7 @@ static const char * const featureNames[] = { // sync this with AvailableSensors enum from board.h static const char * const sensorNames[] = { - "ACC", "BARO", "MAG", "SONAR", "GPS", NULL + "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", NULL }; static const char * const accNames[] = { @@ -896,7 +896,7 @@ static void cliStatus(char *cmdline) if (sensors(SENSOR_ACC)) { printf("ACCHW: %s", accNames[accHardware]); if (accHardware == ACC_MPU6050) - printf(".%c", mcfg.mpu6050_scale ? 'o' : 'n'); + printf(".%c", core.mpu6050_scale ? 'o' : 'n'); } cliPrint("\r\n"); diff --git a/src/mw.h b/src/mw.h index 88ba2dcd7..207fe0cb7 100755 --- a/src/mw.h +++ b/src/mw.h @@ -244,7 +244,6 @@ typedef struct master_t { uint16_t gyro_cmpfm_factor; // Set the Gyro Weight for Gyro/Magnetometer complementary filter. Increasing this value would reduce and delay Magnetometer influence on the output of the filter uint32_t gyro_smoothing_factor; // How much to smoothen with per axis (32bit value with Roll, Pitch, Yaw in bits 24, 16, 8 respectively uint8_t moron_threshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default. - uint8_t mpu6050_scale; // es/non-es variance between MPU6050 sensors, half my boards are mpu6000ES, need this to be dynamic. automatically set by mpu6050 driver. int16_t accZero[3]; int16_t magZero[3]; @@ -265,11 +264,11 @@ typedef struct master_t { uint8_t rssi_aux_channel; // Read rssi from channel. 1+ = AUX1+, 0 to disable. // gps-related stuff - uint8_t gps_type; // Type of GPS hardware. 0: NMEA 1: UBX 2: MTK + uint8_t gps_type; // Type of GPS hardware. 0: NMEA 1: UBX 2: MTK NMEA 3: MTK Binary int8_t gps_baudrate; // GPS baudrate, -1: autodetect (NMEA only), 0: 115200, 1: 57600, 2: 38400, 3: 19200, 4: 9600 uint32_t serial_baudrate; - + uint32_t softserial_baudrate; uint8_t softserial_inverted; // use inverted softserial input and output signals @@ -286,8 +285,9 @@ typedef struct core_t { serialPort_t *gpsport; serialPort_t *telemport; serialPort_t *rcvrport; - bool useServo; - uint8_t numRCChannels; + uint8_t mpu6050_scale; // es/non-es variance between MPU6050 sensors, half my boards are mpu6000ES, need this to be dynamic. automatically set by mpu6050 driver. + uint8_t numRCChannels; // number of rc channels as reported by current input driver + bool useServo; // feature SERVO_TILT or wing/airplane mixers will enable this } core_t; typedef struct flags_t { diff --git a/src/sensors.c b/src/sensors.c index ff4738b72..ed3bd94c3 100755 --- a/src/sensors.c +++ b/src/sensors.c @@ -36,7 +36,7 @@ void sensorsAutodetect(void) bool haveMpu6k = false; // Autodetect gyro hardware. We have MPU3050 or MPU6050. - if (mpu6050Detect(&acc, &gyro, mcfg.gyro_lpf, &mcfg.mpu6050_scale)) { + if (mpu6050Detect(&acc, &gyro, mcfg.gyro_lpf, &core.mpu6050_scale)) { // this filled up acc.* struct with init values haveMpu6k = true; } else if (l3g4200dDetect(&gyro, mcfg.gyro_lpf)) { @@ -64,7 +64,7 @@ retry: ; // fallthrough case ACC_MPU6050: // MPU6050 if (haveMpu6k) { - mpu6050Detect(&acc, &gyro, mcfg.gyro_lpf, &mcfg.mpu6050_scale); // yes, i'm rerunning it again. re-fill acc struct + mpu6050Detect(&acc, &gyro, mcfg.gyro_lpf, &core.mpu6050_scale); // yes, i'm rerunning it again. re-fill acc struct accHardware = ACC_MPU6050; if (mcfg.acc_hardware == ACC_MPU6050) break; From 779dfe8a926af933153f9e7a4dc93d0091e2f8bf Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Wed, 23 Oct 2013 09:47:38 +0000 Subject: [PATCH 15/56] separate all telemetry code and add option to use softserial for telemetry. to use, set softserial_baudrate=9600, softserial_inverted=1 and telemetry_softserial=1 then enable feature TELEMETRY. by disq git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@448 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/board.h | 5 +++++ src/cli.c | 1 + src/config.c | 3 ++- src/main.c | 5 ++++- src/mw.c | 4 ++-- src/mw.h | 5 ++++- src/serial.c | 6 ++---- src/telemetry.c | 32 +++++++++++++++++++++++++++----- 8 files changed, 47 insertions(+), 14 deletions(-) diff --git a/src/board.h b/src/board.h index 757a847a1..b3604eb40 100755 --- a/src/board.h +++ b/src/board.h @@ -90,6 +90,11 @@ typedef enum { GPS_MTK_BINARY, } GPSHardware; +typedef enum { + TELEMETRY_UART = 0, + TELEMETRY_SOFTSERIAL, +} TelemetrySerial; + typedef enum { X = 0, Y, diff --git a/src/cli.c b/src/cli.c index 0947e16bf..002c46018 100644 --- a/src/cli.c +++ b/src/cli.c @@ -120,6 +120,7 @@ const clivalue_t valueTable[] = { { "gps_type", VAR_UINT8, &mcfg.gps_type, 0, 3 }, { "gps_baudrate", VAR_INT8, &mcfg.gps_baudrate, -1, 4 }, { "serialrx_type", VAR_UINT8, &mcfg.serialrx_type, 0, 2 }, + { "telemetry_softserial", VAR_UINT8, &mcfg.telemetry_softserial, 0, 1 }, { "vbatscale", VAR_UINT8, &mcfg.vbatscale, 10, 200 }, { "vbatmaxcellvoltage", VAR_UINT8, &mcfg.vbatmaxcellvoltage, 10, 50 }, { "vbatmincellvoltage", VAR_UINT8, &mcfg.vbatmincellvoltage, 10, 50 }, diff --git a/src/config.c b/src/config.c index 5eba07abe..fe2b5d7eb 100755 --- a/src/config.c +++ b/src/config.c @@ -13,7 +13,7 @@ master_t mcfg; // master config struct with data independent from profiles config_t cfg; // profile config struct const char rcChannelLetters[] = "AERT1234"; -static const uint8_t EEPROM_CONF_VERSION = 54; +static const uint8_t EEPROM_CONF_VERSION = 55; static uint32_t enabledSensors = 0; static void resetConf(void); @@ -192,6 +192,7 @@ static void resetConf(void) mcfg.vbatmincellvoltage = 33; mcfg.power_adc_channel = 0; mcfg.serialrx_type = 0; + mcfg.telemetry_softserial = 0; mcfg.midrc = 1500; mcfg.mincheck = 1100; mcfg.maxcheck = 1900; diff --git a/src/main.c b/src/main.c index 3a84734b1..0926a87db 100755 --- a/src/main.c +++ b/src/main.c @@ -139,7 +139,7 @@ int main(void) batteryInit(); serialInit(mcfg.serial_baudrate); - + if (feature(FEATURE_SOFTSERIAL)) { setupSoftSerial1(mcfg.softserial_baudrate, mcfg.softserial_inverted); #ifdef SOFTSERIAL_LOOPBACK @@ -148,6 +148,9 @@ int main(void) #endif } + if (feature(FEATURE_TELEMETRY)) + initTelemetry(); + previousTime = micros(); if (mcfg.mixerConfiguration == MULTITYPE_GIMBAL) calibratingA = CALIBRATING_ACC_CYCLES; diff --git a/src/mw.c b/src/mw.c index 77b646c0d..19dd864c1 100755 --- a/src/mw.c +++ b/src/mw.c @@ -177,9 +177,9 @@ void annexCode(void) LED0_OFF; if (f.ARMED) LED0_ON; - // This will switch to/from 9600 or 115200 baud depending on state. Of course, it should only do it on changes. + // This will switch to/from 9600 or 115200 baud depending on state. Of course, it should only do it on changes. With telemetry_softserial>0 telemetry is always enabled, also see updateTelemetryState() if (feature(FEATURE_TELEMETRY)) - initTelemetry(f.ARMED); + updateTelemetryState(); } #ifdef LEDRING diff --git a/src/mw.h b/src/mw.h index 207fe0cb7..286f2e9e6 100755 --- a/src/mw.h +++ b/src/mw.h @@ -272,6 +272,8 @@ typedef struct master_t { uint32_t softserial_baudrate; uint8_t softserial_inverted; // use inverted softserial input and output signals + uint8_t telemetry_softserial; // Serial to use for Telemetry. 0:USART1, 1:SoftSerial1 (Enable FEATURE_SOFTSERIAL first) + config_t profile[3]; // 3 separate profiles uint8_t current_profile; // currently loaded profile @@ -456,5 +458,6 @@ void GPS_set_next_wp(int32_t* lat, int32_t* lon); int32_t wrap_18000(int32_t error); // telemetry -void initTelemetry(bool State); +void initTelemetry(void); +void updateTelemetryState(void); void sendTelemetry(void); diff --git a/src/serial.c b/src/serial.c index b20dc7a3d..d06779f2f 100755 --- a/src/serial.c +++ b/src/serial.c @@ -269,8 +269,7 @@ void serialInit(uint32_t baudrate) bool hfadded = false; core.mainport = uartOpen(USART1, NULL, baudrate, MODE_RXTX); - // TODO fix/hax - core.telemport = core.mainport; + // calculate used boxes based on features and fill availableBoxes[] array memset(availableBoxes, 0xFF, sizeof(availableBoxes)); @@ -764,8 +763,7 @@ void serialCom(void) c_state = IDLE; } } - if (!cliMode && !serialTotalBytesWaiting(core.telemport) && feature(FEATURE_TELEMETRY) && f.ARMED) { // The first 2 conditions should never evaluate to true but I'm putting it here anyway - silpstream + if (!cliMode && feature(FEATURE_TELEMETRY)) { // The first condition should never evaluate to true but I'm putting it here anyway - silpstream sendTelemetry(); - return; } } diff --git a/src/telemetry.c b/src/telemetry.c index 3868723a1..0e92ecb22 100644 --- a/src/telemetry.c +++ b/src/telemetry.c @@ -202,13 +202,29 @@ static void sendHeading(void) static bool telemetryEnabled = false; -void initTelemetry(bool State) +void initTelemetry(void) { + // Sanity check for softserial vs. telemetry port + if (!feature(FEATURE_SOFTSERIAL)) + mcfg.telemetry_softserial = TELEMETRY_UART; + + if (mcfg.telemetry_softserial == TELEMETRY_SOFTSERIAL) + core.telemport = &(softSerialPorts[0].port); + else + core.telemport = core.mainport; +} + +void updateTelemetryState(void) +{ + bool State = mcfg.telemetry_softserial != TELEMETRY_UART ? true : f.ARMED; + if (State != telemetryEnabled) { - if (State) - serialInit(9600); - else - serialInit(mcfg.serial_baudrate); + if (mcfg.telemetry_softserial == TELEMETRY_UART) { + if (State) + serialInit(9600); + else + serialInit(mcfg.serial_baudrate); + } telemetryEnabled = State; } } @@ -218,6 +234,12 @@ static uint8_t cycleNum = 0; void sendTelemetry(void) { + if (mcfg.telemetry_softserial == TELEMETRY_UART && !f.ARMED) + return; + + if (serialTotalBytesWaiting(core.telemport) != 0) + return; + if (millis() - lastCycleTime >= CYCLETIME) { lastCycleTime = millis(); cycleNum++; From 35927540b18399fea61dc5f78bec9cc1bcd09de8 Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Wed, 23 Oct 2013 09:52:04 +0000 Subject: [PATCH 16/56] cleaning up some misc fuckups from msp handler git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@449 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/serial.c | 50 +++----------------------------------------------- 1 file changed, 3 insertions(+), 47 deletions(-) diff --git a/src/serial.c b/src/serial.c index d06779f2f..664c820b5 100755 --- a/src/serial.c +++ b/src/serial.c @@ -90,51 +90,6 @@ static uint8_t availableBoxes[CHECKBOXITEMS]; // this is the number of filled indexes in above array static uint8_t numberBoxItems = 0; -static const char boxnames[] = - "ARM;" - "ANGLE;" - "HORIZON;" - "BARO;" - "VARIO;" - "MAG;" - "HEADFREE;" - "HEADADJ;" - "CAMSTAB;" - "CAMTRIG;" - "GPS HOME;" - "GPS HOLD;" - "PASSTHRU;" - "BEEPER;" - "LEDMAX;" - "LEDLOW;" - "LLIGHTS;" - "CALIB;" - "GOVERNOR;" - "OSD SW;"; - -const uint8_t boxids[] = { // permanent IDs associated to boxes. This way, you can rely on an ID number to identify a BOX function. - 0, // "ARM;" - 1, // "ANGLE;" - 2, // "HORIZON;" - 3, // "BARO;" - 4, // "VARIO;" - 5, // "MAG;" - 6, // "HEADFREE;" - 7, // "HEADADJ;" - 8, // "CAMSTAB;" - 9, // "CAMTRIG;" - 10, // "GPS HOME;" - 11, // "GPS HOLD;" - 12, // "PASSTHRU;" - 13, // "BEEPER;" - 14, // "LEDMAX;" - 15, // "LEDLOW;" - 16, // "LLIGHTS;" - 17, // "CALIB;" - 18, // "GOVERNOR;" - 19, // "OSD_SWITCH;" -}; - static const char pidnames[] = "ROLL;" "PITCH;" @@ -305,6 +260,7 @@ void serialInit(uint32_t baudrate) if (mcfg.mixerConfiguration == MULTITYPE_FLYING_WING || mcfg.mixerConfiguration == MULTITYPE_AIRPLANE) availableBoxes[idx++] = BOXPASSTHRU; availableBoxes[idx++] = BOXBEEPERON; + availableBoxes[idx++] = BOXOSD; if (feature(FEATURE_INFLIGHT_ACC_CAL)) availableBoxes[idx++] = BOXCALIB; numberBoxItems = idx; @@ -400,7 +356,7 @@ static void evaluateCommand(void) serialize16(cycleTime); serialize16(i2cGetErrorCounter()); serialize16(sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4); -#if FUCK_MULTIWII +#ifdef FUCK_MULTIWII // OK, so you waste all the fucking time to have BOXNAMES and BOXINDEXES etc, and then you go ahead and serialize enabled shit simply by stuffing all // the bits in order, instead of setting the enabled bits based on BOXINDEX. WHERE IS THE FUCKING LOGIC IN THIS, FUCKWADS. serialize32(f.ANGLE_MODE << BOXANGLE | f.HORIZON_MODE << BOXHORIZON | @@ -452,7 +408,7 @@ static void evaluateCommand(void) break; default: // These just directly rely on their RC inputs - val = rcOptions[ box ]; + val = rcOptions[box]; break; } tmp |= (val << i); From 7ce9aab3d89448683b79a3bd98ee47867d5631dd Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Thu, 24 Oct 2013 00:37:20 +0000 Subject: [PATCH 17/56] fixing servo output for flying_wing w/new servo reorganization git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@450 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/mixer.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/mixer.c b/src/mixer.c index 1b1e6bb52..87d31aa72 100755 --- a/src/mixer.c +++ b/src/mixer.c @@ -240,6 +240,10 @@ void writeServos(void) break; case MULTITYPE_FLYING_WING: + pwmWriteServo(0, servo[3]); + pwmWriteServo(1, servo[4]); + break; + case MULTITYPE_GIMBAL: pwmWriteServo(0, servo[0]); pwmWriteServo(1, servo[1]); From d63c1f060434bc01d4c61c7fdb82105521407516 Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Thu, 24 Oct 2013 11:34:32 +0000 Subject: [PATCH 18/56] Properly set ADXL345 driver default orientation (thx enots) Fixed compile error in i2c_soft driver which still used old GPIO init syntax. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@451 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/drv_adxl345.c | 2 +- src/drv_i2c_soft.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drv_adxl345.c b/src/drv_adxl345.c index eab106549..a8890e2e9 100755 --- a/src/drv_adxl345.c +++ b/src/drv_adxl345.c @@ -35,7 +35,7 @@ static void adxl345Init(sensor_align_e align); static void adxl345Read(int16_t *accelData); static bool useFifo = false; -static sensor_align_e accAlign = CW0_DEG; +static sensor_align_e accAlign = CW270_DEG; bool adxl345Detect(drv_adxl345_config_t *init, sensor_t *acc) { diff --git a/src/drv_i2c_soft.c b/src/drv_i2c_soft.c index 264ff0664..3fdcf1a13 100644 --- a/src/drv_i2c_soft.c +++ b/src/drv_i2c_soft.c @@ -131,7 +131,7 @@ static uint8_t I2C_ReceiveByte(void) void i2cInit(I2C_TypeDef * I2C) { - GPIO_Config gpio; + gpio_config_t gpio; gpio.pin = Pin_10 | Pin_11; gpio.speed = Speed_2MHz; From 5bbf2bc88dedcda7f5cb76e9eee518d4e3095c04 Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Sun, 27 Oct 2013 11:40:45 +0000 Subject: [PATCH 19/56] rewrote box serialization to not use a buffer, also maybe fixed mismatched boxes in GUI (thx Luggi09) git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@452 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/serial.c | 29 ++++++++++++++++++----------- 1 file changed, 18 insertions(+), 11 deletions(-) diff --git a/src/serial.c b/src/serial.c index 664c820b5..2fbd44e12 100755 --- a/src/serial.c +++ b/src/serial.c @@ -201,21 +201,28 @@ void serializeNames(const char *s) void serializeBoxNamesReply(void) { - char buf[256]; // no fucking idea - char *c; - int i, j; + int i, j, k, flag = 1, count = 0, len; - memset(buf, 0, sizeof(buf)); - for (i = 0; i < CHECKBOXITEMS; i++) { - for (j = 0; j < numberBoxItems; j++) { - if (boxes[i].boxIndex == availableBoxes[j]) - strcat(buf, boxes[i].boxName); +reset: + for (i = 0; i < numberBoxItems; i++) { + for (j = 0; j < CHECKBOXITEMS; j++) { + if (boxes[j].boxIndex == availableBoxes[i]) { + len = strlen(boxes[j].boxName); + if (flag) { + count += len; + } else { + for (k = 0; k < len; k++) + serialize8(boxes[j].boxName[k]); + } + } } } - headSerialReply(strlen(buf)); - for (c = buf; *c; c++) - serialize8(*c); + if (flag) { + headSerialReply(count); + flag = 0; + goto reset; + } } void serialInit(uint32_t baudrate) From 241de2455e5a4632ac15a930122eff53eee2c8ab Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Sun, 27 Oct 2013 15:30:20 +0000 Subject: [PATCH 20/56] until multiwii retards fix their shit this is the only solution git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@459 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/serial.c | 16 ++++------------ 1 file changed, 4 insertions(+), 12 deletions(-) diff --git a/src/serial.c b/src/serial.c index 2fbd44e12..322cdcb63 100755 --- a/src/serial.c +++ b/src/serial.c @@ -228,7 +228,6 @@ reset: void serialInit(uint32_t baudrate) { int idx; - bool hfadded = false; core.mainport = uartOpen(USART1, NULL, baudrate, MODE_RXTX); @@ -240,23 +239,16 @@ void serialInit(uint32_t baudrate) if (sensors(SENSOR_ACC)) { availableBoxes[idx++] = BOXANGLE; availableBoxes[idx++] = BOXHORIZON; - availableBoxes[idx++] = BOXMAG; - availableBoxes[idx++] = BOXHEADFREE; - availableBoxes[idx++] = BOXHEADADJ; - hfadded = true; } if (sensors(SENSOR_BARO)) { availableBoxes[idx++] = BOXBARO; if (feature(FEATURE_VARIO)) availableBoxes[idx++] = BOXVARIO; } - if (sensors(SENSOR_MAG)) { - // this really shouldn't even needed to be tested as it wouldn't be possible without acc anyway - if (!hfadded) { - availableBoxes[idx++] = BOXMAG; - availableBoxes[idx++] = BOXHEADFREE; - availableBoxes[idx++] = BOXHEADADJ; - } + if (sensors(SENSOR_ACC) || sensors(SENSOR_MAG)) { + availableBoxes[idx++] = BOXMAG; + availableBoxes[idx++] = BOXHEADFREE; + availableBoxes[idx++] = BOXHEADADJ; } if (feature(FEATURE_SERVO_TILT)) availableBoxes[idx++] = BOXCAMSTAB; From e19aa617533d49cd9aa81b2174e3455eff68f1f5 Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Mon, 28 Oct 2013 00:58:32 +0000 Subject: [PATCH 21/56] OK, tarduino dudes aren't gonna fix their shit. So, let's live with it. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@460 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/serial.c | 77 ++++++++++++++-------------------------------------- 1 file changed, 20 insertions(+), 57 deletions(-) diff --git a/src/serial.c b/src/serial.c index 322cdcb63..b5d61c7ef 100755 --- a/src/serial.c +++ b/src/serial.c @@ -201,20 +201,19 @@ void serializeNames(const char *s) void serializeBoxNamesReply(void) { - int i, j, k, flag = 1, count = 0, len; + int i, idx, j, flag = 1, count = 0, len; reset: + // in first run of the loop, we grab total size of junk to be sent + // then come back and actually send it for (i = 0; i < numberBoxItems; i++) { - for (j = 0; j < CHECKBOXITEMS; j++) { - if (boxes[j].boxIndex == availableBoxes[i]) { - len = strlen(boxes[j].boxName); - if (flag) { - count += len; - } else { - for (k = 0; k < len; k++) - serialize8(boxes[j].boxName[k]); - } - } + idx = availableBoxes[i]; + len = strlen(boxes[idx].boxName); + if (flag) { + count += len; + } else { + for (j = 0; j < len; j++) + serialize8(boxes[idx].boxName[j]); } } @@ -259,15 +258,15 @@ void serialInit(uint32_t baudrate) if (mcfg.mixerConfiguration == MULTITYPE_FLYING_WING || mcfg.mixerConfiguration == MULTITYPE_AIRPLANE) availableBoxes[idx++] = BOXPASSTHRU; availableBoxes[idx++] = BOXBEEPERON; - availableBoxes[idx++] = BOXOSD; if (feature(FEATURE_INFLIGHT_ACC_CAL)) availableBoxes[idx++] = BOXCALIB; + availableBoxes[idx++] = BOXOSD; numberBoxItems = idx; } static void evaluateCommand(void) { - uint32_t i, tmp; + uint32_t i, tmp, junk; uint8_t wp_no; int32_t lat = 0, lon = 0, alt = 0; @@ -355,10 +354,11 @@ static void evaluateCommand(void) serialize16(cycleTime); serialize16(i2cGetErrorCounter()); serialize16(sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4); -#ifdef FUCK_MULTIWII // OK, so you waste all the fucking time to have BOXNAMES and BOXINDEXES etc, and then you go ahead and serialize enabled shit simply by stuffing all // the bits in order, instead of setting the enabled bits based on BOXINDEX. WHERE IS THE FUCKING LOGIC IN THIS, FUCKWADS. - serialize32(f.ANGLE_MODE << BOXANGLE | f.HORIZON_MODE << BOXHORIZON | + // Serialize the boxes in the order we delivered them, until multiwii retards fix their shit + junk = 0; + tmp = f.ANGLE_MODE << BOXANGLE | f.HORIZON_MODE << BOXHORIZON | f.BARO_MODE << BOXBARO | f.MAG_MODE << BOXMAG | f.HEADFREE_MODE << BOXHEADFREE | rcOptions[BOXHEADADJ] << BOXHEADADJ | rcOptions[BOXCAMSTAB] << BOXCAMSTAB | rcOptions[BOXCAMTRIG] << BOXCAMTRIG | f.GPS_HOME_MODE << BOXGPSHOME | f.GPS_HOLD_MODE << BOXGPSHOLD | @@ -370,50 +370,13 @@ static void evaluateCommand(void) rcOptions[BOXCALIB] << BOXCALIB | rcOptions[BOXGOV] << BOXGOV | rcOptions[BOXOSD] << BOXOSD | - f.ARMED << BOXARM); -#else - // Serialize the boxes in the order we delivered them - tmp = 0; + f.ARMED << BOXARM; for (i = 0; i < numberBoxItems; i++) { - uint8_t val, box = availableBoxes[i]; - switch (box) { - // Handle the special cases - case BOXANGLE: - val = f.ANGLE_MODE; - break; - case BOXHORIZON: - val = f.HORIZON_MODE; - break; - case BOXMAG: - val = f.MAG_MODE; - break; - case BOXBARO: - val = f.BARO_MODE; - break; - case BOXHEADFREE: - val = f.HEADFREE_MODE; - break; - case BOXGPSHOME: - val = f.GPS_HOME_MODE; - break; - case BOXGPSHOLD: - val = f.GPS_HOLD_MODE; - break; - case BOXPASSTHRU: - val = f.PASSTHRU_MODE; - break; - case BOXARM: - val = f.ARMED; - break; - default: - // These just directly rely on their RC inputs - val = rcOptions[box]; - break; - } - tmp |= (val << i); + int flag = (tmp & (1 << availableBoxes[i])); + if (flag) + junk |= 1 << i; } - serialize32(tmp); -#endif + serialize32(junk); serialize8(mcfg.current_profile); break; case MSP_RAW_IMU: From 2d076db9086ffb7f6cc778ff2c04b23375dfadf8 Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Mon, 28 Oct 2013 23:49:06 +0000 Subject: [PATCH 22/56] Built firmware to match r460. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@461 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- obj/baseflight.hex | 6602 ++++++++++++++++++++++---------------------- 1 file changed, 3301 insertions(+), 3301 deletions(-) diff --git a/obj/baseflight.hex b/obj/baseflight.hex index 361eeaa74..9223a1b61 100644 --- a/obj/baseflight.hex +++ b/obj/baseflight.hex @@ -1,781 +1,781 @@ :020000040800F2 -:1000000010250020919D0008D19D00088125000841 -:10001000D59D0008D79D0008D99D0008000000006C -:10002000000000000000000000000000DB9D000850 -:10003000DD9D000800000000DF9D000879780008C1 -:10004000E39D0008E39D0008E39D0008E39D000890 -:10005000E39D0008E39D0008E39D00084D8400082F -:10006000E39D0008E39D0008E39D0008E39D000870 -:10007000E39D0008E39D0008C57E0008E39D00089D -:10008000E39D0008E39D0008E39D0008E39D000850 -:10009000E39D0008E39D0008E39D000851840008EB -:1000A000E39D0008E39D0008E39D0008F18C000833 -:1000B000FD8C0008058D0008118D00089D73000857 -:1000C00075710008A5730008A1730008E39D00087E -:1000D000E39D0008F97E0008317F0008E39D0008D9 -:1000E00011690008E39D0008E39D0008DFF80CD0CB -:1000F0000AF004FC00480047852300081025002072 +:100000006029002035A4000875A4000823250008F5 +:1000100079A400087BA400087DA40008000000006B +:100020000000000000000000000000007FA40008A5 +:1000300081A400080000000083A40008957C00084B +:1000400087A4000887A4000887A4000887A40008E4 +:1000500087A4000887A4000887A40008DF87000899 +:1000600087A4000887A4000887A4000887A40008C4 +:1000700087A4000887A400085582000887A4000808 +:1000800087A4000887A4000887A4000887A40008A4 +:1000900087A4000887A4000887A40008E187000857 +:1000A00087A4000887A4000887A400083D900008E2 +:1000B00041900008479000084B9000080576000822 +:1000C000E3730008097600080776000887A4000893 +:1000D00087A4000881820008B582000887A4000870 +:1000E000216D000887A4000887A40008DFF80CD061 +:1000F0000AF014FD00480047E522000860290020AE :1001000070B51546B0FBF5F40646A84203D3204669 :10011000FFF7F6FF014605FB1460FCA2105C0870B7 :10012000481C70BD70B50C46911E232900D30A22CD :100130000025002804DA2D212170611C404200E0D6 -:100140002146FFF7DDFF0570204670BD2DE9F05F09 +:100140002146FFF7DDFF0570204670BD2DE9F04721 :10015000044600E0641C20782028FBD00928F9D050 -:10016000DFF8D0A3C1B24FF000092D2902D02B280F -:1001700004D004E0DFF8C0A34FF00009641C00269F -:100180003746DFF8B8B310E00AF0BEF905468846F6 -:1001900000225B46304639460AF0C7F82A464346F5 -:1001A0000AF01CF806460F46641C207830380928EF -:1001B000EAD920782E281CD10025DFF8808313E0AF -:1001C0000AF0A2F92A4643460AF021F932463B4694 -:1001D0000AF004F806460F4600225B4628464146D0 -:1001E0000AF0A3F80546884614F8010F30380928AC -:1001F000E6D922780020CF49652A01D0452A43D18B -:1002000014F8012F4FF000082D2A02D02B2A02D01B -:1002100002E04FF00108641C00256FF02F0305E099 -:1002200005EB850503EB45051544641C2278A2F116 -:10023000300CBCF1090FF3D94FF49A72954205D9ED -:100240001546BF4ABF4B0AF070F8323D322DF8D246 -:10025000BD4C082D0BD3002223460AF066F8083D5A -:10026000F7E7002223460AF060F86D1E00E05C46C6 -:10027000002DF6D1B8F1000F06D002460B463046ED -:1002800039460AF0C4F803E032463B460AF04DF81E -:100290004A4653460AF049F8BDE8F05F0AF07FB9D4 -:1002A000F0B587B000260D46A94900960196A7A78C -:1002B0000296B0F5000F02DB09F0B6FE01E009F08E -:1002C00005FFA44909F008FF0AF03CF9041E00DC10 -:1002D00060420A2203A9FFF725FF002C01DB202042 -:1002E00000E02D208DF8000003A809F070FE3024F6 -:1002F00001280AD003A809F06AFE02280CD003A83E -:1003000009F065FE03280CD00DE08DF801408DF852 -:1003100002408DF8034006E08DF801408DF8024060 -:1003200001E08DF8014003A9684609F01CFE68460B -:1003300009F04DFEC01EC4B222466946284609F0A7 -:1003400030FE2E553946284609F00DFE0DEB04010E -:10035000284609F008FE07B02846F0BD70B50546EE -:100360000C46086809F033FE024621682868BDE89B -:10037000704009F033BE70B5064609F028FE764D90 -:1003800010F0FF0F0FD0304609F041FE044614284C -:1003900015DA2021304609F010FE09F038FE05EB91 -:1003A0004401C88770BD002405EB44002146C28F7C -:1003B0006AA00AF051FB641C142CF5DB70BDBDE88B -:1003C0007040142168A00AF047BB2DE9F0410025D8 -:1003D00088B007462E4609F0FAFD6D4C10F0FF0F6D -:1003E000A84652D005226BA1384609F0F7FD002837 -:1003F0007ED0042269A1384609F0F0FD002878D0AB -:10040000384609F004FE461E0C2E73DA20213846C9 -:1004100009F0D3FD070007D0781C0746FFF796FECA -:1004200004EB0611012508612021384609F0C5FDBD -:10043000070007D0471C3846FFF788FE04EB06117B -:100440006D1C48612021384609F0B7FD070007D030 -:10045000471C3846FFF77AFE04EB06116D1C8861D5 -:100460002021384609F0A9FD30B1401CFFF76EFE8F -:1004700004EB06116D1CC861042D45D049A000BFD6 -:1004800000F074FF08B0BDE8F08155A000F06EFFE9 -:100490005FF0000504EB0517386910F0FF4F2BD013 -:1004A000761C691C59A00AF0D7FA03A93869FFF72E -:1004B000F7FE014657A00AF0CFFA03A97869FFF7C3 -:1004C000EFFE014653A00AF0C7FA03A9B869FFF787 -:1004D000E7FE01464FA00AF0BFFA03A9F869FFF74B -:1004E000DFFE01464CA00AF0B7FA6D1C0C2D02E0AD -:1004F000C1E0CAE0EFE0CDDBCDF80880CDF80480A4 -:100500000025CDF800809DE0E0E00000303132337E +:100160004FF07E58C1B247462D2902D02B2801D02E +:1001700001E0F04F641C0026DFF8BC930CE000BFE8 +:100180000AF07EFB0546494630460AF0F7FA294652 +:100190000AF09CFA0646641C207830380928EFD90A +:1001A00020782E2815D14D460EE000BF0AF068FBDE +:1001B00029460AF019FB31460AF088FA06464946F4 +:1001C00028460AF0DBFA054614F8010F30380928F2 +:1001D000ECD921784046652901D0452935D114F85C +:1001E000011F4FF000082D2902D02B2902D002E078 +:1001F0004FF00108641C00256FF02F0206E000BFDD +:1002000005EB850302EB4303CD18641C2178A1F1B3 +:100210003003092BF4D94FF49A718D4204D90D465D +:10022000C6490AF0ABFA083D082DF9D203E0494669 +:100230000AF0A4FA6D1E002DF9D1B8F1000F04D018 +:10024000014630460AF0D0FA03E0014630460AF093 +:1002500095FA3946BDE8F0470AF090BAF0B587B094 +:1002600000260D46B74900960196B5A70296B0F54F +:10027000000F02DB0AF02AFA01E00AF079FAB2492B +:100280000AF07CFA0AF00AFB041E00DC60420A2233 +:1002900003A9FFF747FF002C01DB202000E02D2001 +:1002A0008DF8000003A80AF0E4F9302401280AD0F0 +:1002B00003A80AF0DEF902280CD003A80AF0D9F945 +:1002C00003280CD00DE08DF801408DF802408DF828 +:1002D000034006E08DF801408DF8024001E08DF802 +:1002E000014003A968460AF090F968460AF0C1F98E +:1002F000C01EC4B22246694628460AF0A4F92E550B +:10030000394628460AF081F90DEB040128460AF027 +:100310007CF907B02846F0BD70B505460C46086864 +:100320000AF0A7F9024621682868BDE870400AF083 +:10033000A7B970B506460AF09CF9844D10F0FF0F7E +:100340000FD030460AF0B5F90446142815DA2021FA +:1003500030460AF084F90AF0ACF905EB4401C8878D +:1003600070BD002405EB44002146C28F78A00AF03E +:1003700073FC641C142CF5DB70BDBDE870401421C7 +:1003800076A00AF069BC2DE9F041002588B0074647 +:100390002E460AF06EF97B4C10F0FF0FA84652D0A3 +:1003A000052279A138460AF06BF900287ED0042294 +:1003B00077A138460AF064F9002878D038460AF068 +:1003C00078F9461E0C2E73DA202138460AF047F9D8 +:1003D000070007D0781C0746FFF7B8FE04EB0611AC +:1003E00001250861202138460AF039F9070007D0B5 +:1003F000471C3846FFF7AAFE04EB06116D1C486146 +:10040000202138460AF02BF9070007D0471C384650 +:10041000FFF79CFE04EB06116D1C88612021384615 +:100420000AF01DF930B1401CFFF790FE04EB0611F5 +:100430006D1CC861042D67D057A000BF00F070FF8D +:1004400008B0BDE8F08163A000F06AFF5FF000052E +:1004500004EB0517386910F0FF4F2BD0761C691C90 +:1004600067A00AF0F9FB03A93869FFF7F7FE014618 +:1004700065A00AF0F1FB03A97869FFF7EFFE0146DA +:1004800061A00AF0E9FB03A9B869FFF7E7FE01469E +:100490005DA00AF0E1FB03A9F869FFF7DFFE014662 +:1004A0005AA00AF0D9FB6D1C0C2D02E0C8E0D0E088 +:1004B000F5E0CDDBCDF80880CDF804800025CDF83F +:1004C000008011E004EB0517009879690AF0FEF846 +:1004D0000090B96901980AF0F9F80190F969029859 +:1004E0000AF0F4F86D1C0290B542EBDB49A000F075 +:1004F00017FF4C4E00246D4655F8240020F00040B4 +:10050000B04202DD48A092E0C4E08FE030313233E7 :100510003435363738394142434445464748494ADD :100520004B4C4D4E4F505152535455565758595AA3 -:10053000000000000000F03F0000F0BF0000244079 -:100540009A647EC50E1B514A84D797412E00000045 -:100550006F12033A00007A44500800206175782039 -:1005600025752025750D0A00496E76616C69642039 -:100570004665617475726520696E6465783A206DB0 -:10058000757374206265203C2025750D0A000000FB -:100590007004002072657365740000006C6F616404 -:1005A0000000000057726F6E67206E756D62657295 -:1005B000206F6620617267756D656E74732C206E96 -:1005C00065656473206964782074687220726F6C4A -:1005D0006C207069746368207961770D0A000000EF -:1005E000437573746F6D206D697865723A200D0ADA -:1005F0004D6F746F720954687209526F6C6C0950B8 -:1006000069746368095961770D0A00002325643A0B -:10061000090000002573090025730D0A0000000081 -:1006200004EB05170098796909F0FEFC0090B969A0 -:10063000019809F0F9FC0190F969029809F0F4FCBD -:100640006D1C0290B542EBDBF5A000F08FFEF84E7A -:1006500000246D4655F8240020F00040B04201DD32 -:10066000F4A000E0F4A000F081FE641C032CF1DB98 -:10067000AFF26C0004E700204FEA080104EB00121F -:10068000401C11610C28F9DBFCE62021384609F0FA -:1006900094FC0028F8D0401C054609F098FCE74E71 -:1006A000C7B2002456F8241031B13A46284609F062 -:1006B00095FC18B1641CF5E7E1A0E1E6204601F0E5 -:1006C000D1FF56F82410E4A00AF0C6F9AFF2A0104A -:1006D000FFF77BFED6E60C21E4A00AF0BDF9D1E6D7 -:1006E00010B5ECA000F042FE012001F000F9F0A0EE -:1006F00000F03CFE0A2007F0EFF8BDE810400020B3 -:1007000007F0B7B97CB504460D46007900210628EC -:1007100014D2DFE800F003060A0D111EA06801786C -:100720000CE0A06890F9001008E0A068018805E0DE -:10073000A068B0F9001001E0A0680168E0A00AF02C -:100740008BF9002D04D0D4E90312DEA00AF084F95D -:100750007CBDA06869460068FFF7A2FD0146DBA0EA -:100760000AF07AF9002DF3D0E06809F0BFFE69467F -:10077000FFF796FD0146D6A00AF06EF9206909F050 -:10078000B5FE6946FFF78CFD0146D1A00AF064F979 -:100790007CBD2DE9FF47CFA00AF05EF9C7A0FFF7A7 -:1007A000EAFDD84DA549687901EB800050F8041C9A -:1007B000D5A00AF051F9286910F0FF4F4CD0DFF8AE -:1007C00054A3002405EB0410066916F0FF4F3FD038 -:1007D000D0E90598C769611CCFA00AF03DF95645DC -:1007E00002D3CFA00AF038F969463046FFF758FD2A -:1007F0000146B6A00AF030F95646B14502D3C8A06A -:100800000AF02AF969464846FFF74AFD0146AFA0BB -:100810000AF022F9B04502D3C1A00AF01DF96946D9 -:100820004046FFF73DFD0146A8A00AF015F9B74282 -:1008300002D3BBA00AF010F969463846FFF730FD35 -:100840000146AFF22C200AF007F9641C0C2CB9DB2E -:10085000611CB4A00AF000F901F07AF8774E002488 -:1008600007464C3656F8241021B1B3A00AF0F4F82C -:10087000641CF7E700244FF0010800BF56F824106D -:1008800041B108FA04F0384202D0AFA00AF0E4F80F -:10089000641CF3E7B04A002069462C18135C94F8F6 -:1008A0000641401C08280B55F7DB00220A54ABA078 -:1008B0000AF0D2F8AC4D002404EB840005EB80066E -:1008C00055F82010A9A00AF0C7F800213046FFF71C -:1008D00019FF65A000F04AFD641C702CECD3BDE844 -:1008E000FF8710B5A4A000F041FD0121002000F019 -:1008F00036FEA4A000F03AFD0A2006F0EDFFBDE8A8 -:100900001040002007F0B5B810B50446A1A000F0D3 -:100910002DFDA64800210170A5480160A548017081 -:100920002046BDE81040DCE72DE9F047064609F017 -:100930004EFB054601F00CF8DFF8008107464FF04A -:10094000010908F14C0855B12A469BA1304609F02F -:1009500045FBC8B1307800272D2824D026E098A088 -:1009600000F004FD00244D464FEA080656F8241016 -:1009700041B105FA04F0384202D096A00AF06CF8B2 -:10098000641CF3E738A01EE093A000F0EFFC002405 -:100990004FEA080555F824100029F3D08DA00AF07D -:1009A0005BF8641CF6E70127761C6D1E5FF00004FF -:1009B00058F8241031B12A46304609F00FFB30B107 -:1009C000641CF5E78AA0BDE8F04700F0CFBC09FA47 -:1009D00004F01FB100F0B7FF8CA002E000F020FE91 -:1009E0008DA000F0C3FC58F82410BDE8F04758A0D3 -:1009F0000AF032B870B500248AA000F0B7FC5A4D56 -:100A0000B5F1A80504EB440005EB80014A6855F8F0 -:100A100020108AA00AF020F8641C0E2CF2D370BDBE -:100A200053616E69747920636865636B3A090000ED -:100A30000AD7233C4E4709004F4B0900B0B60008C7 -:100A4000496E76616C6964206D697865722074798D -:100A500070652E2E2E0D0A004C6F61646564202592 -:100A600073206D69782E2E2E0D0A00004D6F746F65 -:100A700072206E756D626572206D7573742062658B -:100A8000206265747765656E203120616E64202573 -:100A9000640D0A00526573657474696E6720746F23 -:100AA0002064656661756C74732E2E2E0D0A00002D -:100AB0005265626F6F74696E672E2E2E0000000003 -:100AC00025640000202564202564000025730000B3 -:100AD0002025730043757272656E7420436F6E66D5 -:100AE00069673A20436F707920657665727974681A -:100AF000696E672062656C6F7720686572652E2E5F -:100B00002E0D0A00700400206D697865722025732F -:100B10000D0A000000008080636D69782025640064 -:100B200020000000636D697820256420302030208B -:100B30003020300D0A000000666561747572652012 -:100B40002D25730D0A0000006665617475726520BD -:100B500025730D0A00000000D8C000086D617020E8 -:100B600025730D0A0000000018B800087365742092 -:100B70002573203D20000000536176696E672E2E9C -:100B80002E0000000D0A5265626F6F74696E672E49 -:100B90002E2E00000D0A4C656176696E6720434C6D -:100BA00049206D6F64652E2E2E0D0A004004002032 -:100BB00000000020BE0100206C697374000000007A -:100BC000456E61626C6564206665617475726573FB -:100BD0003A20000025732000417661696C61626CE7 -:100BE000652066656174757265733A2000000000C7 -:100BF000496E76616C696420666561747572652002 -:100C00006E616D652E2E2E0D0A0000004469736121 -:100C1000626C656420000000456E61626C65642052 -:100C200000000000417661696C61626C6520636F51 -:100C30006D6D616E64733A0D0A000000257309251D -:100C4000730D0A003EB5054609F0C1F908281DD10B -:100C50000024285D09F03AF92855641C082CF8D3C3 -:100C60000024FD48295D09F0A8F928B12819295D5B -:100C7000401C09F0A2F918B1F8A000F077FB3EBDC6 -:100C8000641C082CEDD3284600F0AAFBFBA000F062 -:100C90006DFBF14BFF4A0020694615181C5C95F866 -:100CA0000651401C08284C55F7D300220A54AFF2D5 -:100CB000601009F0D1FE3EBD2DE9F041804609F0FB -:100CC00086F9F44FF44D060012D00246AFF2181127 -:100CD000404609F083F990B15FF0000455F8241004 -:100CE000F1B13246404609F079F9F8B1641CF5E7F4 -:100CF000787905EB800050F8041CE8A01BE0ECA01C -:100D000000F034FB5FF0000455F8241029B1AFF275 -:100D10003C1009F0A1FE641CF6E7AFF2B42001E03C -:100D2000AFF2E420BDE8F04100F020BB601C787118 -:100D300055F82410E3A0BDE8F04109F08DBE70B570 -:100D4000054609F044F9D34C10F0FF0F0CD02846AB -:100D500009F05DF902280ED884F8DC03002108466A -:100D600000F0FDFBCAA0EBE794F8DC13BDE870408F -:100D7000D9A009F071BE52E62DE9F047814609F08D -:100D800026F9DB4D060029D0012E03D199F8000089 -:100D90002A2823D0D7A1484609F0F1F800286ED0C0 -:100DA000401C044609F033F982462046FFF7CEF98D -:100DB0008046002606EB860705EB870455F82700DA -:100DC00009F005F9024655F82710484609F006F9DA -:100DD000F8B1761C702EEDD3C7A04CE0CEA000F089 -:100DE000C5FA002404EB840005EB800755F82010B9 -:100DF000AFF2842009F030FE31463846FFF782FC1E -:100E0000AFF29C3000F0B2FA641C702CEAD3BDE85B -:100E1000F08706EB860605EB8607F86809F066FBA7 -:100E2000414609F0D9FB25D8386909F05FFB4146F6 -:100E300009F0DCFB1ED83979052907D05046062970 -:100E40000ED2DFE801F0050508080B0B4046F6E777 -:100E5000A168087004E0A168088001E0A16808604A -:100E600055F82610B2A009F0F7FD2046BDE8F0477E -:100E7000002147E4B1A0BDE8F04700F077BA0024B4 -:100E800004EB8406494655F8260009F078F878B155 -:100E900055F8261005EB8607AFF22C3009F0DCFD83 -:100EA00000213846FFF72EFCAFF2444009F0D4FD94 -:100EB000641C702CE4D3AAE72DE9F04106F0FEFC97 -:100EC0004FF47A71B0FBF1F1A6480378A648027896 -:100ED000A6A009F0C1FD00F02BFD0646B348B449B9 -:100EE0000068B0FBF1F1B3A009F0B6FD6A4F002431 -:100EF00001258C3757F8241051B105FA04F030421F -:100F000003D0AFF2303009F0A7FD641CE4B2F1E782 -:100F1000022000F0FBFCA8B1AE4C5F482178A43061 -:100F200050F82110ACA009F097FD2078022809D1D3 -:100F3000584890F8F50008B16F2100E06E21A9A093 -:100F400009F08AFDAFF2E04000F010FA06F079F8FF -:100F50000246A5484FF478730188BDE8F041A3A08C -:100F600009F07ABDAEA000F001BA2DE9FF5FDFF80D -:100F7000E09299F8000038B9012189F80010B5A075 -:100F800000F0F4F900F0FEF9DFF800B3DFF800A399 -:100F90005446DAF8000007F026FF00285AD02068EF -:100FA00007F024FF092807D03F2805D0DBF8001000 -:100FB0005C4600294FD077E100244D4F2546A83FDD -:100FC000DFF82C81DBF800600CE000BFDBF80020CC -:100FD00022B1B048396809F001F810B904B93C46AB -:100FE0003D460C374745F1D394B1AA4F5946226884 -:100FF00008682B68125C1B5C9A4209D192B92E28B2 -:1010000010D220223A54401C0021CBF80000395461 -:10101000DBF800005F4608B1AC4213D09EA000F0A0 -:10102000A5F90AE03A54401C0860E0E7206800F0A7 -:101030009DF9092000F0A8F90C34AC42F6D900F073 -:10104000A1F90026934C38688642A1D2A05D00F039 -:101050009BF925E188E125E1D8C000084D7573743E -:1010600020626520616E79206F72646572206F6600 -:101070002041455452313233340D0A0043757272A7 -:10108000656E742061737369676E6D656E743A2066 -:101090000000000070040020B0B6000843757272B2 -:1010A000656E74206D697865723A2025730D0A00AB -:1010B000417661696C61626C65206D6978657273F7 -:1010C0003A2000004D697865722073657420746F52 -:1010D0002025730D0A00000043757272656E74203E -:1010E00070726F66696C653A2025640D0A00000015 -:1010F00018B800083D0000004552523A20556E6B6A -:101100006E6F776E207661726961626C65206E61C8 -:101110006D650D0A0000000043757272656E7420E3 -:1011200073657474696E67733A200D0A00000000DD -:1011300025732073657420746F2000004552523A65 -:101140002056616C75652061737369676E6D656E9D -:1011500074206F7574206F662072616E67650D0A6A -:101160000000000071010020CA0000205379737450 -:10117000656D20557074696D653A2025642073652E -:10118000636F6E64732C20566F6C746167653A20D0 -:101190002564202A20302E315620282564532062D1 -:1011A000617474657279290D0A0000000C04002036 -:1011B00040420F004350552025644D487A2C20644E -:1011C000657465637465642073656E736F72733ADA -:1011D000200000008401002041434348573A202565 -:1011E000730000002E256300CC0000204379636C5F -:1011F000652054696D653A2025642C2049324320CE -:101200004572726F72733A2025642C20636F6E668C -:1012100069672073697A653A2025640D0A00000029 -:101220004166726F333220434C4920766572736990 -:101230006F6E20322E32204F6374202034203230E3 -:101240003133202F2032333A33343A313800000022 -:10125000BE0100200D0A456E746572696E672043F9 -:101260004C49204D6F64652C20747970652027658A -:101270007869742720746F2072657475726E2C20E3 -:101280006F72202768656C70270D0A00000000202F -:1012900068090020400400200D1B5B4B000000008B -:1012A000761CD0E6042813D00C2817D019B10A28D0 -:1012B00018D00D2816D07F2840D03029BFF468AE52 -:1012C0002028FFF465AE7E283FF662AEA9B343E066 -:1012D00004B03048BDE8F05FFFF716BB2EA000F069 -:1012E00045F827E0AFF6800000F040F8294E20686E -:1012F00000250C2335542B48CDE900060E222A493F -:10130000029501A808F0E8FD070007D0386808F04A -:101310005EFE3044B968401C884702E023A000F01C -:1013200025F830211B4808F013FE256099F80000CD -:10133000002819D000F026F82AE60BE00029FBD09F -:10134000144A491E0020CBF80010505420A000F091 -:101350000DF81DE62028EFD00E4A5054491CCBF85A -:10136000001000F011F813E6BDE8FF9F70B50446C9 -:10137000184D03E0641C286806F080FD21780029E0 -:10138000F8D1F8E414A0F1E701461248006806F02D -:1013900075BD0000400400201B5B324A1B5B313BE3 -:1013A000314800005D03000870B700084552523A0A -:1013B00020556E6B6E6F776E20636F6D6D616E641E -:1013C0002C20747279202768656C7027000000005B -:1013D00008200800680900200D0A232000000000F2 -:1013E0002DE9F04105460446FD4EFE4F09E0FC485C -:1013F00008F0E3FD20B1611B801B384480F8061122 -:10140000641C21780029F2D1BDE8F081F648002162 -:101410000278332A12D14288B2F5787F0ED1027950 -:10142000BE2A0BD190F8DD23EF2A07D100F57872A0 -:1014300010F8013B59409042FAD309B1002070479F -:10144000012070472DE9F05FFFF7E0FF10B90A2097 -:1014500006F0EEFA4FF47872E349E24808F05FFDD7 -:10146000E04C94F8DC03022802D9002084F8DC0365 -:10147000C0B200EB4001C1EB401004EBC00101F52C -:101480009271E822D94808F04AFDD84AD84F002086 -:1014900092F820C092F81F5040F6C41600FB00F3EB -:1014A000193B0CFB03F101F6C4114143694391FB65 -:1014B000F6F127F81010401CC0B20628EED392F8BF -:1014C000211092F822509146B4F8D220B4F8D0807E -:1014D000DFF820A300204FF00A0E4FF47A7BC5F10D -:1014E000640701EB8106A2EB080400BF00EB800259 -:1014F000C1EB42030122002B03DDC1F16402D2B231 -:1015000001E000DA0A4603FB03FC05FB0CFC02FBCE -:1015100002F29CFBF2F23A4402FB03F292FBFEF26F -:1015200002EB460212B204FB02F292FBFBF24244CF -:101530002AF8102000F10100C0B20B28D6D309F11F -:101540007A04E28FA18F608F04F0FEFF608714F8A9 -:101550007A0C01F035FFBDE8F05F04F0FFBA2DE929 -:10156000F047A04D8146332028704FF4787400274F -:101570006C80BE202871EF2085F8DD033E4685F89B -:10158000DE7369B195F8DC03E82200EB4001C1EBA2 -:10159000401005EBC00000F59270944908F0BFFCC4 -:1015A0009048924903E000BF10F8012B5740884251 -:1015B000FAD385F8DE738C4F4FEA040808F070FB0D -:1015C000342008F0DBFB384608F098FB04280FD1E4 -:1015D0000024E019295908F0ADFB042805D008F0D3 -:1015E00065FB761C032EE9DB02E0241D4445F0D3A5 -:1015F00008F05CFB032E02D0FFF708FF10B90A20A9 -:1016000006F016FAFFF71EFFB9F1000F06D0BDE88D -:10161000F047012214210F2001F0C2BABDE8F08783 -:1016200070498A6802438A6070472DE9FC5F72A1A5 -:10163000D1E90001CDE900014FF47871694808F063 -:1016400087FCE821694808F083FC664B33200025BD -:1016500018700320587102209D60FFF7E1FF83F8A6 -:10166000DC534FF41670A3F8EA00FA20A3F8EC005C -:10167000C8332A201884DD851D865D869D76DD763B -:101680001D779D7701205877202083F82C005C4837 -:1016900098626E2083F83A002B2083F83B002120CB -:1016A00083F83C0083F83D5003F8465F40F2DC507D -:1016B000588040F24C409880463B40F26C70A3F852 -:1016C0004C0083F84E5040F27E40188140F23A7050 -:1016D00058814FF47A70988140F27E50D88140F260 -:1016E000EA50188240F2B450588232209882C100E9 -:1016F000D982188383F850504FF4E13159659965C8 -:1017000040F6AC5123F8BC1C384C83F84F504FF0D6 -:10171000280A257084F801A01E21E1721721617545 -:1017200084F802A01E21217317215746A175552167 -:10173000E1702D216173E57520711921A17350228B -:1017400022760B216171E57365764FF0140984F8F8 -:101750000690082323742D23A3760E23E37184F8C7 -:101760001190E2765A2121720A26A6744FF0640B7A -:1017700084F81CB06772A5722575A577E1774121C1 -:1017800084F8201084F8235084F8245084F82550DD -:1017900084F8210084F8225025856585E58404209D -:1017A00084F82C0084F82D7084F82E70152084F8AD -:1017B0002F0014482063144860631448A06301207C -:1017C00084F83C0012A0FFF70BFE84F8665084F802 -:1017D000675084F86870012084F869001EE00000FA -:1017E000D8C000087004002000FC01085008002048 -:1017F0000C0B0020180B00201E1E646464646464DB -:10180000031414009A99193F52B87E3F3333733F43 -:1018100041455452313233340000000084F86A509C -:1018200004F8AC6FC82767704FF49660608040F290 -:10183000D930A08048480024EC4640F2DC514FF4F7 -:101840007F724FF4FA6300BF00EBC40525F86C2FDC -:101850006B80A9801CF80480641C85F80680082C25 -:10186000F2DB012400F8B24FFF25447041808280F2 -:10187000C380028141818381C281018243820475D8 -:1018800045758475C4750676467684768283C383EF -:10189000018442848384C184078580F82A901E21B4 -:1018A00080F82B1080F82C40A0F82EB04FF49671E1 -:1018B0000186A0F832A00020284D014605EB001259 -:1018C000401C11610C28F9DB5FF0000404EB4400BC -:1018D000C0EB441005EBC00000F59270E8221E49F1 -:1018E00008F01DFB641C032CF0DBBDE8FC9F10B569 -:1018F0000446FFF78BFD641E204206D1FFF795FEDC -:101900000021BDE81040084629E610BD14490968C9 -:10191000014201D0012070470020704710490A6839 -:1019200002430A6070470E490A6882430A607047A2 -:101930000B480068704709498968014201D00120BD -:1019400070470020704705498A6882438A60704763 -:101950000248806870470000500800207004002092 -:101960000400002070B5FE4809F06CFB0446FD48F9 -:10197000008808F0C4FD0546214608F0ADFB08F0DC -:10198000E1FDF94C29462080F84808F0DBFBF849D6 -:1019900008F0D8FBA0650820FFF7B8FF002803D0A7 -:1019A000BDE8704002F098BC70BD002801DD024621 -:1019B00000E042428A4201DA00207047002802DD3E -:1019C000A0EB01007047FDDA084470472DE9F04FA5 -:1019D00091B0D0E90045814686688846086809F0DC -:1019E00031FB0490D8F8000009F086FD0590D8F886 -:1019F000040009F027FB0190D8F8040009F07CFDF1 -:101A00000746D8F8080009F01DFB8246D8F8080000 -:101A100009F072FD83465046049908F05DFB07907B -:101A20005046019908F058FB80465846049908F042 -:101A300053FB06905146059808F04EFB0890594616 -:101A4000059808F049FB03900198594680F0004042 -:101A500008F042FB82463946089808F03DFB06999B -:101A600008F0E2FA10903946039808F035FB079920 -:101A700008F02FFB0E900598019980F0004008F0C7 -:101A80002BFB05903946079808F026FB039908F0D0 -:101A900020FB02903946069808F01EFB089908F0D2 -:101AA000C3FA83460499019808F016FB0490304667 -:101AB000029908F011FB01902846109908F00CFBE0 -:101AC00000904146204608F007FB009908F0ACFA68 -:101AD000019908F0A9FAC9F800005946304608F003 -:101AE000FBFA834628460E9908F0F6FA80465146DE -:101AF000204608F0F1FA414608F096FA594608F0F7 -:101B000093FAC9F804003046049908F0E5FA06464D -:101B10002846059908F0E0FA05463946204608F0BF -:101B2000DBFA294608F080FA314608F07DFAC9F858 -:101B3000080011B0BDE8F08F70B506468A4886B03F -:101B40008030016881F000410391406880F00040DE -:101B500004908848B0F9000008F0C8FC864908F0F5 -:101B6000BBFA864908F0B8FA7F4C05907434B4F992 -:101B7000000008F0BBFC0090B4F9020008F0B6FCCD -:101B80000190B4F9040008F0B1FC029003A9684682 -:101B9000FFF71CFF7A4D743C95F83C00012804D0F7 -:101BA0007048008808F0ABFC17E0764840780028C1 -:101BB000606B0CD1C11700EB9161A0EBA11008F094 -:101BC00095FC029908F030FA08F0BCFC6063C1177C -:101BD00000EB9160801108F089FC029908F079FA15 -:101BE000029008F0AFFC15F82D1FFFF7DEFE08F09D -:101BF0007DFC0290009808F0A5FC6978FFF7D5FEFF -:101C000008F074FC0090019808F09CFC6978FFF7DC -:101C1000CCFE08F06BFC0190E0683044E060206985 -:101C2000401C2061584C206808F060FC009908F0C6 -:101C3000FBF908F087FC2060606808F057FC019908 -:101C400008F0F2F908F07EFC6060A06808F04EFC35 -:101C5000029908F0E9F908F075FCA06006B070BDC3 -:101C60002DE9F05F404D04468035286809F0EAF917 -:101C70008346286809F040FC8246686809F0E2F96A -:101C80008146686809F038FC0546D4F80880294682 -:101C9000404608F021FA594608F01EFA67680646E1 -:101CA0005146384608F018FA294608F015FA054654 -:101CB0004946206808F010FA294608F0B5F931467F -:101CC00008F0B2F904465146404608F005FA0546C8 -:101CD0005946384608F000FA294608F0F7F9214637 -:101CE00009F086F8294908F0F7F9294908F02AFA95 -:101CF0001D49C96A08F098F9264908F023FA09F045 -:101D0000E3FB00B2002802DA00F5B47000B2BDE8CF -:101D1000F09F2DE9F04F87B0002605F0B5FDDFF804 -:101D200048B005465C46DBF83800281A039008F0F6 -:101D3000E6FB1949C96808F0CFF905901048A5637A -:101D40000BF16E0A90F82C7000240AF106054FF092 -:101D50007E580548683030F9140008F0C7FB1DE0D4 -:101D6000F366DF3E8A010020080000200AE81C41DB -:101D700000401C46B801002089C3E43A000020C19D -:101D800050080020FC0A0020500900200000E14417 -:101D9000DB0F494000002041B40C0020059908F0F9 -:101DA0009BF94DF8240017B3384608F0A8FB01460C -:101DB000404608F0C7F9814604903AF9140008F04B -:101DC00095FB494608F088F981464146049808F099 -:101DD00080F9FE4951F8241008F07EF9494608F0D0 -:101DE00023F9FA4941F8240008F0ACFB01E03AF885 -:101DF000140025F8140035F91400641C00FB00667B -:101E0000032CA6D364204643F1486946008840432A -:101E100096FBF0F4ED481830FFF7D8FD0820FFF7E7 -:101E200075FD694610B1E9480C3800E0E948FFF754 -:101E3000CDFDA0B2DFF894934938DFF89CA309F1F7 -:101E400018093C2826D20024BAF8EA0008F057FB0B -:101E500045464146049008F0E7F80146284608F058 -:101E600071F905464E46DB48143830F9140008F085 -:101E70003DFB074656F82410049808F02DF9394622 -:101E800008F0D2F8294608F027F946F82400641C27 -:101E9000032CE8D30820FFF739FD50B34546CB4E5D -:101EA000DFF8308300240C3EA8F10E08BAF8EC00ED -:101EB00008F025FB8246294608F0B6F80146284678 -:101EC00008F040F94FEA000538F9140008F00EFB5D -:101ED0000746504656F8241008F0FEF8394608F038 -:101EE000A3F8294608F0F8F846F82400641C032CEF -:101EF000EAD35E46BBF9000008F0F8FA0146D9F8CB -:101F00000800B64D4C46B0F5000F01DA80F00040F5 -:101F100008F06CFB01D2012000E000206873D4E9D6 -:101F2000010108F065FFAB4D083D2860A06801463F -:101F300008F0D2F807466068014608F0CDF8394647 -:101F400008F072F809F09EFB0146206880F000401E -:101F500008F04EFFDFF8888268604146286808F084 -:101F6000BBF809F0B1FAA5F150074146388068681E -:101F700008F0B2F809F0A8FA78800820FFF7C6FC4C -:101F8000984D10B191480C3800E09248FFF768FE78 -:101F900028800398FFF7D0FD934D95F86A0000283C -:101FA0001BD08B48008808F0AAFA0146A06808F008 -:101FB000C9F88E4908F090F808F0C4FAC0F164003E -:101FC0006422002104F0C0FA95F86A104843C11752 -:101FD00000EB517040F3CF00708007B0AAE52DE907 -:101FE000F04102F070F90220FFF790FC20B102F0FE -:101FF0006FF8FFF78EFE05E0764900201A39088059 -:10200000488088804020FFF796FC7249724B2C393B -:1020100010B3A1F15602107830B9D3F8F000030CD8 -:102020001370030A537090706A4B0020B3F12603BB -:10203000145C31F9105033F91060671E06FB075528 -:102040006D1C95FBF4F421F8104023F81040401C5F -:102050000328EDD3BDE8F081587901280AD05D4A04 -:102060000020203A32F8103021F81030401C0328AC -:10207000F8D3EFE7574AB1F90400883AB2F90430CF -:1020800000EB4300032390FBF3F088809080E1E7AE -:102090004E4900200C310860486088604D498839FD -:1020A0000861C86070472DE9F84F05F0EDFB494C19 -:1020B000883C216C461A46F2A8118E4202D20020BA -:1020C000BDE8F88F4A492064474D088858B195F813 -:1020D0002F20A369521EB3FBF2F2401EE263088078 -:1020E00000206064A06495F82F00401E08F0FEF9FF -:1020F0000746E06B08F0FAF9394607F0EDFF0746AE -:10210000A06908F0FCF9394608F01CF809F012F94A -:10211000384907F0E1FF09F055F84FF07E5107F01C -:10212000D8FF0746606946F6B321084408F0DEF997 -:10213000314907F0D1FF394607F0CEFF08F002FA27 -:10214000D5F83080074641464FF07E5007F0BEFF7D -:102150008146384608F0CAF9494607F0BDFF0746F0 -:10216000E06908F0C3F9414607F0B6FF394607F0C9 -:102170005BFF08F0E7F98346E061E068804608F01D -:10218000D4F91E4A1E4B08F0D0F808F008FA0746AA -:10219000206908F0ABF98146404608F0B0F9804666 -:1021A0000A480C30806808F0A1F9A16D07F094FF8F -:1021B000414607F091FF494607F0C4FF8046606C36 -:1021C0003946009007F088FF81461BE04409002053 -:1021D0008A0100209000002070040020FC0A0020EA -:1021E0004C3D0F44B8010020500800200000C842B8 -:1021F000B601002041D3423EA1D819438DEDB5A0D0 -:10220000F7C6B03E4FF0FF31404607F0DBFF3946DE -:1022100007F062FF494607F007FFA16C07F004FFD3 -:10222000D5F83890824649464FF07E5007F04EFF71 -:102230000746584608F05AF9394607F04DFF074659 -:102240004946504607F048FF394607F0EDFEA064C6 -:1022500008F078F920654146009807F0E5FE6064D3 -:10226000FFF716FFD4E914104FF49678401AC8F11E -:1022700000094246494604F067F90A21FFF795FB39 -:1022800007462879C8227843C11700EB5160C01176 -:10229000514204F059F92062A87B4CF25032784345 -:1022A000C11700EB9160616A01EBA01051426062BE -:1022B00004F04AF9C117606200EBD150216A01EBCA -:1022C00060202062304608F01AF90646E769E06CA3 -:1022D000381A08F00BF9234907F0FEFE314607F0E3 -:1022E00031FF08F02FF942464946E76404F02CF923 -:1022F0000A21FFF75AFB6F6B804639464FF07E503C -:1023000007F0E4FE0646404608F0F0F8314607F0D4 -:10231000E3FE06463946606C07F0DEFE314607F004 -:1023200083FE606408F00EF94FF47A72514204F0B3 -:102330000BF908F0DBF8606408F004F90521FFF7F9 -:1023400034FBA062297E96224143C81701EB10702E -:1023500000116FF0950104F0F7F8216A081A206265 -:102360000120ADE60024744970B57A4D0446286812 -:1023700006F042FD0028FAD0E1B2286806F02EFDF2 -:10238000204670BD86B005F0C7FA0020FFF7AFFA0F -:10239000FFF758F8704C002594F8050118B1012892 -:1023A0001DD009281BD08DF8105084F8055104A8C1 -:1023B00004F06CF90E20FFF7B1FA00F0E9F860794B -:1023C00001260E280ED008280CD08DF8055000BF2D -:1023D0004FF480773846FFF7AEFA50B905E08DF834 -:1023E0001000E4E78DF80560F2E70820FFF7A3FA94 -:1023F00000B101208DF802000120FFF79CFA8DF852 -:1024000001000820FFF797FA80F001008DF8000026 -:102410005048007C8DF803005048017FC1F3C00193 -:102420008DF80410B4F8DE10ADF80810B4F8E01020 -:10243000ADF80A100088ADF80C0094F805010128E9 -:1024400015D0092816D08DF80650684605F020F9F9 -:102450004449434808600820FFF76DFAB0B194F88A -:102460000E0158B1012809D0022817D10AE08DF8D1 -:102470000660EAE707208DF80600E6E7394803F032 -:1024800087FD0BE0374804F09AF807E03846FFF77D -:1024900052FA18B1D4F81C0103F0A9FB0120FFF790 -:1024A0004AFA30B14FF48060FFF745FA08B101F005 -:1024B00097FF2D494FF01009C1F80090A1F10408D1 -:1024C0004FF0080AC8F800A00025A8F104073868F2 -:1024D00080F010003860386880F0080038601920FB -:1024E00005F0FAF9012005F002FA192005F0F4F9D7 -:1024F000002005F0FCF96D1CEDB20A2DE7D3C8F8F9 -:1025000000A0C8F8009001F025FCFFF72BFA02208C -:10251000FFF711FA08B101F0E9FCD4F8200102F04C -:1025200096F805F0B1F9114908606079052803D1E2 -:102530000F494FF4C87008800E494FF47A70088034 -:102540000D49C82008800D4880F80D6000F040FF5C -:10255000FCE700006809002070040020000900204A -:10256000812F0008FC000020140C0140F80000201E -:102570008601002088010020B6010020FC0A00200E -:102580000248B0F9D40000F0F9FAFEE77004002028 -:102590002DE9F041FE4EFF4F707907EBC000407807 -:1025A00000B10120FC4C20742020FFF7C4F908B1D1 -:1025B000012020747079F94CF94D122808D017F8D1 -:1025C000301007EBC0002170426842B3002024E0C5 -:1025D0005FF0000006EB00110A6912F0FF4F1ED0F9 -:1025E000D1E9057C05EB0013C969401CC3E902C1B0 -:1025F000C3E900272178491C21700C28EADB0EE092 -:1026000002EB001305EB0016D3E9007CD3E902834B -:10261000C6E90283C6E9007C401C8842F0DB4FF427 -:102620008040FFF788F900281AD02778012F17D9A2 -:10263000002613E005EB06144FF0FF384146A06872 -:1026400007F0C0FDA0604146606807F0BBFD606018 -:102650004146E06807F0B6FD761CE060BE42E9DB6B -:10266000BDE8F081F0B5401C0021C94A0B4600BF0F -:1026700002EB0114491C23610C29F9DBC54B03EB68 -:10268000C0014C68002C11D0002113F830000BE081 -:1026900004EB011302EB011593E8C010DB68491C41 -:1026A000C5E906C3C5E904678842F1DCF0BDBA4854 -:1026B00010B5007C002833D0B548B84C4079A41C34 -:1026C00005280ED004DC01281BD0042804D112E018 -:1026D000082806D00E2823D02020FFF72CF9002848 -:1026E0001ED02188002005F057F861880120BDE840 -:1026F000104005F051B82189002005F04DF861899E -:10270000F4E7A649A748891C90F8B300498908B1A5 -:102710000020ECE7A44840780028F9D10021F7E731 -:1027200010BD70B59E4E0024183E9C4D07E000BFC2 -:1027300036F81410204605F024F8641CE4B228781A -:102740008442F5D370BD2DE9FC5F944CDFF85C92B8 -:10275000974F2078032814D9B9F904004142002882 -:1027600001DD024600E00A4602F1640200DC084690 -:102770006FF06301A1EB0001B7F9040003F0E4FE80 -:10278000B8808648DFF818B2864C0078ABF1180B99 -:10279000012839D90025804634E000BF94F9B20001 -:1027A000B7F904104042484307F0A0FE7C4901EB12 -:1027B0000516F16807F090FC8246B7F9000007F0B3 -:1027C00095FE716807F088FC0190B7F9020007F0E8 -:1027D0008DFEB16807F080FC0090B9F9060007F0A3 -:1027E00085FE316807F078FC009907F01DFC01991F -:1027F00007F01AFC514607F017FC07F0A3FE2BF870 -:1028000015006D1C4545C9D3614E644DDFF8A4A188 -:102810007079AD1CDFF8A081052838D004DC0128D0 -:1028200026D0042832D102E008282FD155E0B7F98C -:10283000020094F9B210B7F904204FF4FA6901FBD1 -:10284000120000F2DC504A464FF47F7103F07CFE28 -:102850002881B7F9020094F9B210B7F9042001FBFE -:102860000200A0F2DC5040424A464FF47F710AE079 -:10287000B234B7F90420608894F9001001FB12000B -:10288000E288A188B23C03F05FFE68816EE014F933 -:10289000CA0FBAF90210B9F90220484321894F46FC -:1028A0001144C21700EB127001EB2010E288A188DE -:1028B00003F04AFE288094F90100BAF90010B7F934 -:1028C00000204843E1891144C21700EB127001EB6C -:1028D0002010A2896189CA3C45E03348B9F8061046 -:1028E000ABF80010807AC0B1B6F81021B8F9021028 -:1028F000B8F9000014F9C63F891A801A94F9022029 -:102900004B4302FB00322A8094F90120514394F991 -:102910000320C63C02FB001013E014F9C62FB7F9E0 -:10292000020094F90230B7F90010424303FB012280 -:102930002A8094F90120424394F90300C63C00FB2D -:1029400001206880BA34B5F900006188A288084483 -:10295000218803F0F9FD2880B5F9020021896289F8 -:102960000844E188BA3C03F0EFFD68802020FEF7C0 -:10297000E2FFE8B394F8CC300020990707D0B8F80C -:102980000C10B6F81021A1EB020161F30F0015E065 -:1029900070040020D4C4000868090020AC000020A6 -:1029A0009409002050080020FC0A00203C0100206F -:1029B0002E010020380000205C010020590707D4B8 -:1029C000B8F80E10B6F81021A1EB020161F31F4018 -:1029D000B4F8D210014409B22980B4F8D82002EB2F -:1029E000104002B262486A80007A88B3D80600E0DC -:1029F0003EE094F9CA0017D5BAF902304042584374 -:102A000094F9CB30BAF900707B43C71700EB17700D -:102A1000DF17001103EB1773A0EB2317C91B00EBA3 -:102A200023102980104412E0BAF902707843C717C6 -:102A300000EB177001EB2010288094F9CB00BAF955 -:102A400000104843C11700EB117002EB20106880A2 -:102A5000CE34B5F900006288218803F075FD288026 -:102A60002289E188CE3CB5F9020003F06DFD688053 -:102A700094F8CC00000711D500252020FEF75BFF5D -:102A800000B102250024474607EB44000189601984 -:102A9000C0B204F081FE641C042CF5D335495C46B9 -:102AA000BBF9007001200B7806E000BF34F910205C -:102AB000BA4200DD1746401C9842F7D300254FF478 -:102AC000804A89464DE000BFB6F8D200B84205DA28 -:102AD00034F81510381A081A24F815005046FEF775 -:102AE0002AFF98B1B8F9060040F2DC51884204DDB3 -:102AF000B6F8D220B6F8D81003E0B6F8D620B6F86B -:102B0000D41034F9150003F01FFD15E0B6F8D220FB -:102B1000B6F8D01034F9150003F016FD24F81500AE -:102B2000B8F90600B6F81211884207DA1020FEF74D -:102B300002FF38B1B6F8D40024F815000E484078EA -:102B400018B10DE0B6F8D000F6E75046FEF7F3FEF8 -:102B500010B1B6F8DA0001E0B6F8D40024F8150098 -:102B60006D1C99F800008542AED3BDE8FC9F0000C3 -:102B70002E0B0020AC000020FC0A0020064A002199 -:102B8000064B127804E000BF23F81100491CC9B2BB -:102B90009142F9D3FFF7C5BDAC0000207C090020AD -:102BA0002DE9F0471746894606460025DFF83C84A4 -:102BB0001AE0002411E000BFD8F8001081F00801ED -:102BC000C8F80010012004F092FE484604F084FE8C -:102BD000002004F08CFE641CE4B2B442ECD33C2030 -:102BE00004F07AFE6D1CEDB2BD42E2D3BDE8F08781 -:102BF0002DE9FC5FFE4C002540F2DC51B4F90600E3 -:102C0000FC4E4FF4FA73884201DA64210CE0F94972 -:102C1000B0F5FA6F91F8251004DAA0F2DC525143B6 -:102C200091FBF3F1C1F164018946F34996F866E03E -:102C300096F867B0B1F810410022B246EC49EE4B6D -:102C400040F2E63C31F91260311B01F2F31767459F -:102C500003D8002903DCA11B01E04FF4FA71022A1A -:102C600034D0BEF1000F05D08E4502DAA1EB0E0183 -:102C700000E00021642391FBF3F3E04F6FF01808AC -:102C800007EB430C37F91370BCF902C003FB08F3E0 -:102C9000ACEB070C01EB83030CFB03FC64239CFBF4 -:102CA000F3F33B44D24F203F27F812309AF82330F9 -:102CB0004B434FF4FA7193FBF1F1C1F1640189B216 -:102CC00001FB09F1642391FBF3F11EE0BBF1000F5E -:102CD00005D08B4502DAA1EB0B0100E0002193F94E -:102CE000E530DFF80CC35B42ACF1200C4B43ACF891 -:102CF00004309AF82430002900DC49424B434FF459 -:102D0000FA7193FBF1F1C1F164010AEB020764234C -:102D100097F801C0DFF8D8820CFB01FC9CFBF3FCA8 -:102D2000A8F1740808F802C097F80BC008F103086E -:102D30000CFB01FC9CFBF3FC08F802C07F7D4F43B9 -:102D400097FBF3F308F10301A6428B5405DA4E31E9 -:102D500031F812305B4221F81230521C032AFFF680 -:102D60006DAFDFF894A24FF4FA625446BAF812112C -:102D700003F0EAFBB4F812114FF47A72401A504390 -:102D8000C1F5FA61B0FBF1F1642291FBF2F09B4BCB -:102D90006FF018060C3303EB400433F91030704326 -:102DA000B4F9024001EB8000E41A444394FBF2F0D2 -:102DB000DFF83C82914EA8F120081844103EA8F894 -:102DC0000600707AA8F17C04E8B38D48B4F91E10AF -:102DD000B0F90000401A07F089FB8A4907F07CF936 -:102DE000894907F0AFF9074608F02CF901903846F9 -:102DF00008F082FB00904746B8F9000007F076FB28 -:102E00008346009907F068F98046B7F9020007F099 -:102E10006DFB8146019907F05FF9414607F004F91F -:102E200007F090FB80464846009907F055F9814627 -:102E30005846019907F050F9494607F047F907F05D -:102E400081FB388000E001E0A7F802800220FEF755 -:102E500072FD002750B3E078401CC0B20621B0FBE1 -:102E6000F1F2E07001FB1200B8B9002003F080FC21 -:102E70002179624A01F00703AC3A491C22F8130099 -:102E80002171002032F81010401C29448DB208280E -:102E9000F8DBE80801F012F8A072A07AE18C884211 -:102EA00003D89AF80411814201D9A77001E00420E7 -:102EB000A070A07803F00FF954484C4D008818B169 -:102EC0000220FEF723FD10B95148008820B1286880 -:102ED00080F00800286014E0B178082011B143495F -:102EE000091D0860717811B14049083108604FF43C -:102EF0000060FEF720FD20B1707800B1012003F0E2 -:102F0000F5F98020FEF717FD48B1E16C606B411ABE -:102F100005D44CF250310844E06405F03DF8A16C52 -:102F2000606B411A03D4717BF9B10120B07001F0DC -:102F3000A6FF2020FEF7EAFC68B1216D606B411A04 -:102F400009D4E17A052906D3324908442065286866 -:102F500080F0100028603048816800290ED002B04F -:102F60002348BDE8F05F7C380847B770296881F0D6 -:102F70000801296029490844A064D8E7BDE8FC9FFE -:102F800010B51D4C204490F8060104F00FFCA0F28F -:102F9000EE2140F2DD52914201D3B4F8100110BD90 -:102FA0002DE9F047124EDFF854809C3EA8F19C08B2 -:102FB00070790F4F401C00247071A14608F1400544 -:102FC000F16B20468847727908EBC40102F00302D6 -:102FD00021F8120025F814905FF0000035F8143045 -:102FE00031F810201A4425F8142019E00C0C014087 -:102FF0005C01002050080020700400200C0B002011 -:10300000B8010020DB0F4940000034438601002056 -:1030100088010020F0490200B40C002020A1070024 -:10302000401CC0B20428D9D335F91400801CC11744 +:1005300000000000000080BF0000204120BCBE4C35 +:100540002E0000006F12033A00007A44E0070020FA +:100550006175782025752025750D0A00496E766134 +:100560006C6964204665617475726520696E6465A6 +:10057000783A206D757374206265203C2025750DD6 +:100580000A000000640400207265736574000000B6 +:100590006C6F61640000000057726F6E67206E75AB +:1005A0006D626572206F6620617267756D656E742D +:1005B000732C206E6565647320696478207468729A +:1005C00020726F6C6C207069746368207961770D9C +:1005D0000A000000437573746F6D206D6978657251 +:1005E0003A200D0A4D6F746F720954687209526F88 +:1005F0006C6C095069746368095961770D0A0000D1 +:100600002325643A090000002573090025730D0AAB +:100610000000000053616E69747920636865636B44 +:100620003A0900000AD7233C4E470900FDA000F01C +:1006300077FE641C032CFFF65FAFAFF24000FDE6CF +:100640000020414604EB0012401C11610C28F9DB2C +:10065000F6E6202138460AF002F80028F8D0401CBF +:1006600006460AF006F8F04DC7B2002455F82410EB +:1006700031B13A4630460AF003F818B1641CF5E788 +:10068000EAA0DBE6204601F0EFFF55F82410EDA0CC +:100690000AF0E2FAAFF26810FFF775FED0E60C211F +:1006A000EDA00AF0D9FACBE610B5F5A000F038FEBF +:1006B000012001F0DAF8F9A000F032FE0A2007F07C +:1006C00017FBBDE81040002007F0DDBB7CB50446F9 +:1006D0000D4600790021062814D2DFE800F0030659 +:1006E0000A0D111EA06801780CE0A06890F90010B6 +:1006F00008E0A068018805E0A068B0F9001001E0FA +:10070000A0680168E9A00AF0A7FA002D04D0D4E996 +:100710000312E7A00AF0A0FA7CBDA0686946006851 +:10072000FFF79CFD0146E4A00AF096FA002DF3D0F5 +:10073000E0680AF0A5F86946FFF790FD0146DFA0E2 +:100740000AF08AFA20690AF09BF86946FFF786FDED +:100750000146DAA00AF080FA7CBD2DE9FF47D8A057 +:100760000AF07AFAD0A0FFF7E4FDE14DAE496879CE +:1007700001EB800050F8041CDEA00AF06DFA286935 +:1007800010F0FF4F4CD0DFF878A3002405EB0410E5 +:10079000066916F0FF4F3FD0D0E90598C769611C84 +:1007A000D8A00AF059FA564502D3D8A00AF054FA54 +:1007B00069463046FFF752FD0146BFA00AF04CFAE9 +:1007C0005646B14502D3D1A00AF046FA69464846DA +:1007D000FFF744FD0146B8A00AF03EFAB04502D347 +:1007E000CAA00AF039FA69464046FFF737FD0146CC +:1007F000B1A00AF031FAB74202D3C4A00AF02CFA31 +:1008000069463846FFF72AFD0146AFF200200AF09C +:1008100023FA641C0C2CB9DB611CBDA00AF01CFA85 +:1008200001F054F8804E002407464C3656F8241048 +:1008300021B1BCA00AF010FA641CF7E700244FF0C5 +:10084000010800BF56F8241041B108FA04F03842FC +:1008500002D0B8A00AF000FA641CF3E7B94A0020FD +:1008600069462C18135C94F80A41401C08280B5563 +:10087000F7DB00220A54B4A00AF0EEF9B54D0024CB +:1008800004EB840005EB800655F82010B2A00AF0B6 +:10089000E3F900213046FFF719FF6EA000F040FD9C +:1008A000641C612CECD3BDE8FF8710B5ADA000F04F +:1008B00037FD0121002000F022FEADA000F030FD48 +:1008C0000A2007F015FABDE81040002007F0DBBA57 +:1008D00010B50446AAA000F023FDAF480021017026 +:1008E000AE480160AE4801702046BDE81040DCE72C +:1008F0002DE9F047064609F0BCFE054600F0E6FF8C +:10090000DFF8248107464FF0010908F14C0855B182 +:100910002A46A4A1304609F0B3FEC8B130780027BA +:100920002D2824D026E0A1A000F0FAFC00244D469A +:100930004FEA080656F8241041B105FA04F038428F +:1009400002D09FA00AF088F9641CF3E741A01EE0E2 +:100950009CA000F0E5FC00244FEA080555F824109F +:100960000029F3D096A00AF077F9641CF6E7012776 +:10097000761C6D1E5FF0000458F8241031B12A4631 +:10098000304609F07DFE30B1641CF5E793A0BDE868 +:10099000F04700F0C5BC09FA04F01FB100F091FF68 +:1009A00095A002E000F00CFE96A000F0B9FC58F80B +:1009B0002410BDE8F04761A00AF04EB970B50024DC +:1009C00093A000F0ADFC634DB5F1A80504EB440025 +:1009D00005EB80014A6855F8201093A00AF03CF915 +:1009E000641C0E2CF2D370BD3EB5054609F041FEE5 +:1009F000082815D10024285D09F0BAFD2855641C8B +:100A0000082CF8D300244F48295D09F028FE28B1AE +:100A10002819295D401C09F022FE00B108E10BE114 +:100A200011E100004F4B0900B0B80008496E766133 +:100A30006C6964206D6978657220747970652E2EFA +:100A40002E0D0A004C6F61646564202573206D696A +:100A5000782E2E2E0D0A00004D6F746F72206E7569 +:100A60006D626572206D75737420626520626574B5 +:100A70007765656E203120616E642025640D0A0063 +:100A8000526573657474696E6720746F206465665F +:100A900061756C74732E2E2E0D0A00005265626F04 +:100AA0006F74696E672E2E2E000000002564000012 +:100AB0002025642025640000257300002025730094 +:100AC00043757272656E7420436F6E6669673A2073 +:100AD000436F70792065766572797468696E6720F6 +:100AE00062656C6F7720686572652E2E2E0D0A0088 +:100AF000640400206D697865722025730D0A00007A +:100B000000008080636D697820256400200000006B +:100B1000636D697820256420302030203020300D2E +:100B20000A00000066656174757265202D25730DDD +:100B30000A000000666561747572652025730D0AF0 +:100B400000000000B4C100086D61702025730D0A1B +:100B50000000000020BA0008736574202573203D52 +:100B600020000000536176696E672E2E2E00000073 +:100B70000D0A5265626F6F74696E672E2E2E00002B +:100B80000D0A4C656176696E6720434C49206D6F94 +:100B900064652E2E2E0D0A00340400200000002073 +:100BA000AD0100206C69737400000000456E616245 +:100BB0006C65642066656174757265733A20000027 +:100BC00025732000417661696C61626C6520666501 +:100BD0006174757265733A2000000000496E766199 +:100BE0006C69642066656174757265206E616D65FF +:100BF0002E2E2E0D0A00000044697361626C65643C +:100C000020000000456E61626C65642000000000F9 +:100C1000417661696C61626C6520636F6D6D616EB8 +:100C200064733A0D0A00000025730925730D0A004C +:100C3000F7A000F075FB3EBD641C082CFFF4E3AE8A +:100C4000284600F0A7FBFAA000F06AFBFE4BFF4A23 +:100C50000020694615181C5C95F80A51401C0828AC +:100C60004C55F7D300220A54AFF2301009F0F4FFCC +:100C70003EBD2DE9F041804609F0FBFCF34FF44DF9 +:100C8000060011D00246AFF2E401404609F0F8FC3C +:100C900088B1002455F82410F1B13246404609F0DD +:100CA000EFFCF8B1641CF5E7787905EB800050F8AB +:100CB000041CE8A01BE0ECA000F032FB5FF0000495 +:100CC00055F8241029B1AFF2081009F0C5FF641CD3 +:100CD000F6E7AFF2802001E0AFF2B020BDE8F041CE +:100CE00000F01EBB601C787155F82410E3A0BDE82D +:100CF000F04109F0B1BF70B5054609F0BAFCD34C1C +:100D000010F0FF0F0CD0284609F0D3FC02280ED8B3 +:100D100084F878030021084600F0F1FBC9A0EBE756 +:100D200094F87813BDE87040D9A009F095BF70BD64 +:100D30002DE9F047814609F09CFCDB4D060029D0E7 +:100D4000012E03D199F800002A2823D0D7A14846C4 +:100D500009F067FC00286ED0401C044609F0A9FC8D +:100D600082462046FFF7F2F98046002606EB86070A +:100D700005EB870455F8270009F07BFC024655F87F +:100D80002710484609F07CFCF8B1761C612EEDD3A3 +:100D9000C7A04CE0CEA000F0C3FA002404EB84000E +:100DA00005EB800755F82010AFF2502009F054FFF2 +:100DB00031463846FFF78AFCAFF2683000F0B0FAEF +:100DC000641C612CEAD3BDE8F08706EB860605EBD0 +:100DD0008607F86809F054FD414609F08DFD25D8D5 +:100DE000386909F04DFD414609F090FD1ED839796A +:100DF000052907D0504606290ED2DFE801F0050587 +:100E000008080B0B4046F6E7A168087004E0A168EB +:100E1000088001E0A168086055F82610B2A009F02A +:100E20001BFF2046BDE8F04700214FE4B1A0BDE81C +:100E3000F04700F075BA002404EB8406494655F8E3 +:100E4000260009F0EEFB78B155F8261005EB860771 +:100E5000AFF2F82009F000FF00213846FFF736FC1A +:100E6000AFF2104009F0F8FE641C612CE4D3AAE74D +:100E70002DE9F04106F02DFF4FF47A71B0FBF1F14E +:100E8000A6480378A6480278A6A009F0E5FE00F07F +:100E90000DFD0646B348B4490068B0FBF1F1B3A0BC +:100EA00009F0DAFE6A4F00240125903757F8241024 +:100EB00051B105FA04F0304203D0AFF2FC2009F042 +:100EC000CBFE641CE4B2F1E7022000F0DDFCA0B12F +:100ED000AE4C5F482178AC3050F82110ACA009F03E +:100EE000BBFE2078022808D1AC48007C08B16F21F5 +:100EF00000E06E21AAA009F0AFFEAFF2A84000F01A +:100F00000FFA06F0FAFB0246A6484FF45F73018819 +:100F1000BDE8F041A4A009F09FBEB0A000F000BA67 +:100F20002DE9FF5FDFF8E49299F8000038B901215C +:100F300089F80010B6A000F0F3F900F0FDF9DFF831 +:100F400008B3DFF858A25446DAF8000008F0A6FA11 +:100F500000285AD0206808F0A4FA092807D03F28B2 +:100F600005D0DBF800105C4600294FD076E1002464 +:100F70004D4F2546A83FDFF83081DBF800600BE0DD +:100F8000DBF8002022B1B148396809F079FB10B9CB +:100F900004B93C463D460C374745F1D394B1AB4FBD +:100FA0005946226808682B68125C1B5C9A4209D17A +:100FB00092B92E2810D220223A54401C0021CBF89E +:100FC00000003954DBF800005F4608B1AC4213D092 +:100FD0009FA000F0A5F90AE03A54401C0860E0E741 +:100FE000206800F09DF9092000F0A8F90C34AC420B +:100FF000F6D900F0A1F90026944C38688642A2D2B6 +:10100000A05D00F09BF9761CF7E787E124E1000082 +:101010004D75737420626520616E79206F7264650E +:1010200072206F662041455452313233340D0A002C +:1010300043757272656E742061737369676E6D6556 +:101040006E743A2000000000B4C10008640400205F +:10105000B0B8000843757272656E74206D6978656A +:10106000723A2025730D0A00417661696C61626CE9 +:1010700065206D69786572733A2000004D69786566 +:10108000722073657420746F2025730D0A000000B0 +:1010900043757272656E742070726F66696C653A22 +:1010A0002025640D0A00000020BA00083D00000061 +:1010B0004552523A20556E6B6E6F776E2076617294 +:1010C0006961626C65206E616D650D0A000000004B +:1010D00043757272656E742073657474696E67739C +:1010E0003A200D0A000000002573207365742074F7 +:1010F0006F2000004552523A2056616C75652061A0 +:10110000737369676E6D656E74206F7574206F669A +:101110002072616E67650D0A00000000600100200A +:10112000CA00002053797374656D20557074696D21 +:10113000653A202564207365636F6E64732C2056B6 +:101140006F6C746167653A202564202A20302E3147 +:101150005620282564532062617474657279290DC4 +:101160000A0000000004002040420F0043505520B8 +:1011700025644D487A2C2064657465637465642029 +:1011800073656E736F72733A200000007401002063 +:1011900041434348573A202573000000D4080020FB +:1011A0002E256300CC0000204379636C65205469D0 +:1011B0006D653A2025642C20493243204572726FB8 +:1011C00072733A2025642C20636F6E666967207302 +:1011D000697A653A2025640D0A0000004166726F45 +:1011E000333220434C492076657273696F6E20322A +:1011F0002E32204F63742032382032303133202F8A +:101200002030393A35333A3438000000AD0100203F +:101210000D0A456E746572696E6720434C49204D16 +:101220006F64652C20747970652027657869742750 +:1012300020746F2072657475726E2C206F72202777 +:1012400068656C70270D0A0000000020340400203F +:101250000D1B5B4B00000000042813D00C2817D096 +:1012600019B10A2818D00D2816D07F2840D030296F +:10127000BFF469AE2028FFF466AE7E283FF663AE69 +:10128000A9B343E004B03048BDE8F05FFFF720BBEE +:101290002EA000F045F827E0AFF6480000F040F837 +:1012A000294E206800250C2335542B48CDE9000633 +:1012B0000E222A49029501A809F060F9070007D01B +:1012C000386809F0D6F93044B968401C884702E014 +:1012D00023A000F025F830211B4809F08BF9256088 +:1012E00099F80000002819D000F026F82BE60BE052 +:1012F0000029FBD0144A491E0020CBF8001050549E +:1013000020A000F00DF81EE62028EFD00E4A505421 +:10131000491CCBF8001000F011F814E6BDE8FF9F5F +:1013200070B50446184D03E0641C286806F07AFF87 +:1013300021780029F8D170BD14A0F1E701461248C8 +:10134000006806F06FBF0000340400201B5B324AC7 +:101350001B5B313B314800001903000878B90008D5 +:101360004552523A20556E6B6E6F776E20636F6DEB +:101370006D616E642C20747279202768656C70270B +:101380000000000008200800D40800200D0A2320D7 +:10139000000000002DE9F04105460446FD4EFE4FD9 +:1013A00009E0FC4809F05BF920B1611B801B38445F +:1013B00080F80A11641C21780029F2D1BDE8F0817F +:1013C000F64800210278372A12D14288B2F55F7FB1 +:1013D0000ED10279BE2A0BD190F87923EF2A07D1DA +:1013E00000F55F7210F8013B59409042FAD309B101 +:1013F00000207047012070472DE9F05FFFF7E0FF04 +:1014000010B90A2006F01EFD4FF45F72E349E2486E +:1014100009F0D7F8E04C94F87803022802D90020AC +:1014200084F87803C0B200EB001101EB401004EB2C +:10143000800101F59671C422D94809F0C2F8D84A52 +:10144000D84F002092F8201092F81F5040F6C41692 +:1014500000FB00F3193B4B4303F6C41343436B43B8 +:1014600093FBF6F327F81030401CC0B20628EFD3E8 +:1014700092F8211092F822509146B4F8D220B4F894 +:10148000D080DFF824A300204FF00A0E4FF47A7BBF +:10149000C5F1640701EB8106A2EB080400EB8002B2 +:1014A000C1EB42030122002B03DDC1F16402D2B281 +:1014B00001E000DA0A4603FB03FC05FB0CFC02FB1F +:1014C00002F29CFBF2F23A4402FB03F292FBFEF2C0 +:1014D00002EB460212B204FB02F292FBFBF2424420 +:1014E0002AF8102000F10100C0B20B28D6D399F8D9 +:1014F000000001F065FFBDE8F05F04F06FBB2DE96F +:10150000F047A54D8146372028704FF45F740027BF +:101510006C80BE202871EF2085F879033E4685F85F +:101520007A7369B195F87803C42200EB001101EBDE +:10153000401005EB800000F59670994909F041F8DC +:101540009548974903E000BF10F8012B57408842A7 +:10155000FAD385F87A73914F4FEA040808F0F2FE47 +:10156000342008F05DFF384608F01AFF04280FD138 +:101570000024E019295908F02FFF042805D008F0AD +:10158000E7FE761C032EE9DB02E0241D4445F0D380 +:1015900008F0DEFE032E02D0FFF712FF10B90A207A +:1015A00006F050FCFFF728FFB9F1000F06D0BDE8A8 +:1015B000F047012214210F2001F0FABABDE8F087AC +:1015C00075498A6802438A6070472DE9FC5F77A1FC +:1015D000D1E90001CDE900014FF45F716E4809F0D7 +:1015E00009F8C4216E4809F005F86B4B3720002537 +:1015F00018700320587102209D60FFF7E1FF83F807 +:1016000078534FF41670A3F8F000FA20A3F8F20014 +:10161000D0332A20D8835D859D85DD859D74DD745A +:101620001D75DD821D835D831C3301265D701E7078 +:10163000202018735F4898606E2098762B20D8760B +:10164000212018775D7783F82650283340F2DC504C +:101650005D75188040F24C405880443B40F26C70FD +:10166000A3F8480083F84A5040F27E40188040F2C8 +:101670003A7058804FF47A70988040F27E50D8804B +:1016800040F2EA50188140F2B45058813220C10033 +:101690009881D981188283F84C5083F84D504FF4CB +:1016A000E13119654FF49641596583F8585040F679 +:1016B000AC513B4C23F8C41C83F84B5025702827B1 +:1016C00067704FF01E0984F80B9017216175A770A1 +:1016D00084F80C90A1755521E1702D226273E57597 +:1016E00020711921A173502323760B216171E573B9 +:1016F00065764FF0140B84F806B04FF0080C84F8B0 +:1017000010C0A2760E22E27184F811B0E3765A215D +:1017100021724FF00A0884F812804FF0640A84F8AE +:101720001CA06772A5722575A577E177412184F821 +:10173000201084F8235084F8245084F8255084F82D +:10174000210084F8225025856585E584042084F8ED +:101750002C0084F82D7084F82E70152084F82F004A +:1017600015482063154860631548A063012084F87C +:101770003C0014A0FFF70EFE84F8665084F8675012 +:1017800084F86870012084F8690084F86A5004F8CD +:10179000AC8F1DE0B4C100086404002000FC010807 +:1017A000E00700209C0A0020A80A00201E1E646496 +:1017B00064646464031414009A99193F52B87E3F1C +:1017C0003333733F4145545231323334000000000B +:1017D000C82363704FF49660608040F2D930A080D7 +:1017E0003C480021EE4640F2DC544FF47F754FF444 +:1017F000FA6C00BF00EBC10222F86C5FA2F802C0D5 +:1018000094801EF80180491C82F806800829F1DBCB +:1018100000F8B26F4FF4967146708670838080F83E +:1018200006B080F807900672A0F80AA08181C781EF +:101830000020294D014600BF05EB0012401C11613C +:101840000C28F9DB5FF0000404EB041000EB4410FB +:1018500005EB800000F59670C4221E4908F0B1FE29 +:10186000641C032CF0DBBDE8FC9F10B50446FFF7B9 +:10187000A7FD641E204206D1FFF7A7FE0021BDE8A8 +:10188000104008463BE610BD14490968014201D0EA +:10189000012070470020704710490A6802430A601F +:1018A00070470E490A6882430A6070470B48006817 +:1018B000704709498968014201D001207047002022 +:1018C000704705498A6882438A6070470248806889 +:1018D00070470000E007002064040020040000209E +:1018E00070B5FE4809F0AEFC0446FD48008808F0DB +:1018F000D0FF0546214608F041FF08F0CFFFF94C24 +:1019000029462080F84808F06FFFF84908F06CFF7E +:10191000A0650820FFF7B8FF002803D0BDE870409D +:1019200002F0D6BC70BD002801DD024600E0424254 +:101930008A4201DA00207047002802DDA0EB010096 +:101940007047FDDA084470472DE9F04F91B0D0E9B7 +:101950000045814686688846086809F073FC049053 +:10196000D8F8000009F0C8FE0590D8F8040009F086 +:1019700069FC0190D8F8040009F0BEFE0746D8F8CB +:10198000080009F05FFC8246D8F8080009F0B4FEB0 +:1019900083465046049908F0F1FE0790504601999D +:1019A00008F0ECFE80465846049908F0E7FE0690E1 +:1019B0005146059808F0E2FE08905946059808F04F +:1019C000DDFE03900198594680F0004008F0D6FEF5 +:1019D00082463946089808F0D1FE069908F076FE4E +:1019E00010903946039808F0C9FE079908F0C3FE25 +:1019F0000E900598019980F0004008F0BFFE059018 +:101A00003946079808F0BAFE039908F0B4FE029030 +:101A10003946069808F0B2FE089908F057FE83464A +:101A20000499019808F0AAFE04903046029908F043 +:101A3000A5FE01902846109908F0A0FE00904146AE +:101A4000204608F09BFE009908F040FE019908F03E +:101A50003DFEC9F800005946304608F08FFE834627 +:101A600028460E9908F08AFE80465146204608F026 +:101A700085FE414608F02AFE594608F027FEC9F8BF +:101A800004003046049908F079FE06462846059978 +:101A900008F074FE05463946204608F06FFE2946D8 +:101AA00008F014FE314608F011FEC9F8080011B024 +:101AB000BDE8F08F70B506468A4886B08030016870 +:101AC00081F000410391406880F000400490884814 +:101AD000B0F9000008F0D4FE864908F04FFE8649B0 +:101AE00008F04CFE7F4C05907434B4F9000008F007 +:101AF000C7FE0090B4F9020008F0C2FE0190B4F9EC +:101B0000040008F0BDFE029003A96846FFF71CFF21 +:101B10007A4D743C95F83C00012804D07048008848 +:101B200008F0B7FE17E0764840780028606B0CD1CB +:101B3000C11700EB9161A0EBA11008F0A1FE029982 +:101B400008F0C4FD08F0AAFE6063C11700EB9160C5 +:101B5000801108F095FE029908F00DFE029008F041 +:101B60009DFE15F82D1FFFF7DEFE08F089FE02909E +:101B7000009808F093FE6978FFF7D5FE08F080FE24 +:101B80000090019808F08AFE6978FFF7CCFE08F013 +:101B900077FE0190E0683044E0602069401C2061DD +:101BA000584C206808F06CFE009908F08FFD08F092 +:101BB00075FE2060606808F063FE019908F086FDFC +:101BC00008F06CFE6060A06808F05AFE029908F008 +:101BD0007DFD08F063FEA06006B070BD2DE9F05FEA +:101BE000404D04468035286809F02CFB8346286860 +:101BF00009F082FD8246686809F024FB8146686826 +:101C000009F07AFD0546D4F808802946404608F0D8 +:101C1000B5FD594608F0B2FD67680646514638469C +:101C200008F0ACFD294608F0A9FD054649462068A4 +:101C300008F0A4FD294608F049FD314608F046FDAC +:101C400004465146404608F099FD05465946384637 +:101C500008F094FD294608F08BFD214609F0C8F9EB +:101C6000294908F08BFD294908F0BEFD1D49C96AC4 +:101C700008F02CFD264908F0B7FD09F025FD00B25B +:101C8000002802DA00F5B47000B2BDE8F09F2DE93B +:101C9000F04F8DB0002606F002F8DFF848B0054698 +:101CA0005C46DBF83800281A099008F0F2FD194963 +:101CB000C96808F063FD04901048A5630BF16E0A33 +:101CC00090F82C7000240AF106054FF07E58054864 +:101CD000683030F9140008F0D3FD1DE0F366DF3EF4 +:101CE0007A010020080000200AE81C4100401C4640 +:101CF000A801002089C3E43A000020C1E0070020C9 +:101D0000680A0020BC0800200000E144DB0F4940C5 +:101D100000002041440C0020049908F02FFD06A982 +:101D200041F8240017B3384608F0B3FD0146404699 +:101D300008F05AFD81460B903AF9140008F0A0FD16 +:101D4000494608F01BFD814641460B9808F013FDFB +:101D5000FE4951F8241008F011FD494608F0B6FC80 +:101D6000FA4941F8240008F099FD01E03AF814001E +:101D700025F8140035F91400641C00FB0066032CE0 +:101D8000A5D3DFF8CCA364204643BAF8000006A927 +:101D9000404396FBF0F4ED481830FFF7D5FD0820DE +:101DA000FFF772FD06A910B1E8480C3800E0E948D9 +:101DB000FFF7CAFDA0B24938DFF89C933C2827D230 +:101DC0000024B9F8F00008F064FD4546414605904E +:101DD00008F07CFC0146284608F006FDDB4E05466F +:101DE0001836DC48143830F9140008F049FD07466D +:101DF00056F82410059808F0C1FC394608F066FC36 +:101E0000294608F0BBFC46F82400641C032CE8D3E8 +:101E10000820FFF739FD50B34546CC4EDFF8348338 +:101E200000240C3EA8F10E08B9F8F20008F031FDCC +:101E30008146294608F04AFC0146284608F0D4FCB1 +:101E40004FEA000538F9140008F01AFD0746484625 +:101E500056F8241008F092FC394608F037FC294661 +:101E600008F08CFC46F82400641C032CEAD35E4680 +:101E7000BBF9000008F004FDB44C1834A16808F068 +:101E80003BFD01D2012100E00021B4484173D4E9B7 +:101E9000010109F0ADF8AF4D083D2860A06801468A +:101EA00008F06CFC07466068014608F067FC39469C +:101EB00008F00CFC09F0E6FC0146206880F00040C8 +:101EC00009F096F8DFF8988268604146286808F0C3 +:101ED00055FC09F0F9FBA5F15007414638806868C8 +:101EE00008F04CFC09F0F0FB78800820FFF7CCFCF0 +:101EF0009C4D10B195480C3800E09648FFF76EFEF7 +:101F000028800998FFF7D6FD974D95F86A000028BC +:101F10001BD0BAF8000008F0BCFC0146A06808F02D +:101F200063FC924908F02AFC08F0B8FCC0F1640098 +:101F30006422002104F086FB95F86A104843C1171B +:101F400000EB517040F3CF0070800DB0B0E52DE98B +:101F5000F04102F0B4F90220FFF796FC20B102F044 +:101F6000B1F8FFF794FE05E07A4900201A3908809D +:101F7000488088804020FFF79CFC7649764B2C39BE +:101F800010B3A1F15602107830B9D3F8F400030C65 +:101F90001370030A537090706E4B0020B3F1260348 +:101FA000145C31F9105033F91060671E06FB0755B9 +:101FB0006D1C95FBF4F421F8104023F81040401CF0 +:101FC0000328EDD3BDE8F081587901280AD0614A91 +:101FD0000020203A32F8103021F81030401C03283D +:101FE000F8D3EFE75B4AB1F90400883AB2F904305C +:101FF00000EB4300032390FBF3F088809080E1E73F +:10200000524900200C310860486088605149883985 +:102010000861C86070472DE9F84F05F040FE4D4C4F +:10202000883C216C461A46F2A8118E4202D200204A +:10203000BDE8F88F4E4920644B4D088858B195F89B +:102040002F20A369521EB3FBF2F2401EE263088008 +:1020500000206064A06495F82F00401E08F010FC7A +:102060000746E06B08F00CFC394608F087FB074692 +:10207000A06908F00EFC394608F0B6FB09F05AFAE0 +:102080003C4908F07BFB09F09DF94FF07E5108F0C8 +:1020900072FB0746606946F6B321084408F0F0FB7E +:1020A000354908F06BFB394608F068FB08F0F6FB91 +:1020B000D5F83080074641464FF07E5008F058FB77 +:1020C0008146384608F0DCFB494608F057FB0746D6 +:1020D000E06908F0D5FB414608F050FB394608F0AE +:1020E000F5FA08F0DBFB8346E061E06808F0D1FB1D +:1020F0008046224908F042FB0746206908F0C0FBF1 +:10210000814612480C30806808F0BAFBA16D08F0D7 +:1021100035FB414608F032FB494608F065FB804636 +:10212000606C3946009008F029FB81464FF0FF3182 +:10213000404608F099FB394608F020FB494608F074 +:10214000C5FAA16C08F0C2FA824619E0B008002076 +:102150007A0100209000002064040020680A00201A +:102160004C3D0F44A8010020E00700200000C842B9 +:10217000A601002041D3423EA1D81943BD37863580 +:10218000D5F838904FF07E50494608F0F1FA0746EE +:10219000584608F075FB394608F0F0FA07464946FC +:1021A000504608F0EBFA394608F090FAA06408F0BF +:1021B00075FB20654146009808F088FA6064FFF7D7 +:1021C0001FFFD4E914104FF49678401AC8F10009A3 +:1021D0004246494604F036FA0A21FFF7A4FB0746B7 +:1021E0002879C8227843C11700EB5160C0115142D1 +:1021F00004F028FA2062A87B4CF250327843C117D1 +:1022000000EB9160616A01EBA0105142606204F042 +:1022100019FAC117606200EBD150216A01EB60200E +:102220002062304608F035FB0646E769E06C381A54 +:1022300008F026FB234908F0A1FA314608F0D4FA49 +:1022400008F02CFB42464946E76404F0FBF90A21FA +:10225000FFF769FB6F6B804639464FF07E5008F000 +:1022600087FA0646404608F00BFB314608F086FA2E +:1022700006463946606C08F081FA314608F026FAC5 +:10228000606408F00BFB4FF47A72514204F0DAF903 +:1022900008F0F6FA606408F001FB0521FFF743FB44 +:1022A000A062297E96224143C81701EB10700011ED +:1022B0006FF0950104F0C6F9216A081A2062012026 +:1022C000B6E600000024744970B5994D04462868AC +:1022D00007F0EDF80028FAD0E1B2286807F0CEF850 +:1022E000204670BD86B005F023FD0020FFF7BDFA43 +:1022F000FFF782F88F4C002594F8090118B10128E6 +:102300001ED009281CD08DF8105084F8095104A85B +:1023100004F0C4FB04F09EF90E20FFF7BDFA00F0B4 +:1023200039F9607901260E280DD008280BD08DF8D8 +:10233000065000BF4FF48070FFF7BBFA50B905E0BC +:102340008DF81000E3E78DF80660F3E70820FFF74B +:10235000B0FA00B101208DF802004FF4004B58464E +:10236000FFF7A7FA8DF803000120FFF7A2FA8DF816 +:1023700001000820FFF79DFADFF8B48180F001002A +:102380008DF800006C4F98F812008DF8040097F853 +:10239000B400C0F380008DF80500B4F8DE00ADF89D +:1023A0000800B4F8E000ADF80A004FF48040FFF7F1 +:1023B00080FA08B1B4F8DA00ADF80C00B7F8B00054 +:1023C000ADF80E0094F80901012823D0092824D083 +:1023D0008DF80750684605F05DFB5849002040F233 +:1023E000DE5200BF21F81020401CC0B21228F9D3E1 +:1023F000544953480827086088F811703846FFF799 +:1024000058FAB0B194F8120158B1012809D0022845 +:102410001CD10AE08DF80760DCE707208DF8070083 +:10242000D8E7484803F002FE10E0464804F0CDFA31 +:102430000CE094F81C0128B194F91D01002801DA80 +:1024400084F81D5194F81D0103F011FC0120FFF7E1 +:1024500030FA30B14FF48060FFF72BFA08B101F089 +:10246000BBFF39494FF0100AC1F800A0A1F10409DF +:10247000B846C9F800700025A9F10407386880F053 +:1024800010003860386880F008003860192005F0C6 +:102490002FFC012005F037FC192005F029FC002055 +:1024A00005F031FC6D1CEDB20A2DE7D3C9F80080B0 +:1024B000C9F800A001F048FCFFF712FA0220FFF76C +:1024C000F8F908B101F00CFDD4F8200102F0B5F8DC +:1024D0005846FFF7EEF928B194F82811D4F82401F2 +:1024E00006F0EAFE4FF40060FFF7E3F908B103F0ED +:1024F0004BFF05F0D4FB154908606079052803D12E +:1025000013494FF4C870088012494FF47A7008805C +:102510001149C8200880114880F80D6000F058FF6C +:10252000FCE70448B0F9D40000F015F9FEE700001C +:10253000D408002064040020E0070020780A00206E +:10254000832F0008FC000020140C0140F80000203C +:102550007601002078010020A6010020680A0020F2 +:102560000146FE4800EBC100B0F97000122804DA01 +:10257000082902DAFA4931F910007047F74A02EBEC +:10258000C00090F97200084202D04FF0FF3070474F +:10259000012070472DE9F041F24EF34F707907EBBF +:1025A000C000407800B10120F04CA0742020FFF75B +:1025B00080F908B10120A0747079ED4CED4D12281E +:1025C00008D017F8301007EBC0002170426842B302 +:1025D000002024E05FF0000006EB00110A6912F011 +:1025E000FF4F1ED0D1E9057C05EB0013C969401CE3 +:1025F000C3E902C1C3E900272178491C21700C28D6 +:10260000EADB0EE002EB001305EB0016D3E9007CD9 +:10261000D3E90283C6E90283C6E9007C401C8842F4 +:10262000F0DB4FF48040FFF744F900281AD02778F8 +:10263000012F17D9002613E005EB06144FF0FF38E1 +:102640004146A06808F010F9A0604146606808F0B3 +:102650000BF960604146E06808F006F9761CE0601E +:10266000BE42E9DBBDE8F081F0B5401C0021BD4A67 +:102670000B4600BF02EB0114491C23610C29F9DB56 +:10268000B94B03EBC0014C68002C11D0002113F8AA +:1026900030000BE004EB011302EB011593E8C010CE +:1026A000DB68491CC5E906C3C5E904678842F1DC5B +:1026B000F0BDAE4810B5807C002839D0A948AC4C9C +:1026C0004079A41C05280ED004DC01281BD0042866 +:1026D00004D112E0082825D00E2829D02020FFF7A9 +:1026E000E8F8002824D02188002005F063FA6188EA +:1026F0000120BDE8104005F05DBA2189002005F0F9 +:1027000059FA6189F4E79A499448891C90F8B30012 +:10271000498908B10020ECE7974840780028F9D1B2 +:102720000021F7E7E188002005F044FA2189DFE77E +:1027300010BD70B58F4E0024183E8D4D07E000BFD0 +:1027400036F81410204605F02AFA641CE4B2287802 +:102750008442F5D370BD864A864B00211278183B1F +:1027600004E000BF23F81100491CC9B29142F9D31B +:10277000DFE72DE9FC5F7E4C804EDFF80492207885 +:10278000032814D9B9F904004142002801DD0246AA +:1027900000E00A4602F1640200DC08466FF06301C3 +:1027A000A1EB0001B6F9040003F04CFFB0807048C3 +:1027B000DFF8C0A1DFF8A4810778AAF1180A012F79 +:1027C00038D9002434E000BF98F9B200B6F90410FB +:1027D0004042484308F054F8664901EB0415E968A3 +:1027E00007F0CCFF0190B6F9000008F049F86968DD +:1027F00007F0C4FF0090B6F9020008F041F8A9689C +:1028000007F0BCFF8346B9F9060008F039F82968DB +:1028100007F0B4FF594607F059FF009907F056FF3B +:10282000019907F053FF08F039F82AF81400641CE6 +:10283000BC42C9D34B4D4E4CDFF848B16879A41C5B +:10284000052842D004DC012831D004283CD102E024 +:102850000828FBD156E00420FFF782FE0346022140 +:102860000420FFF78BFEB6F9041000FB01F70121ED +:102870000420FFF783FEB6F9021000FB0170184434 +:1028800020810520FFF76CFE034602210520FFF79B +:1028900075FEB6F9041000FB01F701210520FFF7D2 +:1028A0006DFEB6F9021000FB017018440BE0052024 +:1028B000FFF756FE034601210520FFF75FFEB6F93C +:1028C000041000FB0130608199E098F97200BBF9B7 +:1028D00002103226484390FBF6F708F172025B467D +:1028E0000020FFF73DFE3844208092F90800B3F93C +:1028F0000010484390FBF6F20120FFF731FE104430 +:1029000060807CE01C4F7878F0B3B5F8D220B5F841 +:10291000D010B9F9060003F095FEE081AAF8000096 +:10292000B87A4FF0010100284FF003003BD0FFF7C9 +:1029300025FEB9F902104B4600FB01F602210320E7 +:10294000FFF71CFEB3F9001000FB0160E0800121DD +:102950000420FFF713FEB3F9021016E0E007002091 +:10296000780A002064040020B0C50008D4080020C4 +:10297000AC00002000090020680A00202E01002081 +:102980003C010020380000200AE000FB01F6022193 +:102990000420FFF7F3FDB3F9001000FB016021E014 +:1029A000B5F8D400B9E7FFF7E9FDB6F9021000FB6E +:1029B00001F302210320FFF7E1FDB6F9001000FB4F +:1029C0000130E08001210420FFF7D8FDB6F90210A4 +:1029D00000FB01F302210420FFF7D0FDB6F900103F +:1029E00000FB013020810320FFF7BAFDE188084495 +:1029F000E0800420FFF7B4FD2189084420812020D5 +:102A0000FEF757FFC0B30020FFF7AAFD208001208A +:102A1000FFF7A6FD62496080097A69B398F8B4208F +:102A20004146920715D591F97220BBF90230564202 +:102A30005E43322398F97A10BBF9002096FBF3F637 +:102A4000514391FBF3F1721A238831449A1A228080 +:102A500010E098F97230BBF90210278803FB01F6E9 +:102A6000322196FBF1F63E442680BBF90020534309 +:102A700093FBF1F1084460800026474607EBC6004F +:102A80006C30B0F90220B0F9001034F9160003F0F0 +:102A9000D9FD24F81600761C082EEFD397F8B40061 +:102AA000DFF80091400711D500262020FEF701FF36 +:102AB00000B1022600244F4607EB44000189A0190B +:102AC000C0B205F077F8641C042CF5D3364956469D +:102AD000BAF9007001200B7806E000BF36F910202B +:102AE000BA4200DD1746401C9842F7D300244FF449 +:102AF000804A88464DE000BFB5F8D200B84205DAFA +:102B000036F81410381A081A26F814005046FEF742 +:102B1000D0FE98B1B9F9060040F2DC51884204DDDC +:102B2000B5F8D220B5F8D81003E0B5F8D620B5F83E +:102B3000D41036F9140003F085FD15E0B5F8D22065 +:102B4000B5F8D01036F9140003F07CFD26F8140017 +:102B5000B9F90600B5F81611884207DA1020FEF719 +:102B6000A8FE38B1B5F8D40026F814000F48407814 +:102B700018B10DE0B5F8D000F6E75046FEF799FE23 +:102B800010B1B5F8DA0001E0B5F8D40026F8140069 +:102B9000641C98F800008442AED3BDE8FC9F00009E +:102BA000BE0A0020780A0020AC000020680A00203D +:102BB0002DE9F0471746894606460025DFF83C8494 +:102BC0001AE0002411E000BFD8F8001081F00801DD +:102BD000C8F80010012005F096F8484605F088F87E +:102BE000002005F090F8641CE4B2B442ECD33C2021 +:102BF00005F07EF86D1CEDB2BD42E2D3BDE8F08772 +:102C00002DE9FC5FFE4C002540F2DC51B4F90600D2 +:102C1000FC4E4FF4FA73884201DA64210CE0F94962 +:102C2000B0F5FA6F91F8251004DAA0F2DC525143A6 +:102C300091FBF3F1C1F164018946F34996F866E02E +:102C400096F867B0B1F814410022B246EC49EE4B59 +:102C500040F2E63C31F91260311B01F2F31767458F +:102C600003D8002903DCA11B01E04FF4FA71022A0A +:102C700034D0BEF1000F05D08E4502DAA1EB0E0173 +:102C800000E00021642391FBF3F3DD4F6FF018089F +:102C9000243707EB430C37F91370BCF902C003FB70 +:102CA00008F3ACEB070C01EB83030CFB03FC642380 +:102CB0009CFBF3F33B44D54F27F812309AF82330AE +:102CC0004B434FF4FA7193FBF1F1C1F1640189B206 +:102CD00001FB09F1642391FBF3F11CE0BBF1000F50 +:102CE00005D08B4502DAA1EB0B0100E0002193F93E +:102CF000EC30DFF818C35B424B43ACF804309AF871 +:102D00002430002900DC49424B434FF4FA7193FB15 +:102D1000F1F1C1F164010AEB0207642397F801C0E5 +:102D2000DFF8E8820CFB01FC9CFBF3FCA8F15408E3 +:102D300008F802C097F80BC008F103080CFB01FC6F +:102D40009CFBF3FC08F802C07F7D4F4397FBF3F137 +:102D500008F10303A642995405DAAC4931F8123060 +:102D60005B4221F81230521C032AFFF66FAFDFF8E6 +:102D700098A24FF4FA625446BAF8161103F062FCB6 +:102D8000B4F816114FF47A72401A5043C1F5FA6143 +:102D9000B0FBF1F1642291FBF2F0994B6FF0180651 +:102DA000303303EB400433F910307043B4F9024080 +:102DB00001EB8000E41A444394FBF2F0DFF84C820C +:102DC0008F4E1844103EA8F80600707AA8F17C04D3 +:102DD000E8B38F48B4F91E10B0F90000401A07F0AC +:102DE0004FFD8C4907F0CAFC8B4907F0FDFC0746F4 +:102DF00008F028FA0190384608F07EFC009047461B +:102E0000B8F9000007F03CFD8346009907F0B6FCD6 +:102E10008046B7F9020007F033FD8146019907F0BB +:102E2000ADFC414607F052FC07F038FD80464846AD +:102E3000009907F0A3FC81465846019907F09EFCD3 +:102E4000494607F095FC07F029FD388000E001E0D5 +:102E5000A7F802800220FEF72CFD002750B3E0788F +:102E6000401CC0B20621B0FBF1F2E07001FB120081 +:102E7000B8B9002003F084FE2179614A01F007030C +:102E8000AC3A491C22F813002171002032F81010CE +:102E9000401C29448DB20828F8DBE80801F008F846 +:102EA000A072A07AE18C884203D89AF80811814276 +:102EB00001D9A77001E00420A070A07803F059F9AF +:102EC00056484E4D008818B10220FEF7DDFC10B9BF +:102ED0005348008820B1286880F00800286011E07D +:102EE000B178082011B14549091D0860717811B108 +:102EF0004249083108604FF40060FEF7DAFC08B17F +:102F000003F057FA8020FEF7D4FC48B1E16C606B07 +:102F1000411A05D44CF250310844E06405F00AFA35 +:102F2000A16C606B411A03D4717BF9B10120B070C0 +:102F300002F00BF82020FEF7A7FC68B1216D606B52 +:102F4000411A09D4E17A052906D336490844206597 +:102F5000286880F0100028603348816800290ED06E +:102F600002B02A48BDE8F05F5C380847B7702968AE +:102F700081F0080129602D490844A064D8E7BDE824 +:102F8000FC9F10B5204C204490F80A0104F01CFE70 +:102F9000A0F2EE2140F2DD52914201D3B4F81401C7 +:102FA00010BD2DE9F047194EDFF854807C3EA8F1A2 +:102FB0009C087079124F401C00247071A14608F1E2 +:102FC0004005F16B20468847727908EBC40102F096 +:102FD000030221F8120025F81490002035F814306F +:102FE00031F81020401C1A44C0B225F814200428DF +:102FF000F4D335F91400801CC11719E00C0C014002 +:10300000780A0020E0070020640400203C01002032 +:10301000A8010020DB0F4940000034437601002066 +:1030200078010020F0490200440C002020A1070094 :1030300000EB9170801025F8140037F91410C91EA8 :10304000884202DA811C27F8141037F91410C91CC1 :10305000884202DD801E27F81400641CE4B2082CAC -:10306000AED3C3E5FE480288FE48417852B9827863 +:10306000AFD3CBE5FE480288FE48417852B982785A :1030700042B1002905D101214170FB48FB4900887C -:10308000C88370470029FCD10122FF21022087E577 +:10308000C88370470029FCD10122FF2102208FE56F :103090002DE9FC5F0020F54982467C310546074654 :1030A0000190B1F902004342002801DD044600E02E :1030B0001C468B46B1F900104A42002901DD0E463C @@ -783,17 +783,17 @@ :1030D000002901DD084600E01046DFF89493002443 :1030E0000090E04EF07808B93079E8B3022C3FDA6E :1030F000DE484FF4FA72443030F914103BF91400F2 -:1031000001EB4000514203F01FFADA49DFF868A3EF +:1031000001EB4000514203F09DFADA49DFF868A371 :1031100031F91410411A0AEB4400B0F9280001EB10 :1031200000089AF80810642001FB08F191FBF0F008 :103130009AF81C1001EB8102494201EB810103F076 -:1031400003FA0190C94842F21072743050F824100A -:1031500001EB0800514203F0F7F9C449743141F81A +:1031400081FA0190C94842F21072743050F824108C +:1031500001EB0800514203F075FAC449743141F89B :1031600024009AF8121000E008E048434FEA203AA1 :10317000F07818B1307908B9022C48D13BF91450D5 :10318000B84F05EB85000101BB48A83F00EB0408E0 :103190004FF47A5298F8010091FBF0F039F91410CD -:1031A000401A57F824100844514203F0CDF947F86B +:1031A000401A57F824100844514203F04BFA47F8EC :1031B000240039F9140000F52070B0F5A06F02D892 :1031C00057F8240002E0002047F824007D2190FBFE :1031D000F1F098F80B10484387113079A8B1022C10 @@ -807,17 +807,17 @@ :1032500024C041F824309C44844448F82400834826 :103260002E30005D00FB0CF0C11700EBD16091190E :10327000A1EB60107D496E3121F81400641C032C11 -:10328000FFF62FAF7AE62DE9F05F764E4FF0000B98 +:10328000FFF62FAF7BE62DE9F05F764E4FF0000B97 :10329000DFF8E4A1DFF8D4915C46A83E714DE878F0 :1032A00008B92879D0B1022C18DA70484FF4FA72B4 :1032B000443030F91410383030F9140001EB40007C -:1032C000514203F041F96B4931F91410411A0AEBEC +:1032C000514203F0BFF96B4931F91410411A0AEB6E :1032D0004400B0F9280001EB000B01E0022C52D0B1 :1032E000E878E0B39AF8080000FB0BF000116049A1 :1032F0000AEB040731F91410FA7A451A787856F86F :10330000241068434FEAE018B9F80C006843C01273 :1033100000FB02104FF4001246F82400514203F063 -:1033200013F946F8240043134E480C3850F8241083 +:1033200091F946F8240043134E480C3850F8241005 :1033300040F82450B9F80C00691A02094FF6FF70E2 :10334000B0FBF2F0484347498011243901F10C02E7 :1033500051F824C052F824506544054400E01CE0B4 @@ -828,64 +828,64 @@ :1033A0007C321B3032F9142050432A790011002A54 :1033B0009DD09AF8121001FB0BF100EB212096E74B :1033C0002A49012801D02D4800E02D4808647047A3 -:1033D0002DE9F84F0027B946B8460820FEF7ABFAAA -:1033E000DFF8A0B068B19BF80E0120B1012802D02F -:1033F000022806D102E002F0EDFD01E003F0FCF846 +:1033D0002DE9F84F0027B946B8460820FEF769FAEC +:1033E000DFF8A0B068B19BF8120120B1012802D02B +:1033F000022806D102E002F03CFE01E003F004FBEB :103400008046DFF868A0174C4FF00005DAF834105A :10341000DAF854004FF00106081A02D5B8F1000F8F -:103420007DD044F620621144CAF85410FFF7B8FD6D -:103430004FF48040FEF77FFA28B10A483230007816 -:1034400008B900F07EFC9BF8170168B307494FF4F8 -:103450007A729C3101EB40000021B0F9060013E0C4 -:1034600088010020FC0A0020B8010020C0000020D4 -:10347000640000203800002050080020913000082F -:103480008732000870040020A0F57A7003F05CF821 -:1034900007F02CF8FE4906F055FEFE4906F01CFE2A -:1034A00007F069F8AAF822004FF40070FEF743FA1B +:103420007DD044F620621144CAF85410FFF7B9FD6C +:103430004FF48040FEF73DFA28B10A485630007834 +:1034400008B900F078FC9BF81B0168B305494FF4FC +:103450007A72103101EB40000021B0F9060013E050 +:1034600078010020680A0020A8010020C000002088 +:103470006400002038000020E007002091300008A0 +:103480008732000864040020A0F57A7003F0DAF8AF +:1034900007F0F6F9FE4907F0A7F9FE4907F06EF9C3 +:1034A00007F015FAAAF822004FF40070FEF701FAAF :1034B000B0B3DFF8E483BAF90E2098F8ACC00CEB97 -:1034C0008C0191421DDA6078D8B1BBF91031F34913 +:1034C0008C0191421DDA6078D8B1BBF91431F3490F :1034D000002000BF21F81030401C0328FADBB8F8A8 :1034E000AE30CB8098F8AD00604400EB8000904295 -:1034F00002DA00F026FC2570BAF81010491CAAF870 +:1034F00002DA00F020FC2570BAF81010491CAAF876 :10350000101098F8AC0000EB8001BAF90E0081426F -:1035100004DA607810B900F014FC257001E068E26C -:1035200004E0BAF80E10491CAAF80E10BBF81231CC -:10353000BBF81421DFF864830020BF0838F910C0FD +:1035100004DA607810B900F00EFC257001E068E272 +:1035200004E0BAF80E10491CAAF80E10BBF81631C8 +:10353000BBF81821DFF864830020BF0838F910C0F9 :103540009C4501DD47F08007944501DA47F04007CC :10355000401C0428F1DB9AF8071050468F4205D131 :103560008179FA2903D2491C817100E085718AF8BA -:1035700007704FF480473846FEF7DDF958B1BBF8C5 -:103580001011BBF8DC00B8F906200B1A934202DADE -:103590000844904209DC3846FEF7CDF9E8B9B8F99D -:1035A0000610BBF81201814217DABD48056045607C -:1035B0008560BA48283805604560B748C08F60B15B -:1035C000B748DA30007820B1207810B1FFF74AFD13 -:1035D00003E0607808B100F0B4FB9AF80600142804 +:1035700007704FF480473846FEF79BF958B1BBF807 +:103580001411BBF8DC00B8F906200B1A934202DADA +:103590000844904209DC3846FEF78BF9E8B9B8F9DF +:1035A0000610BBF81601814217DABC48B83805602E +:1035B00045608560BA4805604560B748C08F60B116 +:1035C000B6484630007820B1207810B1FFF74AFDA8 +:1035D00003E0607808B100F0AEFB9AF8060014280A :1035E00017D16078B0B1AC4FF88F28B99AF80700BE -:1035F0005F2801D100F0A5FB9BF81601002808D038 +:1035F0005F2801D100F09FFB9BF81A01002808D03A :10360000F88F002805D19AF807007D2801D100F035 -:1036100098FB8FE09AF80700572809D00420FEF79E -:103620008AF9E8B19AF8071050465A2921D017E0D4 -:103630009C494FF47A7008804FF48070FEF77BF954 -:1036400008B101F01FFF0420FEF760F910B19649A0 -:103650000A2008800820FEF759F908B99348058028 +:1036100092FB8FE09AF80700572809D00420FEF7A4 +:1036200048F9E8B19AF8071050465A2921D017E016 +:103630009C494FF47A7008804FF48070FEF739F996 +:1036400008B101F062FF0420FEF71EF910B196499F +:103650000A2008800820FEF717F908B9934805806A :103660009AF807005D2817D05B2817D05E2817D07E :1036700023E0818A19B18582AAF816601DE0818C49 :1036800021B10021818419B1022102E00121F9E771 :1036900003218AF8001010E0012702E0022700E071 -:1036A0000327781E8BF8DC0300210846FDF757FF3F -:1036B0003A4628210220FFF773FA774FF88F18B99E -:1036C0009AF807106F290ED09BF8161121B118B97E +:1036A0000327781E8BF8780300210846FDF727FFD3 +:1036B0003A4628210220FFF77BFA774FF88F18B996 +:1036C0009AF807106F290ED09BF81A1121B118B97A :1036D0009AF807007E2806D09AF80700972805D0A8 :1036E000A72808D008E0FFF7BDFC05E070494FF4BB :1036F000C870088000E0A6739AF80700BB2806D0BF :10370000B72807D0BE2809D0BD280AD012E0788D8E :10371000801C01E0788D801E788505E0388D801C46 -:1037200001E0388D801E388501210846FDF717FF1E -:103730008AF806500420FEF7FEF820B3BAF82420D9 +:1037200001E0388D801E388501210846FDF7E7FE4F +:103730008AF806500420FEF7BCF820B3BAF824201B :10374000504632216AB162785AB1B8F90630BBF8F6 -:103750001221934205DD524ADA3212780AB94182C7 -:1037600085844F4ADA32527C32B1028B838A1A4303 +:103750001621934205DD514A463212780AB9418258 +:1037600085844E4A4632527C32B1028B838A1A4398 :1037700009D1AAF8121006E0818A21B1617811B945 :103780008582AAF816600020C64640F2A46700BFF2 :103790000EEB4001B1F9082040F214518A4201DADF @@ -893,2499 +893,2499 @@ :1037B000BCF5C77F02D84FF0010C01E04FF0000CC0 :1037C00001F101080CFA08FC43EA0C03BA4201DDDE :1037D000012200E00022891C8A40134343EA0903C6 -:1037E000401C1FFA83F90428D2DB2D4F0020DA3762 +:1037E000401C1FFA83F90428D2DB2C4F00204637F7 :1037F000294901EB4001C98F11EA090100D00121DB :103800003954401C1428F3DB787840B9224890F8EA -:10381000AC0000EB8001BAF90E0081420BDA022005 -:10382000FEF774F838B1E07830B91C4828380560E4 -:103830004560E67000E0E570B87840B1E570207949 -:1038400030B91648283805604560267100E02571BA -:103850003878B84600B92670E178102009B9217986 -:1038600009B1144901E01349091F08600420FEF75B -:103870004DF8C0B398F80300474648B3A07930BB71 -:103880000D48A67101680D4801600448203817E012 -:1038900000007A4400C07F44500800205C010020F2 -:1038A000540A002088010020B6010020B801002041 -:1038B00086010020140C0140580000205C0000200C -:1038C000C188F748AAF81A100560F648056000E0BC -:1038D000A5714FF40050FEF72EF820B1387918B1D9 -:1038E000E07B00B9E67300E0E5730220FEF70EF816 -:1038F00018B90820FEF70AF8D0B198F8051040462C -:1039000039B1617931B9E84966710A88E7490A80B5 -:1039100000E06571817919B1617A11B9667200E0D0 -:10392000657298F8070018B1DF480188AAF81E10E0 -:103930002020FDF7EBFFE0B3E07AD8B39AF80B0054 -:103940005746052843D398F80A1059B1E07980BB4F -:10395000E671D74925723D72081F02F021FA022054 -:10396000787038E0E57198F80B0040B3D04A143A0B -:10397000B2F90000002800DC4042CE49B1F8E41062 -:1039800088421CDAB2F90200002800DC404288427A -:1039900015DA207A68B9C64826720C383D7200F1F3 -:1039A000100102680A60406841F8040FC048001D19 -:1039B00001E010E00BE002F0F3F97E700BE02572FD -:1039C000387A40B98AF8086002F0C3F903E0E5717B +:10381000AC0000EB8001BAF90E0081420ADA022006 +:10382000FEF732F830B1E07828B91D4805604560F0 +:10383000E67000E0E570B87838B1E570207928B915 +:10384000174805604560267100E025713878B84654 +:1038500000B92670E178102009B9217909B115491C +:1038600001E01449091F08600420FEF70DF870B14B +:1038700098F80300474650B3A07938BB0E48A671AC +:1038800001680E48016006480830C18818E02BE046 +:1038900000007A4400C07F44E0070020780A00203E +:1038A0003401002078010020A6010020A80100209A +:1038B00076010020140C0140580000205C0000201C +:1038C000FF48AAF81A100560FE48056000E0A571DF +:1038D0004FF40050FDF7EDFF30B1387918B1E07BBF +:1038E00010B9E67300E0E5730220FDF7CDFF18B9CB +:1038F0000820FDF7C9FFD0B198F80510404639B14E +:10390000617931B9F04966710A88F0490A8000E0AE +:103910006571817919B1617A11B9667200E06572D9 +:1039200098F8070018B1E8480188AAF81E1020206E +:10393000FDF7AAFFF0B3E07AE8B39AF80B00574618 +:10394000052844D398F80A1059B1E07990BBE67184 +:10395000DF4925723D72081F02F095FA0220787047 +:1039600039E0E57198F80B0030B3D94A143AB2F94E +:103970000000002800DC4042D649B1F8C01088425F +:103980001DDAB2F90200002800DC4042884216DA53 +:10399000207A78B9CE4826720C383D7200F11001B9 +:1039A00002680A60406841F8040FC948001D02F02F +:1039B0006AFA02E00FE00AE001E07E700BE0257297 +:1039C000387A40B98AF8086002F032FA03E0E5710B :1039D00025728AF8015098F80C0008B1A67200E030 -:1039E000A5729BF80500082801D00E2839D1657210 -:1039F00037E0DAF85C005746032801DD001FF86560 -:103A000030B101280CD0022814D0032829D11BE0A2 -:103A10000820FE65FDF77AFF10B100F06AFC00BBDC -:103A2000F86D401CF8650420FDF770FF10B100F040 -:103A300072FBB0B9F86D401CF8650420FDF766FF15 -:103A400010B1FEF730FB60B9F86D401CF86510202E -:103A5000FDF75CFF08B100F0CEFC4FF40050FDF71D -:103A60006AFF03F011FFCAF83400BBF80C20574678 -:103A700012B1BB6DC31A79D41044D946B865FEF7AC -:103A8000AEFAFFF7B5F803F0FFFE7863398F411AFD -:103A9000B981B8630820FDF739FF20B38449143990 -:103AA000B1F9042002F145008A281DD86079D8B107 -:103AB0007D4803887D480088181A00B210F1B40FC1 -:103AC00002DC00F5B47000B2B42802DBA0F5B470DB -:103AD00000B2637B3BB1774B5B7A43431E2093FB81 -:103AE000F0F0101A888003E06F4801886F48018069 -:103AF0000420FDF70BFF58B3A07948B36D4991F846 -:103B0000690030B36A48B7F91A201438B0F90630A2 -:103B1000A3EB020CBCF1000F01DCA2EB030C91F84B -:103B200068108C4509DDDFF878C19342CCF800506D -:103B30007E7200DD4942194409E0797A21B15E497B -:103B40000B685E490B607D72564909881144C1803B -:103B500039E0DFF85C81B7F91A00A8F11408B8F968 -:103B600006301A1A002A02DD134601E0E7E0C31A04 -:103B700091F868108B420FDDB98B4FF4FA6C114449 -:103B800009B291FBFCF34D4A0CFB131115681D445F -:103B90001560B9837E7207E0797A29B146490A68CF -:103BA00046490A60BD837D723E490988084400B2D7 -:103BB000A8F80600B9F8D010B9F8D220963102F072 -:103BC000C3FCA8F806003B4D95F86A0050B1E078B8 -:103BD00008B9207930B13648394A1438C18812887A -:103BE0001144C1802020FDF791FEE8B3E07908B9C7 -:103BF000207AC8B3207BB8B32B4CB4F9000006F090 -:103C000075FC304E314606F067FA07F075FC0090FF -:103C1000B4F9000006F06AFC314606F05DFA07F0E0 -:103C200011FA0646A94695F8DD00214DDFF898A067 -:103C3000303DA5F11C0890B32C1DB5F90200B4F974 -:103C40000210401A01F0CDF999F8DD20514202F03E -:103C50007BFC618808446080B5F90000B4F900106D -:103C6000401A01F0BEF900E05FE099F8DD20514212 -:103C700002F06AFC2188084400B2208006F036FC7D -:103C80008346009906F028FA0546B4F9020006F0CA -:103C90002DFC8146314606F01FFA294628E015E042 -:103CA0002C00002028000020B8010020BA010020CC -:103CB0005001002050080020580000205C00002027 -:103CC0000A00002035FA8E3C00002041B5F90000C2 -:103CD00006F00CFC8346009906F0FEF90446B5F99F -:103CE000020006F003FC8146314606F0F5F9214654 -:103CF00006F0ECF95546514606F024FA06F022FC8F -:103D0000A8F8000044465846314606F0E5F9064654 -:103D10004846009906F0E0F9314606F085F9294653 -:103D200006F010FA06F00EFC6080386C8047FEF753 -:103D30000AFDFEF7BCFCBDE8F84FFEF7F2BCBDE89B -:103D4000F88F03484178002901D000214170704765 -:103D5000FC0A00202DE9F843FE4CFF4904F1F5036D -:103D60000026B4F8E8209846A1F1100004F015FAF6 -:103D700008B101260EE0B4F8E810F74804F022FC80 -:103D800040B9B4F8E810F44803F079FB10B9032007 -:103D900003F04EFEF14D002794F8E60006283CD2D1 -:103DA000DFE800F00707192833030220FDF7BBFD09 -:103DB00033E08DF800704FF44870E749ADF8020029 -:103DC0001039684602F077FD08B10120287094F898 -:103DD000E600012821D06EB1DF49B4F8E82043465F -:103DE000A1F1100004F0D9F90220287094F8E6003F -:103DF00002281DD0D848103804F0D8FA28B1032082 -:103E0000287094F8E600032812D0D348103804F044 -:103E1000C4FF10B1042028700AE0287840B994F853 -:103E2000E60010B184F8E670B6E70220FDF77BFDEE -:103E3000C948103004F0C9FC38B9C748103002F046 -:103E4000E4FD10B90420FDF76EFD0220FDF75EFDD4 -:103E500028B1C14994F8E300103909688847BE4980 -:103E600014F8E20F09688847A07802F0E7FE10B95D -:103E70000820FDF758FDBA486421B0F9262092FBCE -:103E8000F1F001FB102406B20820FDF73FFDB54D0F -:103E900090B1204606F02AFBB34906F01DF904460E -:103EA000304606F023FB214606F0BEF8AF4906F087 -:103EB00013F92860BDE8F8832F60FBE770B505466D -:103EC000A44890F8020106F01AFB0446284606F0C2 -:103ED00016FBA74906F000F9A64906F033F921467A -:103EE00006F0FAF806F047FB80B270BD70B5002509 -:103EF0002C46002002F03CFC05440A2003F0ECFCB8 -:103F0000641C202CF5D3C5F34F10FFF7D7FF914A5F -:103F1000022192F8033100BF03FB01F4844202D86E -:103F2000491C0629F8D39448017092F804014843CB -:103F30009249088070BD2DE9F05FDFF82092904E25 -:103F4000874FB9F80220834C0025C2B38D49002069 -:103F50004FF4C878424501D141F8205051F8203043 -:103F600036F910C0634441F8203026F8105004EBB5 -:103F70004003401CA3F8F6500328EBDB012A19D1BB -:103F80000868C83090FBF8F024F8F60F4868C8308D -:103F900090FBF8F060808868C83090FBF8F1B9F8C1 -:103FA0000600081AA0803D850121F63C7D85084663 -:103FB000FDF7D5FAB9F80210491EA9F8021004203D -:103FC000FDF7B9FC002874D06F4BDFF890816D4984 -:103FD0001A8808F120080C31A8F1180A322A05D0F5 -:103FE000F2B300209B46322A14D015E034F8F60FC5 -:103FF000A8F800006088A8F80200A088A8F80400CB -:10400000B7F828C0AAF800C0B7F82AC0F63CAAF84A -:1040100002C0E6E741F8205051F8203036F910C0D0 -:10402000634441F8203026F8105004EB4003401C54 -:10403000A3F8F6500328D6DB012A1AD15348544B73 -:10404000058001201880534B02201870B8F800003A -:1040500024F8F60FB8F802006080B8F8040000E019 -:104060000AE0A080BAF800303B85BAF80200F63CBE -:104070007885521EABF8002047480288012A18D1E3 -:1040800005800A68322092FBF0F224F8F62F4A6885 -:1040900092FBF0F26280896891FBF0F1B9F80600BA -:1040A000081AA0803D850121F63C7D850846FDF774 -:1040B00056FA308834F8F61F401A308070886188CC -:1040C000401A7080B088A188401AB080BDE8F09F87 -:1040D000214810B51038416829488847BDE810408C -:1040E00029E730B51D4C1E4AE06892F82F200146A2 -:1040F000401C824200D10020284A1368214A18320D -:1041000042F82130264952F820200D682B449A1A93 -:104110000A60E06030BD70B52248104C006821692B -:10412000411A01D5002070BD20610B4D606910352A -:1041300078B12869804768688047288821690844E1 -:1041400020616A6918491548904700206061022083 -:1041500070BD2BE070040020B40C0020840100200E -:1041600050080020340000208988883C000020414D -:104170003333534000F07F4571010020E6000020FA -:1041800076000020840B0020D2000020D800002000 -:10419000D4000020C0000020D60000209C00002099 -:1041A00020000020F40000201C000020A8688047A8 -:1041B000E8688047FFF795FF012060616888216902 -:1041C00008442061012070BD2DE9F05FA24DA88850 -:1041D00000286AD0DFF884820024A3464FF47A795D -:1041E000A8F10C06A888484507D104EB840208EB27 -:1041F000820146F824B0C1F810B0994F56F8241047 -:1042000037F91400014446F8241006F06FF901460E -:1042100004EB840208EB8200824600F0EFF827F8F6 -:1042200014B0904F27F814B0A888012837D1DAF8D5 -:104230001000012808DD401E06F058F90146DAF8A2 -:104240000C0005F07FFF00E0002007F01BFA82461B -:10425000854890F8F400A8B106F051F9514606F0EF -:10426000BBF90FD27D49A5F80490C8F810B0C1F889 -:1042700024B0C1F838B0C6F808B0C6F804B0C6F823 -:1042800000B00CE056F82400012200F5FA7090FB13 -:10429000F9F027F814000F210A20FEF781FC641CB6 -:1042A000032C9FDBA888401EA8806D496D4A002022 -:1042B00031F8103032F810401B1B21F81030401C30 -:1042C0000328F5DB02E7654810B54C3041686448C7 -:1042D0008847BDE8104077E710B5644810240460B3 -:1042E00002F0FBFC6148001F04605B49012048703C -:1042F00010BD2DE9F0415E48574C0068A169411A94 -:1043000002D50020BDE8F0815A490844A0615A480E -:1043100002F0ABFCDFF864C14F4B00269CF80E00A6 -:104320005549514A26339D1D88B1A069E06100209E -:1043300002EB4007A7F8FC6031F8107023F810700A -:1043400025F81070401C0328F2D38CF80E606078BA -:1043500068B1088832F8FC7FC01B088048885788FD -:10436000C01B488088889788FC3AC01B8880E06919 -:10437000A0B3A769381A424FB84219D23B4808384F -:10438000026882F0080202605FF0000031F910203C -:1043900033F91040A24201DA23F8102035F9104019 -:1043A000A24201DD25F81020401C0328EED315E0C1 -:1043B0000020E66133F9101035F91040214402EB7A -:1043C000400401EBD17141F34F01401CA4F8FC10F3 -:1043D0000328EFD301210846FDF7C1F8012091E73A -:1043E00010B5012004F036F81020FDF797FA2549A2 -:1043F0000020086010BD234804F07FB82DE9F0418B -:10440000044600690E46401C206101281FD006F0BA -:104410006DF8256880462946304605F057FE074668 -:10442000414605F08FFE294605F0FEFD0546606019 -:104430002946304605F04AFE0146384605F04CFE56 -:10444000A16805F0F1FD2560E060A0605AE76660B4 -:1044500000202660F9E7000084010020680C00209D -:1044600070000020A000002070040020140C014007 -:10447000F4000020A086010082000020FC0A002039 -:1044800080C3C901A800002070B5FB4CFB4EC1B22F -:104490000546E170306804F0A1FC207AE1784840DC -:1044A0002072C5F30721E170306804F097FC207A90 -:1044B000E17848402072C5F30741E170306804F0AC -:1044C0008DFC207AE17848402072290EE170306836 -:1044D00004F084FC207AE1784840207270BD70B509 -:1044E000E54CE64EC1B205462171306804F076FC19 -:1044F000207A217948402072C5F307212171306864 -:1045000004F06CFC207A21794840207270BD10B50F -:104510000446DA482146006804F060FCD648017A77 -:104520006140017210BDD44AD548517A405C491CA3 -:104530005172704700B5FFF7F6FF0346FFF7F3FF30 -:1045400003EB002080B200BD10B5FFF7F3FF044677 -:10455000FFF7F0FF04EB004010BD70B504460D46B8 -:104560002420FFF7D4FF4D20FFF7D1FF0CB121200D -:1045700000E03E20FFF7CBFFBF4C00202072284612 -:10458000FFF7C5FFA07ABDE87040C0E701460020F4 -:10459000E3E701460120E0E7B748007AB7E770B5E6 -:1045A00004460D460846FFF7F1FF03E014F8010B3F -:1045B000FFF7ADFF2800A5F10105EDB2F6D170BD02 -:1045C00010B5044603E000BFFFF7A1FF641C20788C -:1045D0000028F9D110BD2DE9F047C0B04FF480712B -:1045E000684605F0B5FCDFF898A2A34E0025DFF879 -:1045F0008882AAF1140A0C3605EB4507002406EB65 -:1046000087090BE016F827101AF80400814204D13C -:104610006846D9F8041005F0A6FC641C98F8000060 -:104620008442EFDB6D1C142DE6DB684605F0CFFC01 -:10463000C0B2FFF7ABFF6C4603E000BFFFF767FFB8 -:10464000641C20780028F9D140B0BDE8F0872DE93E -:10465000F04700270246032339468A4803F0F4FA5C -:104660008649FF220860886085481421143805F0C7 -:1046700068FC834D0020143D012428700220FDF7C2 -:1046800045F905264FF006084FF0070950B1012003 -:1046900068700220A870EE7085F80480062485F802 -:1046A000059001270420FDF731F950B1032028556A -:1046B000641C4FF40050FDF73EF910B1042028555A -:1046C000641C0820FDF722F940B13FB92E55641C47 -:1046D00005F80480641C05F80490641C2020FDF794 -:1046E0002AF910B108202855641C4FF48070FDF79A -:1046F00022F948B12020FDF709F928B10A202855F0 -:10470000641C0B202855641C5F484079082801D0A0 -:104710000E2802D10C202855641C0D202855641C3D -:104720000420FDF708F910B111202855641C5248E7 -:1047300004708AE72DE9F05F4F4E00273146B07ACA -:10474000DFF83C910978DFF844B1DFF83CA1504C28 -:10475000504DB846A9F11409772877D00FDCA0F1A5 -:10476000640013283CD2DFE800F0F5EFEEEDECEB4F -:10477000EAE9E8E7E6E5E4E3E2E1E0DFDE00454917 -:104780000127CE28497871D014DCC92842D008DC32 -:1047900078286CD0A0286BD0A4286AD0C8281FD154 -:1047A00024E0CA2853D0CB2864D0CC2863D0CD28AD -:1047B00016D1BAE2D3287BD00ADCCF281FD0D0286C -:1047C00077D04FF00009D12874D0D22808D19BE0CF -:1047D000EF2818D0F0286ED0FA286DD0FE286CD0C3 -:1047E0000020FFF7D6FEBDE8F05FD5E600242A4D95 -:1047F000FFF7A0FE25F81400641C082CF8D3002055 -:10480000FFF7C4FEEFE7FFF795FE6085FFF792FE26 -:104810002085F4E7FFF787FEE872FFF784FE1F4963 -:104820000870FFF791FE1E4C2060FFF78DFE606060 -:10483000FFF780FE1B490880FFF77CFE1A490880BD -:104840001A48017841F002010170D8E7F1E1002334 -:10485000FFF769FEE5186870FFF765FEE872FFF77D -:1048600062FE5B1C68750A2BF2D3C8E7A2E21BE16B -:10487000CEE2DFE222E030E0BC0100206809002047 -:10488000F00C002000380140700400205C00002083 -:1048900050080020FC0A00205C010020CB00002012 -:1048A000440100207E010020800100206C010020D6 -:1048B0004CE034E201E2A1E280E281E200254F46D1 -:1048C00007E000BFFFF736FE795D6D1C04EB410188 -:1048D000C88730788542F5D391E7FFF724FE04F8C6 -:1048E0001F0FFFF720FE6070FFF71DFE2071FFF71E -:1048F0001AFE6071FFF717FEA071FFF714FEA0709B -:10490000FFF711FEE0707AE700299ED1FFF70BFE5A -:104910008AF8DC03022801D98AF8DC930021002000 -:10492000FCF71DFE6BE7A3E166E17FE194E18EE118 -:1049300069E14FE136E127E11DE104E1F1E0D3E077 -:10494000C4E0B6E0A2E06EE014E003E0FFF7F2FDA1 -:10495000F949EFE10720FFF719FEDC20FFF7D7FD4B -:104960009AF80500FFF7D3FD0020FFF7D0FD4FF0C8 -:1049700000405CE20B20FFF709FEF048008800B21F -:10498000FFF7ADFD02F05DFB00B2FFF7A8FD0220CE -:10499000FCF7BCFF04460420FCF7B8FF44EA4004DF -:1049A0000820FCF7B3FF44EA80042020FCF7AEFFA8 -:1049B00044EAC0041020FCF7A9FF44EA0010FFF706 -:1049C0008EFD00200246347824E000BF19F8021062 -:1049D0000D291AD2DFE801F01707090D190B0F197D -:1049E000191911131500E97811E029790FE0697997 -:1049F0000DE0A9790BE0697A09E0E97907E0297A05 -:104A000005E0A97A03E0697801E0CD4B595C91405B -:104A10000843521CA242D9D3FFF736FD9AF8DC03B3 -:104A2000FFF775FDDFE61220FFF7B0FDC548C64D64 -:104A30004FF000040088B0F5806F0BD935F91400F1 -:104A4000C11700EB5170C010FFF749FD641C032C27 -:104A5000F4D306E035F91400FFF741FD641C032C84 -:104A6000F8D3BA4D002400BF35F91400FFF737FD25 -:104A7000641C032CF8D3B64D002400BF35F9140094 -:104A8000FFF72DFD641C032CF8D3ACE61020FFF7D4 -:104A90007DFDB04D002400BF35F91400FFF71FFD68 -:104AA000641C082CF8D39EE63821AB48FFF777FD4D -:104AB00099E61020FFF76AFDA84D002435F914008F -:104AC000FFF70DFD641C082CF8D38CE61020FFF7CF -:104AD0005DFDA34D002400BF35F91400FFF7FFFC76 -:104AE000641C082CF8D37EE61020FFF74FFDE87A0F -:104AF000FFF70DFD9B480078FFF709FD9A4C2068F1 -:104B0000FFF7C2FC6068FFF7BFFC9848008800B25E -:104B1000FFF7E5FC9648008800B2FFF7E0FC9548F7 -:104B20003DE00520FFF732FD9348008800B2FFF713 -:104B3000D6FC9248B0F90000FFF7D1FC904800780D -:104B400000F001006CE70820FFF720FD8D4D0024E8 -:104B500035F91400FFF7C3FC641C022CF8D38A4813 -:104B6000B0F90000FFF7BBFC8848B0F9000000BFB7 -:104B7000FFF7B5FC37E60620FFF708FD844800681C -:104B8000FFF782FC83480AE00520FFF7FFFC82481C -:104B90000078FFF7BCFC0020FFF7A1FC7F480088ED -:104BA00000B2E5E70720FFF7F1FC14F81F0FFFF74D -:104BB000AEFC6078FFF7ABFC2079FFF7A8FC6079CA -:104BC000FFF7A5FCA079FFF7A2FCA078FFF79FFCF8 -:104BD000E07825E71E20FFF7D9FC002566197078DC -:104BE000FFF795FCF07AFFF792FC707DFFF78FFCE2 -:104BF0006D1C0A2DF2D3F6E52F20FFF7C7FC68489D -:104C0000FFF7DEFCEFE54806000EFFF7BFFC0025CE -:104C10004F4607E0785D04EB4000B0F93E00FFF737 -:104C20005EFC6D1C30788542F4D3DCE5FFF7D3FCE5 -:104C3000D9E50846FFF7AAFC00244D4603E0285DAD -:104C4000FFF765FC641C30788442F8D3CBE5022082 -:104C5000FFF79CFC00208BE70820FFF797FC00245F -:104C6000601CC0B2FFF753FC641C082CF8D3BAE5F3 -:104C7000FFF759FC04461220FFF788FC14B1102CF2 -:104C800002D005E0474800E04748D0E90070804680 -:104C90002046FFF73CFC3846FFF7F6FB4046FFF79F -:104CA000F3FBDBF80000FFF7EFFB0020FFF717FC3A -:104CB0000020FFF714FC0020B2E6FFF734FC80462A -:104CC000FFF742FC0646FFF73FFC8446FFF73CFC3B -:104CD0000446FFF72FFCFFF72DFCFFF724FCB8F18B -:104CE000000F11D0B8F1100F7FF493AD2E49C1E938 -:104CF000006C0CB1CBF800402C4A0220091D10704A -:104D0000294801F04DF87AE52648002CC0E9006CEE -:104D100085F807902F73F6D0CBF800406FE5002997 -:104D2000F1D10120FCF7E3FD69E50029EBD1204931 -:104D30004FF4C870088062E5BA010020CC00002062 -:104D40002E0B00208A0100207C000020640000203F -:104D500082000020AE000020BC0800207C0900205A -:104D60005C010020CB000020440100207E010020D7 -:104D7000800100206E0100207A0100207C010020CB -:104D80006C01002038000020B8010020DE00002067 -:104D90005800002030000020CA000020E20000205F -:104DA0006CC500084C01002054010020C100002007 -:104DB000860100200029A6D1AF7320E50121AEE5D0 -:104DC0000820FFF7E3FB6A486B4A6C4D01686948AD -:104DD0001268B1FBF0F1B2FBF0F000EB4002C2EB65 -:104DE000C01001EBC000E8805FF0000435F914004A -:104DF000FFF775FB641C042CF8D3F4E40420FFF7E0 -:104E0000C5FBB4F92A00FFF76AFBB4F92800AFE646 -:104E10000C20FFF7BBFB5A480068FFF735FB5848EA -:104E2000001D0068FFF730FB554808300068FFF7A9 -:104E30002BFBD8E4534D287807EB8000C0B2FFF776 -:104E4000A5FB2878FFF763FB00244F4E4F4FDFF898 -:104E50004081DFF840910EE0305DFFF758FB385D90 -:104E6000FFF755FB18F80400FFF751FB19F8040091 -:104E7000FFF74DFB641C28788442EDD3B3E470B592 -:104E8000454C464D0026A07810B3BDE87040FCF7B5 -:104E90006CB8286803F0AAFFE17951B101291CD050 -:104EA00002291FD0032923D004292CD0052942D15F -:104EB0002FE0242803D00021E17149B901E001214C -:104EC000FAE7232802D0522835D102E0FCF74DF84A -:104ED00031E0012002F0CDFD2DE04D2804D102206B -:104EE000E07128E03C2801D00020F9E70320F7E733 -:104EF00040281FD8A0716671667220720420E0718C -:104F00000120607017E0A072217A414021720520D3 -:104F1000E6E76179A279914207D2227A4240227271 -:104F20001F4A5054491C617105E0217A814201D128 -:104F3000FFF700FCE671286803F055FF0028A8D1B0 -:104F4000A078002812D1A86803F04DFF00280DD1E9 -:104F50004FF40060FCF7EFFC002807D011484078C0 -:104F6000002803D0BDE8704001F0D1B970BD000049 -:104F70000C04002040420F001004002072010020A9 -:104F8000E8F7FF1F82010020420B0020520B002097 -:104F9000620B0020720B0020BC0100206809002079 -:104FA000F00C0020FC0A002070B50446FC4DFD4EBC -:104FB0000AE0686803F012FF96F81801012802D190 -:104FC000042002F089FC641C21780029F1D1686872 -:104FD00003F012FF0028FAD0BDE870401E2002F056 -:104FE0007BBC44F25061884201DDA0EB4100EE49F8 -:104FF000884202DA48F6A041084470472DE9F0479C -:1050000006465068994614460D46301A05F06EFA69 -:10501000296805F097F82061A768394605F056F829 -:105020008046E24890F8DC0005F069FAE04905F0B6 -:1050300053F801464FF07E5005F084F82D6829465C -:1050400004F0F2FF0146284605F07CF8414605F0E1 -:1050500043F8394604F0E8FF2061C4E901600146E5 -:10506000D9F8080005F038F8BDE8F04705F06ABA4D -:105070002DE9F0411D4614460E4605F037FA6968E1 -:1050800005F02AF8316805F027F8216804F0CCFF14 -:105090002060ED680746284605F054FA064685F07C -:1050A000004005F04FFA0546384605F04BFA324607 -:1050B000294601F049FA05F019FA2060BDE8F041EF -:1050C00005F040BA70B5BB4CD4E90D01401AFFF7AA -:1050D00088FF0028D4E90D01A0EB010002DDFFF7F5 -:1050E00080FF02E0FFF77DFF404241F294118842C9 -:1050F00028DAD4E90D01401A05F0F8F9AE4904F0B8 -:10510000EBFF0646E06B05F0FAF90546304606F07F -:10511000F3F9294604F0E0FF05F014FA00B240F676 -:10512000B8322082514201F00FFA616B084448F610 -:10513000A0416064884200DD401A002800DA08447B -:10514000606470BD606BFBE72DE9FE4F0546FFF71D -:10515000B9FF984842F22831406C081A05F0C6F9A8 -:10516000954904F0B9FF044605F06CFF0190204614 -:1051700006F0C2F900900024284605F0B7F9DFF8E0 -:1051800034A2DFF83892DFF838B20AF1300A029020 -:1051900088481A3030F9140005F0A8F905465DF882 -:1051A0002410029804F098FF294604F08FFF05F0C0 -:1051B000C9F900B24FF47A7255462AF814005142E8 -:1051C00001F0C2F97D4900B225F81400603900F001 -:1051D0000EFE04EB8406794B7649074609EB8602FE -:1051E000904635F91400603B2831FFF741FF734BBF -:1051F00070490744424635F91400603B2831FFF7F7 -:10520000FDFE384400B240F6B8325D462BF814007B -:10521000514201F099F925F81400684859F8261010 -:105220002838641C40F82610022CB1DBBDE8FE8F44 -:105230002DE9F05F5F4E0024DFF880915036DFF8F3 -:1052400080B1A6F1360AA9F1280900BF5B4956F8DA -:105250002400803900F0CBFD3AF81410554F401A65 -:105260003037564900B227F81400703900F0BFFDFE -:10527000054637F9140056F8241004EB8407084457 -:105280004E4B4C4909EB87029046703B2831FFF7A3 -:10529000EFFE2844494B47492BF814005D4642462F -:1052A00056F82400703B2831FFF7A8FE4FF4FA624D -:1052B000514201F049F93AF914103131622900D80C -:1052C000002035F8141040F6B832084400B225F832 -:1052D0001400514201F038F925F81400374859F804 -:1052E0002710641C40F82710022CAFDBBDE8F09FAC -:1052F00070B50546086819681446401A05F0F6F8B6 -:105300002C49C96A04F0E8FE05F01CF90146294859 -:105310005030416029682268891A016070BD2DE90A -:10532000F0410F46DDE90685116800681E46081A3F -:1053300005F0DCF8044630683968401A05F0D6F804 -:105340001C49C96A04F0C8FE0646014604F0C4FEC2 -:1053500007462146084604F0BFFE394604F064FEC5 -:1053600006F090F9174904F0B7FE05F004F9C8F803 -:10537000000084F00040314605F03AFD124904F087 -:10538000ABFE124904F050FE05F0DCF8286000285E -:1053900003DA48F6A04108442860BDE8F081000027 -:1053A0006809002070040020B0B9FFFF50080020F9 -:1053B000DB0FC940C4020020D3023739C00D0020E2 -:1053C000200100202C7D8E3FA00CB34500A00C4690 -:1053D0002DE9F047FB48FA4CD0E90056617804F11A -:1053E0004809B1B34FF07E50A16A04F0ABFE82468B -:1053F000D9F80400301A05F079F8E16A04F06CFE7F -:10540000514604F069FE05F09DF807B2D9F8000096 -:1054100004F11A08281A05F069F8514604F05CFEF8 -:1054200005F090F801B204F12400B0F902203A44EA -:1054300002EBD27242F34F02A8F80220B0F900301A -:10544000194401EBD17141F34F01A8F800104280DB -:10545000018001206070C9E90056BDE8F08710B5F1 -:10546000044605F043F8002C01DC80F00040D649EA -:1054700004F068FED54904F02FFE05F0E3FDD049A5 -:10548000C86210BD10B5D24CE07A002811D0D148C6 -:10549000007805280DD3CB49CF4A086810604968C9 -:1054A0005160FFF7DCFFCD48C549008888820120A4 -:1054B000207310BD2DE9F043C149C948C44B8E7A11 -:1054C000012502790024062E29D004DC022E09D001 -:1054D000032E04D116E0122E33D0302E3DD0002002 -:1054E000BDE8F083B74A4668566086681660006972 -:1054F0004FF47A7290FBF2F0BA4A1080C87AD872F0 -:105500004D7350E04079C00701D0032A03D000203A -:10551000C87210B147E00120FAE7DC7243E0C27ABA -:10552000D20702D0827A032A03D00022CA7212B1B3 -:1055300002E00122FAE7DC72A64A90F82F00107010 -:1055400031E0A94B828A1A80806942F2107290FB86 -:10555000F2F0A64A10808D7325E0A54B102A1A7030 -:1055600001D910221A700022A24EA34FDFF88CC27C -:10557000DFF88C921D7814E002EB420300EB83030A -:1055800093F8088006F8028093F8098007F80280F3 -:1055900093F80B800CF8028093F80C8009F80280D5 -:1055A000521CAA42E8DB487B8A7B104098D04C739F -:1055B0008C73012094E72DE9F047814900240A46C5 -:1055C00091F8098092F807C0157A0CEB0003D78A8E -:1055D0004FF00109DEB22246B8F1090F55D2DFE8DB -:1055E00008F0080510161D2434444A00622803D030 -:1055F0004A72B52802D048E0022034E081F80990D0 -:1056000043E003224A720873C87108723DE0042225 -:105610004A72CE7172190A72887236E005224A7295 -:10562000CE7172190A72C8822FE006234B72731969 -:1056300007EB0020CE7180B20B72C882B0F5007FFC -:1056400001D9CA824A720A831FE0CE7172190A72A6 -:105650000A8BC82A01D2624B9854521C90B208831C -:10566000B84212D1072048720FE008234B728445DC -:105670000BD04A7209E04A72854206D1614981F82D -:105680000090FFF717FF00B101242046E5E670B552 -:10569000034600200246054611E02E2C04D1521C80 -:1056A00000290FD054181D559C5C00EB8000400071 -:1056B000A4F13006092E01D830382044521C9C5CDD -:1056C000002CEAD170BD2DE9F04100268046354618 -:1056D0003746044604F0F6FB016800E0641C2078BD -:1056E000085C2028FAD0404609E01EB106EB86028D -:1056F0005206160E10F8012B303E3244D6B2221A52 -:10570000022AF2DC09E01DB105EB85025206150EF6 -:1057100010F8012B303D2A44D5B28442F3D82078CA -:105720002E280ED1641C002007EB87025700227838 -:105730008B5C202B02D1303F1744641C401C042892 -:10574000F2DB31480621454307EBC70000EB0710A9 -:1057500005EB8000B0FBF1F02C494E4300EBC61086 -:105760001BE62DE9F0470027154C05463E464FF055 -:105770000109242815D01A482146E038C9782C2D73 -:1057800013D02A2D11D022460D2D527970D00A2D1A -:105790006ED00F2902D24554491CE170002A68D00E -:1057A000B7E0A670E6702671B3E04654A178B04623 -:1057B000324669B3A279012A4AD0022A70D09EE00B -:1057C000C4020020440100208096184B35FA8E3C1C -:1057D000FC0A0020CB0000204C010020B801002072 -:1057E000100E00207E010020800100206E010020AC -:1057F00082010020420B0020520B0020620B00208F -:10580000720B00207001002040420F002D3101007A -:10581000FFE7A2710178472971D1417850296ED1F3 -:105820008178472902D0522909D068E0C1784729F8 -:1058300065D10079412862D184F806905FE0C17893 -:105840004D295CD10079432859D10220A07156E03E -:10585000FE4E02290ED0032910D0042915D00529A7 -:1058600017D006291DD0072924D0092929D046E0C0 -:105870005CE04BE0F648FFF726FF04E00078532891 -:105880003DD130684042306039E0F148FFF71BFFFE -:1058900004E00078572832D17068404270602EE0F2 -:1058A00015E00078302801D9012000E00020E94906 -:1058B000C87224E00021E648FFF7E9FEE6490870D7 -:1058C0001DE00021E248FFF7E2FEE44916E0072967 -:1058D00002D008290DD012E00121DD48FFF7D7FEE4 -:1058E00041F2184148434FF47A71B0FBF1F0DC49C2 -:1058F00004E00121D648FFF7CAFEDA490880A07803 -:10590000401CA07084F803802A2D0CD020796840B8 -:105910002071A07910B1D44A82F800900FB101280B -:1059200000D0002099E584F80590F2E772B1804636 -:10593000007800F08AFA050198F8010000F085FA75 -:1059400028442179C0B2884200D101276671E0E77E -:105950002DE9FF5FC549C0B24FF0000B91F8181157 -:1059600019B1012904D002297ED1FFF7FAFE01E026 -:10597000FFF721FE002877D0BD480178012910D01B -:1059800001210170B348C17A00296DD0B24909786C -:10599000052969D38246407830B19AF80C1031B1AC -:1059A00008E080F800B0EDE78AF80CB002E008B13A -:1059B000FFF768FDAF4805218E460278A34C521CC4 -:1059C000B2FBF1F301FB1322AB490270002091F905 -:1059D000009000BFA74954F820306831A54D41F828 -:1059E0002030A649783593FBF1F145F82010A44DFD -:1059F00000EB80074D4303EBC51342F2107593FB98 -:105A0000F5F5AEB29B4D403525F81060904DB83598 -:105A100005EB8707974D57F822C0603555F8208071 -:105A200047F82230A8EB0C0C634445F8203093FB78 -:105A3000FEF3934D6D42694303EBC1138D49703101 -:105A4000B9F1010F41F8203005D1B61EB6F5797FC6 -:105A500001D844F82030401C0228BBDB01F02EFFA7 -:105A6000844D296A401A00E073E004F048FD85493E -:105A700004F068FBA86201F021FF2862A86A4FF0D9 -:105A80007E51884200DB0846A86203A902A87E4B2B -:105A9000CDE900011A1F211D6C48FFF740FC029858 -:105AA0006426B0FBF6F07949794A57460880039896 -:105AB00090FBF6F010809AF80C0018B9A1F800B02D -:105AC000A2F800B0FFF784FC387A10B9F879002802 -:105AD0003FD06849343101F1080000F11C07CDE9DD -:105AE00000013B1D3A46211D5848FFF718FC231DB5 -:105AF000564A391D3846FFF7FBFB5F4C94F900000E -:105B0000012828D0022824D1624F0121B7F9E200F0 -:105B100000F078F9FFF718FB97F8DE005E4A18B13D -:105B2000686C90FBF6F01080B7F8DA00E96B8842F9 -:105B30000BD2D5E90D01401AFFF753FA002800DC1B -:105B4000404242F21071884203DD01202070A88A91 -:105B50001080BDE8FF9FFFF76BFBFAE72DE9F047E8 -:105B60004C4C607904F0CBFCDFF83091494604F0EE -:105B7000E9FA374D10352860E07B04F0C0FC494657 -:105B800004F0E0FA464EEE606860A07904F0B7FCDD -:105B9000444F394604F0D6FA10352860207C04F0D2 -:105BA000AEFC494604F0CEFA6860A07E04F0A7FC83 -:105BB000DFF8D080414604F0C5FAC5E90206E07975 -:105BC00004F09DFC394604F0BDFA10352860607C75 -:105BD00004F095FC494604F0B5FA6860E07E04F0F4 -:105BE0008EFC414604F0AEFAC5E9020635E42DE923 -:105BF000F05F07460025FFF7B1FF03233A462A4925 -:105C00002A4802F021F82A4CDFF86080606098F89A -:105C10001801012802D0022856D0A8B1DFF89490CC -:105C200000264FF4964B09F1140A00BF59F82610CC -:105C3000606803F0DEF8606803F0D3F80746584563 -:105C400044D0B7F5164F37E04EE000004401002085 -:105C5000300D0020FC0A0020CB0000207E01002037 -:105C6000800100206E0100207001002070040020DF -:105C70006C010020C4020020C10000208096980022 -:105C8000D3CEFEFF00007A44500100207A010020AC -:105C90007C01002050080020BA0100200000C8420A -:105CA0000000FA440000204151590008004400401F -:105CB000680900209CC500080BD0B7F5614F1ED0C5 -:105CC000B7F5E13F0AD11EE00425A7E75AF8250001 -:105CD00002E00AEB85004068FFF766F90A2001F050 -:105CE000FBFD761C052EA1DB3946606803F081F8C8 -:105CF00098F8180101280AD0022815D01AE00AEBFA -:105D000085008068E8E70AEB8500C068E4E7564E46 -:105D100000256068715D03F061F8042001F0DCFD8E -:105D20006D1C8C2DF5D305E050A0FFF73DF95CA06C -:105D3000FFF73AF94FF47A7001F0CEFD5D48007834 -:105D4000002804D0BDE8F05F2020FBF7E7BDBDE8E8 -:105D5000F09F2DE9F05FDFF86CA10024564FDFF8CB -:105D60005C81DFF85C9125460AF1280B27F8145076 -:105D700028F8145004EB840629F814500AEB860026 -:105D800000F06CF80BEB860000F068F84D485030DE -:105D900000EB860000F062F8641C022CE6DBD6E71C -:105DA0007CB5494C02682260096861600068FFF7B1 -:105DB00056FBA4F1240101F10800444ECDE9000195 -:105DC000231D2246311D3046FFF7A9FAA4F15805DC -:105DD000331D686B68643246211D2046FFF788FA40 -:105DE000686BA8633A48B0F8E00068827CBD10B5E3 -:105DF0000C4604F07BFB216804F06EF9BDE810400E -:105E000004F0A0BB70B5304C583CE26B21B1B0EB54 -:105E1000520F0BD3500809E0904200D310462C4992 -:105E200000B2B1F8E010814200DB0846B4F912502C -:105E300000B2A84208DD2749A06A04F04DF904F039 -:105E400081FB284400B2608270BD3038C0B209289E -:105E500001D9C01FC0B200F00F00704700210160DF -:105E60004160816070470000D0C5000824504D5447 -:105E70004B3331342C302C312C302C312C302C3015 -:105E80002C302C302C302C302C302C302C302C3032 -:105E90002C302C302C302C302C302A32380D0A008B -:105EA00024504D544B3232302C3230302A32430D94 -:105EB0000A000000700100200401002024010020DD -:105EC00020010020700D00201C0300204401002050 -:105ED000500800200000C842F0B5404A404C1178FC -:105EE000E9B192F805C01779032104F11C035E188B -:105EF00016F8015CFD4005F00F05072D09D213F8D7 -:105F000001E016F8016C06EA0C060EEB062644F8D2 -:105F10002560891CC9B21029E9D3002111703149CB -:105F200007280ED2937863B151782E4A104490F826 -:105F3000060149B154F820004FF4777101EB50008D -:105F400006E0B1F81001F0BD34F8200000F57770DC -:105F500080B2F0BD70B5214C01260546A67001F057 -:105F600093FCA168421AC4E9020241F28830002180 -:105F7000824200D9E1701A4AE0781C3215540F2889 -:105F800002D0401CE07070BD17482670018070BDC3 -:105F900010B504461348114990F80E21032032B180 -:105FA000012A09D1087107204871012003E002226B -:105FB0000A7148710020487001234FF4E1320B4907 -:105FC0000B4801F041FE0B49002CC86001D00A4883 -:105FD000206010BD01480078704700004403002095 -:105FE000D80E002070040020CE000020555F00086D -:105FF0000044004068090020D95E000870B57C4C60 -:1060000006460125207880B901F058FCA16832319C -:10601000884207D32570012001F069FC01F04EFC95 -:10602000A06070BD20780028FBD001F047FCA1687B -:1060300031448842F5D30020207001F058FC01F073 -:106040003DFC6C49A060087808B1401E087065707E -:1060500070BDF8B5664D8DF800008DF801108DF813 -:1060600002208DF80330A8791DF8001044292DD0A6 -:106070004C2929D04D2925D04E292AD0322400265A -:10608000032806D274B12046FFF7B8FFA879032889 -:1060900008D301F013FCA968001B884202D95548B7 -:1060A000AE7106706878012801D0002C09D1A8795A -:1060B000032801D2401CA8716E702E70002001F0E0 -:1060C00016FCF8BD6424DAE7C824D8E74FF4FA6474 -:1060D000D5E70024D3E72DE9F047DFF81CA10546FA -:1060E000434C9AF80D004FF00109002610B184F8D6 -:1060F000029000E0A6704FF40070FBF71CFC3F4FCD -:1061000018B33F493F484FF0020C91F8AC30B0F95A -:10611000000003EB830282420FDA97F80180B8F1A6 -:10612000000F0AD084F8049091F8AD10194401EBE7 -:106130008101814201DA84F804C0824203DA79786D -:1061400009B984F804C000B926712020FBF7DEFBF2 -:1061500040B19AF80A1011B99AF80B0008B1F87A10 -:10616000A8B1E6702079022814D0012817D0E07871 -:10617000012817D0A078012817D0042D19D0022D9E -:106180001ED0012D1ED0607901281ED022E084F897 -:106190000390E7E74E22442311464C200DE04D23A7 -:1061A0004C2208E04D234E2201E04D23532253217F -:1061B00002E044234D224D215320BDE8F04748E73B -:1061C000442305E044234E22F5E7787810B14E23AE -:1061D0004D22ECE70748007818B1BDE8F0473220BF -:1061E0000CE72670BDE8F047002001F080BB0000FE -:1061F00054030020C00000202E0B0020FC0A0020C9 -:1062000050080020CE00002010B5C24C5E28A268C5 -:1062100007D05D280CD001461046BDE8104002F0C2 -:10622000DDBD5D21104602F0D9FD3E21A068F4E7F6 -:106230005D21104602F0D2FD3D21A068EDE72DE979 -:10624000F041132000F01EF9B34C2068002800DC58 -:106250004042B24D90FBF5F000B200F025F91B2052 -:1062600000F010F92068002800DC40420A2690FB6C -:10627000F6F042F2107790FBF7F107FB110000B245 -:1062800000F012F9232000F0FDF82068002801DA60 -:10629000532000E04E2000F007F9122000F0F2F841 -:1062A0006068002800DC404290FBF5F000B200F08E -:1062B000FBF81A2000F0E6F86068002800DC404295 -:1062C00090FBF6F090FBF7F107FB110000B200F035 -:1062D000EBF8222000F0D6F86068002801DA572099 -:1062E00000E04520BDE8F04100F0DEB870B58C4D0F -:1062F00004462878844209D014B14FF4165002E0C5 -:106300008848D0F82001FEF7A2F92C7070BD2DE965 -:10631000F04701F0D3FA824D6968401A7D287DD399 -:1063200001F0CCFA686068787F4F401CDFF8FC8190 -:10633000DFF8FC916870002404F12400C0B200F082 -:10634000A1F8388804F0DBF8064638F9140004F0A8 -:10635000CDF8314603F0F6FE494603F0BDFE04F0E9 -:10636000F1F800B200F0A0F8641C032CE4DB00F0AC -:1063700096F868784FF06404800724D1102000F06C -:1063800081F86C4E306890FBF4F000B200F08CF8AD -:10639000212000F077F8306890FBF4F104FB110045 -:1063A00000B200F081F8142000F06CF86248B0F9F7 -:1063B000000000F079F81C2000F064F8002000F0E4 -:1063C00073F800F06CF86878400735D1022000F0CF -:1063D00059F85A484FF00A08B0F9001091FBF8F04C -:1063E00000B200F061F80220FBF7A5FAE0B100F07E -:1063F00065F853486E21007848431521B0FBF1F64B -:106400003A2000F03FF8B6FBF4F738B200F04CF851 -:106410003B2000F037F804FB176000E030E0401D3F -:10642000B0FBF8F000F040F82020FBF76FFA08B15D -:10643000FFF705FF00F033F86878282820D1002006 -:10644000687001F03BFA4FF47A71B0FBF1F53C242F -:10645000B5FBF4F6B6FBF4F004FB1067172000F070 -:1064600011F8380200B200F01FF8182000F00AF806 -:1064700004FB165000F018F8BDE8F04700F00FB824 -:10648000BDE8F08770B5234C05465E21A06802F098 -:10649000A5FC2946A068BDE8704002F09FBC1D48DD -:1064A0005E21806802F09ABC10B50446C0B2FFF7C6 -:1064B000ABFEC4F30720BDE81040A5E670B5204848 -:1064C000204E40F6340200783178154DB0FBF1F0E3 -:1064D00050432A22B0FBF2F06A88B2FBF1F301FBD1 -:1064E00013214FF6FF7202EA011141EA0024C0F3C2 -:1064F000032004430620FFF7C5FF20B2FFF7D4FFB7 -:1065000068883178401C80B2B0FBF1F201FB1200C8 -:10651000688070BD6809002044010020A086010049 -:1065200060030020700400208A0100207C0000200D -:1065300000007A4424000020B8010020E000002080 -:10654000CA00002071010020884201DA0846704725 -:106550009042FCDD1046704743490844434990F897 -:10656000060151F820004FF4777101EB500080B222 -:10657000704710B5044601F087F93D490246486866 -:10658000131A0020B3F57A6F00D948704A604A7830 -:106590000AB90F2C0AD1087032B1344B203313449E -:1065A000182A03F8014C02D0521C4A7010BD2F4A21 -:1065B0002032D27D0AB901220A70487010BD10B590 -:1065C000044629480021294BB0F810014200A2F5E9 -:1065D000F76200BF43F82120491C0829FADB012398 -:1065E000244A2549254801F02FFB2549002CC86085 -:1065F00001D02448206010BD1D4B10B5187840B163 -:106600001A484FF000022030817DC908C90702D026 -:106610001A70002010BD1C49401C0A8030F8011C73 -:10662000C1F30A0411490C600488C4F3CA044C6025 -:106630000468C4F38A348C60B0F80340C4F34A049D -:10664000CC608488C4F30A140C614468C4F3CA346F -:106650004C61B0F80740C4F38A048C61008940099A -:10666000C8611A70012010BD70040020040F0020C2 -:1066700068030020A0860100736500080044004004 -:106680006809002059650008CE0000202DE9F0417E -:106690000646007890B008B1012500E00025DFF83B -:1066A000D880404602F06CFD344800900024344805 -:1066B000CDE90104012725B10220CDE903048020A2 -:1066C00002E0CDE90374002005904FF4807006903D -:1066D00080000790202008900002CDE90904694657 -:1066E000404602F0BAFD0121404602F0E0FD8DF87F -:1066F00030500B948DF831704FF46020CDE90D04CB -:106700000DB1022000E001201C4C8DF83C004C3CF7 -:106710000BA9204602F0A0FC0323012204212046FD -:1067200002F0EFFC2DB1317803230222204602F063 -:10673000E8FC0121204602F0B8FC0121204602F0CD -:10674000AAFC204602F0BBFC204602F0BDFC00285B -:10675000FAD1204602F0BFFC204602F0C1FC00281E -:10676000FAD10121204602F0C2FC10B0BDE8F08150 -:10677000034931F810007047080002404C240140E2 -:10678000700300202DE9FF47DFF86C81814698F8FF -:106790000000D0B300273E463D463C46641CE4B2B0 -:1067A00002AB08223221532000F015FC9DF80800AE -:1067B0009DF80910202C00EB012000B207449DF841 -:1067C0000A009DF80B1000EB012000B206449DF872 -:1067D0000C009DF80D1000EB012000B205449DF85F -:1067E0000F0000F07F0001D20028D7D197FBF4F012 -:1067F000ADF8000096FBF4F0ADF8020095FBF4F064 -:10680000ADF8040088F802401EE0FFE702AB062264 -:106810003221532000F0DFFB9DF808009DF809109D -:1068200000EB0120ADF800009DF80A009DF80B1068 -:1068300000EB0120ADF802009DF80C009DF80D1052 -:1068400000EB0120ADF8040098F8012049466846A5 -:1068500001F018F9BDE8FF8770B5274D04464FF0E9 -:10686000080228784FF02D0100284FF053000ED079 -:1068700000F0ABFB0A223121532000F0A6FB0C22D2 -:106880002C21532000F0A1FB9022382108E000F0D9 -:106890009CFB0A223121532000F097FB0A222C2175 -:1068A000532000F092FB154940F20910002C08809B -:1068B00000D06C7070BD38B5054600208DF8000022 -:1068C0000F480C460F49006888420AD06B460122E7 -:1068D0000021532000F07FFB18B19DF80000E5284F -:1068E00001D0002038BD044928780870064820608F -:1068F00006486060012038BD740300208A01002032 -:1069000010040020001BB7005968000885670008C4 -:1069100010B54FF48044204602F02EFD012805D129 -:10692000204602F023FD02490120087010BD00003E -:106930007803002070B50D46B549B64A06468888EA -:106940005389B2F91440C01A13895843B2F912306E -:10695000C013DB02044493FBF4F31844D06100EB52 -:106960008000082202EB40000411886800F0D0F893 -:1069700006B13060002D00D02C6070BD38B5A44C3D -:10698000207810B96088401C60806B460322F62195 -:10699000772000F020FB9DF800009DF80110000416 -:1069A00040EA01209DF8021008439A49B1F92010ED -:1069B000C1F10801C840A06038BD9648342190F864 -:1069C000200001EB80109249C2B200200870F4212F -:1069D000772000F0FABA38B58D4C207810B960886D -:1069E000401C60806B460222F621772000F0F3FA0B -:1069F000BDF8000040BAA08038BD854900202E2295 -:106A00000870F421772000F0E0BA2DE9F043044645 -:106A10008148824985B00068884203D1002005B0D2 -:106A2000BDE8F083DFF8E89199F8010008B1012092 -:106A3000F5E74FF40055ADF80C5002208DF80F002B -:106A40001020774E8DF80E0003A9304601F076FF36 -:106A50006F00ADF80C7004208DF80E0003A93046CD -:106A600001F06CFF35610E21022003F005F90020D2 -:106A70008DF8080008208DF809004FF001080197F3 -:106A800047468DF80A8001A802F03AFC28208DF8CC -:106A900010000F208DF811008DF812008DF8137082 -:106AA00004A802F0A6FA142000F016FF6B4601229B -:106AB000D021772000F08FFA564F9DF80000032177 -:106AC000F8753984552801D07561A7E76B46012216 -:106AD000D121772000F07FFA9DF8000000F00F012F -:106AE00039760009787600F05CF889F8018041F287 -:106AF0007070208046F6781060804A4860604A488E -:106B0000A0604A48E0604A4820614A4860618EE7D8 -:106B100070B54049CA69B1F90E40A2F57A6202FB2C -:106B200002F31D136C43E512B1F90240B1F90460A0 -:106B3000544305EBE424B1F9005004EB850591F8CA -:106B40002040A54056437213B1F90C601B135E43FD -:106B500002EB2642921C9210C98802F50042AD1C3D -:106B60005143C90B4CF25032A0EBA500E240504318 -:106B7000B0F1004F03D24000B0FBF1F002E0B0FBF7 -:106B8000F1F040000112494340F6DE3251432A4AF7 -:106B90000914424301EB224101F6CF6100EB2110C1 -:106BA00070BD00B587B06B461622AA21772000F091 -:106BB00012FABDF8000041BA16480180BDF8021073 -:106BC00049BA4180BDF8041049BA8180BDF8061069 -:106BD00049BAC180BDF8081049BA0181BDF80A1050 -:106BE00049BA4181BDF80C1049BA8181BDF80E1037 -:106BF00049BAC181BDF8101049BA0182BDF812101E -:106C000049BA4182BDF8141049BA818207B000BD6B -:106C100078030020400F002010040020001BB70064 -:106C200000100140FB690008D7690008BB69000833 -:106C30007D6900083569000843E3FFFF38B5044665 -:106C400000208DF800006B4601220A211E2000F072 -:106C5000C2F918B19DF80000482801D0002038BDC5 -:106C60000CB18D480470012038BD7FB5054602ABDC -:106C7000062203211E2000F0AEF9BDF8080040BA3C -:106C800000B203F033FC844C241D216803F024FA85 -:106C900003F058FCADF80000BDF80A0040BA00B29D -:106CA00003F024FCA16803F017FA03F04BFCADF8E5 -:106CB0000400BDF80C0040BA00B203F017FC616894 -:106CC00003F00AFA03F03EFCADF80200201F29464B -:106CD0000278684600F0D6FE7FBD2DE9F0476F4888 -:106CE00000246F49006825468EB02E464FF00108FB -:106CF00088420CD14FF48050ADF8280002208DF866 -:106D00002B0004208DF82A000AA9664808E066498D -:106D1000884207D14FF48040ADF828000AA96348A3 -:106D200001F00CFE322000F0D7FD112200211E20C0 -:106D300000F04BF9602201211E2000F046F964208A -:106D400000F0CAFD6846FFF790FFDFF858A1DFF8B2 -:106D5000609100270AF10C0A012202211E2000F096 -:106D600034F9322000F0B8FD6846FFF77EFFBDF928 -:106D70000210BDF90400BDF900200D44144406447E -:106D8000814201DA0B4600E00346934201DD1046E2 -:106D900002E0814200DA0846484502DC4FF0000874 -:106DA00008E0DAF8001081F01001CAF800107F1C2A -:106DB0000A2FD1DB122200211E2000F006F9002745 -:106DC000012202211E2000F000F9322000F084FD93 -:106DD0006846FFF74AFFBDF90020BDF90210BDF972 -:106DE0000400A41A6D1A361A814201DA0B4600E03B -:106DF0000346934201DD104602E0814200DA084674 -:106E0000484502DC4FF0000808E0DAF8001081F095 -:106E10001001CAF800107F1C0A2FD1DB204603F0B6 -:106E200065FB244F0146384603F08CF91A4C20F0DC -:106E30000040241D2060284603F058FB01463846D8 -:106E400003F080F920F000406060304603F04EFB14 -:106E50000146194803F076F920F00040A060702246 -:106E600000211E2000F0B1F8202201211E2000F098 -:106E7000ACF8002202211E2000F0A7F8642000F0E8 -:106E80002BFDB8F1000F04D14FF07E502060606000 -:106E9000A0600EB0BDE8F08784030020100400203D -:106EA00000127A00000C0140001BB70000100140E6 -:106EB00000F0FFFF00406F4601C05E4630B587B06E -:106EC00005464FF44060ADF8140002208DF817001D -:106ED0001C208DF8160005A9844801F02FFD844C74 -:106EE000E56000F0B1F8E06802F056FA684602F09A -:106EF000BEFA00224FF44071E06802F0DAFA002591 -:106F0000ADF804504BF6FF70ADF806004FF480402A -:106F1000ADF80C00774800900121E06802F0B5FA66 -:106F20006946E06802F04BFA4FF4A06002F05CF8AA -:106F300022208DF810008DF811508DF8125001208C -:106F40008DF8130004A802F054F821208DF81000E9 -:106F50008DF8115004A802F04CF807B030BD70B5A0 -:106F6000634C4FEA400047F230556071A171012037 -:106F700020720021617223616361E27120712170CE -:106F8000E068818889050ED40188C90505D4018887 -:106F90008905FCD4012102F082FA01224FF44071EC -:106FA000E06802F086FA207910B16D1EFBD104E092 -:106FB0001DB1207880F0010070BD6089401C6081A7 -:106FC000E068FFF77BFF002070BD07B502AB012230 -:106FD000FFF7C5FF0EBD70B5454C4FEA400047F2C4 -:106FE00030556071A17100202072012161726361CE -:106FF0002361E27121712070E068818889050ED4D7 -:107000000188C90505D401888905FCD4012102F055 -:1070100046FA01224FF44071E06802F04AFA207902 -:1070200010B16D1EFBD104E01DB1207880F001008D -:1070300070BD6089401C6081E068FFF73FFF002061 -:1070400070BD2B48408970472DE9F84F4FF44067D9 -:10705000ADF800704FF0020A8DF803A01420DFF89D -:107060008CB08DF802006946584601F067FC1F4D50 -:1070700010352F60DFF8749000262C1505F10408F8 -:1070800009F1080902E00A2000F01BFCD9F8000011 -:107090004005F8D5C8F800400A2000F012FC2C602A -:1070A0000A2000F00EFC761CF6B2082EEED34FF448 -:1070B00000694646C8F800900A2000F002FC3460DF -:1070C0000A2000F0FEFB2C600A2000F0FAFBC5F855 -:1070D0000090ADF800708DF803A01C208DF8020020 -:1070E0006946584601F02AFCBDE8F88F000C0140C3 -:1070F00094030020801A060038B51D4CE068818A90 -:10710000009111F4706F01D001212170009911F4E8 -:10711000E06F25D0018B00224FF4806102F0C9F9A5 -:10712000009880051CD4E0680188890518D401887E -:10713000C9050CD50188C905FCD4012102F0C8F9A4 -:10714000E06801888905FCD4FFF7B8FE08E001215A -:1071500002F0BEF900224FF44071E06802F0A9F994 -:10716000E068818A21F4706181820020207138BD3D -:1071700094030020FFF7C0BF2DE9F041864CE06882 -:10718000818A4FF00105C9B2CA074FF0000627D027 -:10719000018821F400610180012102F0A3F9E67069 -:1071A000607A20B1607860B9A079FF2809D0617950 -:1071B0000022E06802F0A5F9A079FF2848D0FF205E -:1071C000C9E06570E079022804D1E068018841F4E3 -:1071D0000061018061790122E06802F092F937E0F4 -:1071E0008A074FF4806745D5BFF3508FE0790128B7 -:1071F00010D1607A70B1607860B10021E06802F06F -:1072000071F9BFF3508FE068018B012102F060F942 -:10721000A57018E0E068008BBFF3508FE07902287A -:1072200008D1607A30B1607820B10021E06802F0C6 -:1072300059F906E0E079032805D1607A18B1607841 -:1072400008B1002200E001223946E06802F031F97D -:1072500094F90310E079401C814209D16670A0784E -:1072600028B100224FF44071E06802F022F9267143 -:10727000BDE8F0814A0753D5A570627A464949783E -:10728000CAB3C9B3E17902291FD9002102F02AF952 -:10729000E06802F033F994F9031062695054491C14 -:1072A000E1700121E06802F013F9A570E06802F0D6 -:1072B00025F994F9031062695054491CE1700122C8 -:1072C0003946E06802F0F5F825E0012102F000F906 -:1072D000E06802F013F994F9031062695054491CF4 -:1072E000E170E06802F00AF994F903106269505401 -:1072F000891CE1700FE000E000E009B9217A31B1AA -:10730000012102F0E5F8E078401CE07003E0012183 -:1073100002F0C5F86570E0680188C905FCD497E7FC -:107320004A061AD502F0EAF894F90310626950543B -:10733000491C48B2E070E179C01C814204D10022AE -:107340003946E06802F0B5F8E17994F9030081422A -:10735000E5D100F10100E0707AE70906DFD594F984 -:1073600003104B1C5AB20BD02369595CE27002F037 -:10737000C3F8E07994F9031088423FF45AAF67E705 -:10738000E270A17902F0B8F8607A00287FF451AF7A -:10739000E0790028F1D05BE794030020FFF7ECBE12 -:1073A000FFF7AABEFFF7E8BE38B504466B460222D7 -:1073B0001B216820FFF70FFEBDF8000043F290315B -:1073C00040BA08444FF48C71B0FBF1F023302080B8 -:1073D00038BD1FB5044602AB06221D216820FFF709 -:1073E000FAFDBDF80800214640BA02B2D01702EB00 -:1073F00090708010ADF80000BDF80A0040BA02B2EB -:10740000D01702EB90708010ADF80200BDF80C00B0 -:1074100040BA02B2D01702EB90708010ADF80400B1 -:107420002F484278684600F02DFB1FBD70B504461A -:10743000192000F051FA002215216820FFF7C5FD40 -:1074400010B9032000F0F4FA254D1621287840F0F9 -:1074500018026820FFF7B9FD002217216820FFF706 -:10746000B4FD01223D216820FFF7AFFD01223E213E -:107470006820FFF7AAFD002C00D06C7070BD70B5BD -:1074800004460D46192000F027FA00221521682035 -:10749000FFF79BFD00281CD0124820601248606056 -:1074A0001248A0601248E0600D48622D12D004DC42 -:1074B0000A2D13D0142D05D10EE0BC2D06D0B5F544 -:1074C000807F01D0032102E0002100E00121017052 -:1074D000012070BD0221FAE70421F8E70521F6E753 -:1074E000AC0300202D740008D3730008A9730008B2 -:1074F00018449231FEB5064614460D46684602F021 -:10750000D5FA0120ADF804000021ADF80050ADF827 -:107510000610ADF80810ADF802406946304602F09A -:1075200015FAFEBD70B51646CA4A02EB0015CA4AE6 -:1075300002EB00140122206801F029FBD4E90101CB -:10754000182200F07BF9217B3246206800F033F9E5 -:10755000A07B18B10121206802F0BAFA012120684D -:1075600002F0ACFA207B30B1042807D008280AD0FA -:107570000C2806D10AE02068343001E02068383059 -:107580002860284670BD20683C30F9E7206840300C -:10759000F6E72DE9F0410546AE480F4600EB05162B -:1075A000AD48B27100EB05142822D4E9010100F0C6 -:1075B00045F9217B00222068FFF79CFF01224FF64E -:1075C000FF71204601F000FB3A462946204601F0B3 -:1075D000C1FA3046BDE8F08170B5A04800240289A8 -:1075E00042810181891A8BB240F68C218B4201D9EC -:1075F000C47070BD9949A3F2EF2540F2DB56984A5A -:10760000C978B5421BD2082919D2924DE035042918 -:1076100025F8113007D2C588AB4204D9012305797A -:107620008B402B43037103790F2B08D10471B2F9FE -:107630000030142B02DD143B138000E01480491C41 -:10764000C170148070BD70B5824A834B02EB00128A -:1076500003EB0013D47918681B7B8CB1518114891A -:107660007C4D091B91819479E03525F81410002494 -:10767000D47122461946FFF73DFF7948048070BD5A -:1076800011810121D171BDE870400222194631E714 -:107690002DE9F0470446714DA1890020E980617908 -:1076A00001B10220617801B1401C6E49DFF8B88158 -:1076B000002651F820704FF47A79BA5D02F00F007D -:1076C00002F0F001FF2A59D0A2781AB1022852D054 -:1076D000032850D0A2790AB182424CD011F0300F69 -:1076E00002D0227802B90021E27832B1627922B95F -:1076F000082801D0092800D1802122792AB1627995 -:107700001AB9021F032A00D88021CA0605D5002213 -:107710005649FFF73EFF082008E08A0608D5AA78F8 -:107720005349FFF736FFA87800F10100A87022E066 -:107730004A0610D52289B8FBF2F189B24A46FFF712 -:10774000F1FE0146434A2878F03242F8201000F159 -:10775000010028700FE009060DD56289B8FBF2F12F -:1077600089B24A46FFF7DEFE0146424A687842F88F -:107770002010401C6870761C0E2E9EDB0020BDE899 -:10778000F087364A1278904205D23A4A303A52F897 -:107790002000006801807047304A5278904204D23D -:1077A000344A52F82000006801807047314940395E -:1077B00031F8100070477FB5064615460C466846FE -:1077C00002F06AF97020ADF800000120ADF8020067 -:1077D0000020ADF804000220ADF80800C001ADF8AB -:1077E0000650ADF80C0074B1042C15D0082C1CD038 -:1077F0000C2C07D16946304601F0F4FF08213046D1 -:1078000002F08FF97FBD6946304601F040FF082144 -:10781000304602F070F97FBD6946304601F06CFFDA -:107820000821304602F06DF97FBD6946304601F00F -:107830009FFF0821304602F06EF97FBD08B5ADF814 -:1078400000108DF8022002218DF80310694601F026 -:1078500075F808BD640F0020D0C60008AE030020F4 -:10786000CE00002094C6000840420F00D9750008E1 -:10787000477600088410002002484168491C416096 -:1078800070470000BC03002010B599484FF0E0237A -:1078900041689A694468A142FAD10368006803EB21 -:1078A0004304C4EBC313C2EBC302B2FBF0F001EB21 -:1078B0004102C2EBC11100EBC10010BD8C48406811 -:1078C000704730B50546FFF7DFFF0446FFF7DCFFE2 -:1078D000001BA842FAD330BD30B504464FF47A7588 -:1078E00002E02846FFF7EDFF641EFAD230BD804962 -:1078F000896808474FF4805108B17E4801E07D480F -:10790000001F016070474FF4805110B17948001F8B -:1079100000E07848016070472DE9F04F8DB01822E3 -:107920007549684602F0FBFA032701F0BCFA012111 -:10793000724801F047FE012144F61D2001F039FE96 -:107940000121084601F02CFE01F057FE4FF6FF70B2 -:10795000ADF8180067484FF0000B8DF81AB006A973 -:10796000143800F0EBFF06A9654800F0E7FF06A910 -:10797000644800F0E3FF6448416841F000714160F1 -:10798000624DDFF88C915A4E2968494501D1614812 -:1079900000E06148B0605A480821103001604FF0A3 -:1079A0001008C0F800800020FFF7A1FFAA460024BD -:1079B0004FEA0D05DAF80010494506D105EBC40081 -:1079C0008179142901D180F8068005EBC401091DD5 -:1079D00055F8340000F0B2FF641CBC42EAD307A89B -:1079E00001F098FD4D490798B0FBF1F030604C482C -:1079F0004FF47A710068B0FBF1F0B0F1807F0CD2E7 -:107A000020F07F414FF0E020491E4161454AF021BE -:107A10001170C0F818B0072101614348FFF74EFA12 -:107A200000F0F7FF6420FFF757FF0DB0BDE8F08FBF -:107A3000334A1021143211600821121F11600446CC -:107A4000151F40F2DB104443286880F010002860C6 -:107A5000286880F008002860A01EFFF73DFF012085 -:107A6000FFF745FF1920FFF737FF0020FFF73FFF23 -:107A7000EAE710B12E492D4808602A492D481739E8 -:107A800008607047092A32D2DFE802F03105091098 -:107A9000161B2024280002880A80428803E04288BE -:107AA0000A80028806E04A8080881FE002885242ED -:107AB0000A8042885242F6E7428852420A8002888F -:107AC000F1E7028852420A8042880CE042880A802C -:107AD000028808E002880A80428803E04288524215 -:107AE0000A80028852424A808088404288807047DB -:107AF000BC03002014080140A4C600080700400091 -:107B0000000C014000100140000001401004002062 -:107B1000001BB70007790008F578000840420F0005 -:107B20000C04002023ED00E000580040EFBEADDE65 -:107B3000F04F00200400FA057CB5DC4C0D46DC4912 -:107B40002160A060A4F53070606100F58070A061D4 -:107B50004FF48070E0602061D6482063D548012151 -:107B600014386063880301F024FD02208DF80300BF -:107B70000002ADF8000018208DF80200CE4EA807D4 -:107B800003D56946304600F0D9FE4FF48060ADF869 -:107B9000000048208DF80200E80703D0694630460F -:107BA00000F0CCFE0E208DF8040001208DF80500B9 -:107BB0008DF806008DF8070001A801F01AFA20469A -:107BC0007CBD2DE9FC41B94C0D464C34B8492160CF -:107BD000A0608020E06040202061A4F58670606194 -:107BE0008030A061B5480121A064480401F0EAFC9E -:107BF00002268DF803600420ADF8000018208DF8EF -:107C00000200AD4FA80703D56946384600F096FE3E -:107C10000820ADF8000048208DF80200E80703D0E6 -:107C20006946384600F08AFE26208DF804000120BF -:107C30008DF805008DF806608DF8070001A801F0A9 -:107C4000D8F92046BDE8FC812DE9F0438946064677 -:107C50009B49002499488FB01D4617468E4204D197 -:107C600019461046FFF768FF05E0864204D1194621 -:107C70001046FFF7A6FF04464FF00008C4F8208026 -:107C8000C4F81C80C4F82880C4F82C90C4F8248060 -:107C9000A6642571A760ADF83080ADF834800B97ED -:107CA000ADF83280ADF83880ADF83680E80702D004 -:107CB0000420ADF83600A80705D5BDF8360040F021 -:107CC0000800ADF836000BA9304601F051FF012144 -:107CD000304601F0A5FF684601F0DCFA301D009047 -:107CE0004FF48050CDE909088020CDF81080CDE90F -:107CF00005084746CDF81C80E80723D0206BD8B193 -:107D0000E068CDE902702020089060690190206B46 -:107D100001F036FA6946206B01F09FFA0121206BD1 -:107D200001F0C5FA01224021304601F09BFF206B93 -:107D300001F0D2FA206405E0012240F225513046DC -:107D400001F078FFA80724D5606BE0B120690390AB -:107D5000102008970290606B01F012FA6946606B80 -:107D600001F07BFA01220221606B01F0ABFA0021E5 -:107D7000606B01F0AFFA606B4760012280213046F2 -:107D800001F070FF05E0012240F22771304601F05A -:107D900051FF0FB02046BDE8F0837FB504460020B8 -:107DA000ADF80400ADF808000091ADF80600ADF89C -:107DB0000C00ADF80A0020790D46C00702D004205F -:107DC000ADF80A002079800705D5BDF80A0040F01B -:107DD0000800ADF80A006946A06C01F0C9FEA56074 -:107DE0007FBD826A81691144426BD160D0E909216B -:107DF00000238A4205D9511A426B5160416A81625F -:107E000004E00269511A426B5160836280F8443089 -:107E1000406B012101F04BBA016B11B14968006C54 -:107E200001E01C3003C8814201D0012070470020CE -:107E30007047416B11B190F844007047243003C87B -:107E4000814201D1012070470020704710B50146E2 -:107E5000036BC268406943B10B6CD21A805C5B1E35 -:107E60000B6401D1CA680A6410BD0B6AC05C5B1C5C -:107E7000B3FBF2F402FB14320A6210BD436A82695A -:107E8000D154416A0269491CB1FBF2F302FB1311A0 -:107E90004162416B19B10968C90706D1A1E7806C3D -:107EA000012240F2277101F0C5BE70476413002023 -:107EB000BCC60008580002400008014000440040D1 -:107EC0000038014010B50B4C4FF4005001F00CFA93 -:107ED0000021606B01F0EBF9D4E90901884204D07C -:107EE0002046BDE81040FFF77CBF012084F8440025 -:107EF00010BD0000641300200C49886C0288120633 -:107F00000ED5D1E909329A420BD08B699A5C8280F6 -:107F1000886A0A69401CB0FBF2F302FB1300886216 -:107F20007047002240F2277101F084BE64130020E4 -:107F300070B5184CA06C0588A90610D58088E16A38 -:107F400009B188470BE0E26961698854E069E1683A -:107F500000F10100B0FBF1F201FB1200E061280624 -:107F60000FD5D4E9091088420CD0A169085CA16C36 -:107F70008880A06A2169401CB0FBF1F201FB12006D -:107F8000A06270BDA06CBDE87040002240F2277175 -:107F900001F050BEB0130020FEB52C4C0125207816 -:107FA00078B1012823D0022820D164208DF8000068 -:107FB00027488DF8015000264078E0B38DF8025034 -:107FC0003CE07A208DF8000022486B460222B0F98E -:107FD0000000FF21C0F1B40000EBD070C0F34700F7 -:107FE0008DF801006D20FEF7BAFF2570FEBD1A4E18 -:107FF00079208DF80000B6F900000A2590FBF5F015 -:108000005A30B4220021FEF79FFA8DF80100B6F92C -:108010000200B42290FBF5F05A300021FEF794FAEA -:108020008DF802006B460322FF216D20FEF797FFBB -:1080300002202070FEBDFFE78DF802606B46032230 -:10804000FF216D20FEF78BFF2670F3E7C8030020A9 -:10805000FC0A0020B8010020380000201FB50446AB -:1080600002AB062243216820FEF7B5FFBDF80800E9 -:10807000214640BA02B2D01702EB90708010ADF8E2 -:108080000000BDF80A0040BA02B2D01702EB9070AF -:108090008010ADF80200BDF80C0040BA02B2D01753 -:1080A00002EB90708010ADF804007C48427868467E -:1080B000FFF7E8FC1FBD38B504464FF40050ADF89B -:1080C000000002208DF8030004208DF8020074489F -:1080D00074490068884202D16946734804E07349D4 -:1080E000884203D16946724800F028FC80226B2147 -:1080F0006820FEF76AFF0520FFF7EEFB002219213A -:108100006820FEF762FF03226B216820FEF75DFF07 -:10811000022237216820FEF758FF604D1A2168209F -:108120002A78FEF752FF18221B216820FEF74DFF28 -:1081300010221C216820FEF748FF002C00D06C7034 -:1081400038BD1FB5044602AB06223B216820FEF76E -:1081500042FFBDF80800214640BAADF80000BDF866 -:108160000A0040BAADF80200BDF80C0040BAADF804 -:1081700004004A4882786846FFF784FC1FBD4749DF -:108180004C4ACB7813B14FF4FF6301E04FF48053B6 -:108190001380002800D0887070472DE9FE4F81467B -:1081A000984692460D462320FFF796FB6B46012228 -:1081B00075216820FEF70FFF002804D09DF800000D -:1081C000682802D00020BDE8FE8F062201AB1146D0 -:1081D0006820FEF700FF9DF809009DF80710C00712 -:1081E000400F01F0010140EA41009DF805102B4CC1 -:1081F00001F0010108434FF001064FF0000704D0E1 -:10820000012833D002280DD02CE06B4601220C212E -:108210006820FEF7E0FE9DF8000010F00F0021D06E -:10822000042823D0E7702449C9F8001023492448C2 -:10823000C9F804102860234868602348E860B8F152 -:10824000000F02D0E17888F800105046BAF1620FB2 -:1082500019D00DDC05281ED00A281AD0BAF1140F47 -:108260000BD114E00520FFF7E3FBDCE7E670DAE76B -:10827000BC2806D0BAF5807F01D0032004E0277027 -:1082800003E0267001E00220207001209BE704201B -:10829000FAE70520F8E70620F6E70000C90300200A -:1082A0001004002000127A00000C0140001BB700EF -:1082B000001001408A0100207F81000843810008EE -:1082C000B78000085D800008194492311FB504464C -:1082D00002AB062201211C20FEF77DFEBDF808003E -:1082E000214640BA40F38D02D01702EB9070801007 -:1082F000ADF80000BDF80A0040BA40F38D02D01777 -:1083000002EB90708010ADF80200BDF80C0040BA8E -:1083100040F38D02D01702EB90708010ADF804008E -:10832000334802786846FFF7ADFB1FBD38B50446F9 -:108330002020ADF8000002208DF8030004208DF805 -:10834000020069462B4800F0F9FA00222A211C207D -:10835000FEF73BFE02220E211C20FEF736FE032212 -:108360000F211C20FEF731FE12222B211C20FEF7CC -:108370002CFE02222C211C20FEF727FE01222D219B -:108380001C20FEF722FE00222E211C20FEF71DFEDF -:1083900005222A211C20FEF718FE17494FF4807091 -:1083A000002C088001D01248047038BD38B504464E -:1083B00000208DF8000011481149006888420CD057 -:1083C0006B4601220D211C20FEF705FE28B19DF809 -:1083D00000002A2803D01A2801D0002038BD0949FE -:1083E00021600949616002494870012038BD0000E0 -:1083F000CD030020000801408A0100201004002065 -:10840000001BB7002D830008CD8200080D4810B571 -:1084100000680D4CA188084203D0FFF735FAA06030 -:108420000AE0FFF731FAA168884205D9401A3B21DA -:1084300090FBF1F061690860E068BDE8104000F071 -:1084400095BF0000080C0140D0030020FFF7DEBFFD -:10845000FFF7DCBFFEB50125334C022110B1012826 -:1084600010D109E04FF4807060804000A080E0608F -:1084700009202070172004E06580A180E16025704C -:10848000072060706088ADF8000010268DF802604B -:10849000264F8DF803106946384600F04FFAA08841 -:1084A000ADF8000004208DF802006946384600F05F -:1084B00045FA2178012001F0DFFBE06800F056FF6B -:1084C000E068019000208DF808008DF809608DF8B3 -:1084D0000A5001A800F014FF94F9010000F01F01F8 -:1084E0008D4040094FF0E02101EB8000C0F80051C1 -:1084F000FFF7E4F93C382061FEBD70B50546FFF793 -:10850000DDF9094C21693C3188420CD3C4E90405EA -:1085100006496088103108600B20FFF7D2F9034943 -:1085200060881431086070BDD0030020000C014049 -:108530001FB5044602AB0622A8216820FEF74BFDBA -:10854000BDF80800214640BA02B2D01702EB907085 -:108550008010ADF80000BDF80A0040BA02B2D01792 -:1085600002EB90708010ADF80200BDF80C0040BA2C -:1085700002B2D01702EB90708010ADF804002648CC -:1085800042786846FFF77EFA1FBD70B50446642046 -:10859000FFF7A2F9F02223216820FEF716FD10B99B -:1085A0000320FFF745FA0520FFF796F91A4D202121 -:1085B000287840F00F026820FEF707FD002C00D05D -:1085C0006C7070BD38B504460D461920FFF784F96C -:1085D0006B4601220F216820FEF7FDFC9DF800008C -:1085E000D32801D0002038BD0C4820600C486060C2 -:1085F0000C48E0600848362D05D04E2D07D05D2D83 -:1086000007D0002100E040210170012038BD802109 -:10861000FAE7C021F8E70000E80300208B85000896 -:1086200031850008DDE9A7312DE9F04FB74C8346CD -:108630008E46608926890102B5484FF0000A4068DD -:10864000421AA6FB027CA0884FEAE2754FEA10416D -:108650004FEA00430AFB02C006FB05064FEAD710AB -:1086600040EA466013EB000941EBE611E6886388B7 -:10867000A6FB02C84FEA53404FEAC3370AFB028306 -:1086800006FB05364FEA1C2343EA0663FB1840EB62 -:108690002620A689A6FB027C0AFB02C206FB052453 -:1086A0004FEAD75242EA44224FF4FA654FEAE454C3 -:1086B000521944F10004A246551B74F1000448DA33 -:1086C000944D5519A5FB05674AF1FF3404FB057766 -:1086D00005FB047C0525A6FB05480CFB058500274A -:1086E00006FB07556F104FEA340CB9EB0C0961EB30 -:1086F0000701A40844EA85741B1B60EBA500864DA6 -:10870000551B7AF1FF3424DA40F2DC555619A6FBEA -:1087100006474AF1000505FB067706FB05750726A7 -:10872000A4FB06C805FB0686002704FB0767B9EB18 -:108730000C0961EB07010B27A4FB07C805FB0785A4 -:10874000002604FB065464104FEA3C055B1B60EBFB -:1087500004006F4CA5680024A5FB036704FB0373AA -:1087600005FB0030740D44EAC0244015B4EB090346 -:1087700060EB0100410441EAD330BBF1000F01D0AE -:10878000CBF80000BEF1000F01D0CEF80020BDE80C -:10879000F08F10B500F072F85D49886010BD5C483C -:1087A000012200784030C1B27720FEF70EBC10B530 -:1087B00000F064F85649486010BD55480122007821 -:1087C0005030C1B27720FEF700BC2DE9FE430546CC -:1087D00052485349006888420FD04FF40054ADF816 -:1087E000004002208DF8030010204E4E8DF802004C -:1087F0006946304600F0A2F874610A20FFF76CF871 -:1088000001AB0122A0217720FEF7E5FB002823D051 -:1088100001221E217720FEF7D8FB4FF42F60FFF7CF -:1088200050F80024DFF8E4802646A02707EB440038 -:10883000C1B202AB022277200296FEF7CCFBBDF854 -:10884000080040BA28F81400641C082CEEDB2F48FE -:1088500000F026F810B10020BDE8FE8342F210704F -:1088600028806880304868603048A8603048E860F8 -:1088700030482861304868610120EDE708B56B4653 -:10888000032200217720FEF7A6FB9DF800009DF84B -:108890000110000440EA01209DF80210084308BDC1 -:1088A000F0B5C289002102F47F4502F00F040123D4 -:1088B000C5810A4630F8126006B10023521C082A0E -:1088C000F8DB4FF0FF36F3B90022D30722F00103A3 -:1088D00002D0C35C594002E0C35A81EA1321082345 -:1088E0000F0401D581F4C05149005B1E002BF7DC59 -:1088F000521C102AE9DB2543C581C1F303308442B1 -:1089000001D10020F0BD3046F0BD0000FC13002076 -:10891000EC03002030F8FFFF24FAFFFF10040020D2 -:10892000001BB70000100140BB870008AF8700089C -:108930009F8700089387000829860008F0B5002368 -:108940004FF0010C0A880CFA03F52A4228D04FEAAE -:10895000D30200EB82064FEA437491F802E04FEA3B -:10896000D46734680EF00F025FEACE6E03D591F83B -:1089700003E04EEA02024FF00F0E0EFA07FE24EA61 -:108980000E04BA40224332608A78282A02D0482A4C -:1089900003D005E0C268AA4301E0C2682A43C2606E -:1089A0005B1C102BCED3F0BD4FF4805108B14E4864 -:1089B00001E04D48001F016070472DE9F041044679 -:1089C0004A4817460D460088484E0C3E1CE015B13B -:1089D00015F8010B00E0FF2080460221304601F02F -:1089E00063FA0028F9D04146304601F059FA0121D6 -:1089F000304601F059FA0028F9D0304601F052FA19 -:108A0000C0B20CB104F8010B7F1EE0D20120BDE81A -:108A1000F081F0B501218C0389B0204600F0D2FD31 -:108A20000121204600F0E0FD18208DF816004FF4DB -:108A30002040ADF814002C4E03208DF81700143E92 -:108A400005A93046FFF77AFFADF8144004208DF8F1 -:108A5000160005A93046FFF771FFA010ADF814000D -:108A600010258DF8165005A93046FFF767FF1F4EF9 -:108A70000C3E304601F0CAF94FF48270ADF80200A6 -:108A800068010024ADF80A000720ADF81000ADF829 -:108A900004400220ADF80E40ADF806000127ADF805 -:108AA0000040ADF80870ADF80C506946304601F052 -:108AB000D1F90121304601F0E9F90DA000680690D6 -:108AC0000120FFF771FF042206A907A8FFF775FF31 -:108AD0000020FFF769FF9DF81D00EF2802D0204617 -:108AE00009B0F0BD3846FBE7140C01400C380040DB -:108AF0009F0000002DE9F04180461D4616460C46B9 -:108B0000084600F079F80746404600F06AF807EB9F -:108B10008000C0B2102805D23C4901EB00108560EE -:108B200004710673BDE8F08151B104290BD0082906 -:108B30000CD00C290DD101225FF0100100F0D3BF41 -:108B400001220221FAE701220421F7E7012208218C -:108B5000F4E7704770B50D460446017B1346006884 -:108B60002A46FFF7C7FF217B2068BDE87040DBE79E -:108B700008B58DF8000000208DF8010001208DF867 -:108B800002008DF80300684600F033FA08BDFEB518 -:108B9000064614460D46684600F075FF1C486D1EDB -:108BA00044431C48ADF8045069460068B0FBF4F03B -:108BB000401EADF800000020ADF80600ADF8020040 -:108BC000304600F02BFDFEBD10B504460068FFF7EF -:108BD000DEFF0121206800F071FF607BBDE81040DE -:108BE000C6E7014600200C4A01E0401CC0B252F822 -:108BF00020308B42F9D1704701460020074A01E03E -:108C0000401CC0B2135C8B42FAD170470C14002098 -:108C100040420F000C040020F8030020B0C70008F9 -:108C200070B505460846FFF7E7FF04462846FFF7FC -:108C3000D8FF04EB80000249C0B201EB001070BD08 -:108C40000C14002070B50546022100F082FF0128B7 -:108C500025D00421284600F07CFF01282CD00821D3 -:108C6000284600F076FF012833D01021284600F076 -:108C700070FF01283AD11021284600F076FF0C2120 -:108C80002846FFF7CDFF0446284600F05FFFA268A4 -:108C90000146002A2AD0207BBDE8704010470221FF -:108CA000284600F062FF00212846FFF7B9FF04467E -:108CB000284600F045FFEAE70421284600F055FF6A -:108CC00004212846FFF7ACFF0446284600F03AFF8F -:108CD000DDE70821284600F048FF08212846FFF775 -:108CE0009FFF0446284600F02FFFD0E770BD00002C -:108CF0000148FFF7A7BF0000002C01404FF0804063 -:108D0000FFF7A0BF0148FFF79DBF0000000400402F -:108D10000148FFF797BF0000000800401FB5044658 -:108D200002AB062202211820FEF755F99DF8080033 -:108D30009DF80910800800EB0120ADF800009DF8B7 -:108D40000A009DF80B10800800EB0120ADF802002E -:108D50009DF80C009DF80D10800800EB0120ADF887 -:108D600004001A48214602786846FEF78BFE1FBDB4 -:108D700010B5044608220F211820FEF726F90E220E -:108D800010211820FEF721F911494FF48050002CD2 -:108D9000088001D00D48047010BD38B5044600208D -:108DA0008DF8000001466B4601221820FEF713F9EA -:108DB00018B19DF80000FB2801D0002038BD0548FF -:108DC000206005486060012038BD000008040020D4 -:108DD0008A010020718D00081D8D0008026812684C -:108DE00010478068704701684968084701688968CA -:108DF00008470268D26810470168096908470000FF -:108E00000D48016841F00101016041680B4A1140C1 -:108E1000416001680A4A11400160016821F4802123 -:108E20000160416821F4FE0141604FF41F0181603F -:108E30000449C00308607047001002400000FFF8BA -:108E4000FFFFF6FE08ED00E0604A10B55068604B89 -:108E500010F00C015F4803D0042903D0082903D087 -:108E6000036016E0416813E05168536801F4701123 -:108E70004FF0020413F4803F04EB914106D0536895 -:108E80009B03436800D55B084B43E9E7524B5943CA -:108E9000016051684F4AC1F303110832515C026806 -:108EA000CA40026010BD3EB4002100914FF4E013AF -:108EB00001914648CDE90131484A046844F48034C0 -:108EC0000460846944F0100484614FF4A064056870 -:108ED00005F400350195009D6D1C0095019D15B9A7 -:108EE000009DA542F3D10568AD0301D5022114E030 -:108EF000056845F0010505600091016801F0020177 -:108F000001910099491C0091019911B90099A14260 -:108F1000F3D10168890739D50121029130490C68E4 -:108F200044F010040C600C6824F003040C600C681E -:108F300044F002040C60416841604168416041684E -:108F400041F480614160116821F070411160214C51 -:108F50001F496160416821F47C114160116841F052 -:108F6000004111601D49091FCA6822F40042CA600D -:108F70008968090403D51B494FF480136160029985 -:108F80000193012908D002290AD100E0FEE74168D7 -:108F900043F48032114302E0416841F460114160C2 -:108FA000016841F08071016001688901FCD5416868 -:108FB00021F003014160416841F0020141604168D4 -:108FC000C1F381010229FAD13EBC3DE70010024005 -:108FD00000127A000C04002000093D00041001403A -:108FE00000200240001BB7001849084318490860D8 -:108FF0007047F0B50F21C478027801234FF0E026C6 -:10900000DCB1134C2468457804F4E064C4F5E064F2 -:10901000240AC4F10407E1408478BD400C402C438D -:1090200021010C4C1155007800F01F018B404009C4 -:1090300006EB8000C0F80031F0BD02F01F00834055 -:10904000500906EB8000C0F88031F0BD0000FA0541 -:109050000CED00E000E400E010B54268464B0C79EE -:109060001A400B6842EA0422134343608368434A70 -:109070001340D1E9024222434C7943EA44031A43A4 -:109080008260C26A097C22F47002491EC9B242EAB7 -:109090000151C16210BD0029816802D041F0010177 -:1090A00001E021F00101816070470029816802D050 -:1090B00041F4807101E021F4807181607047816822 -:1090C00041F0080181607047014600208968090766 -:1090D00000D501207047816841F00401816070472C -:1090E000014600208968490700D501207047002902 -:1090F000816802D041F4A00101E021F4A001816067 -:10910000704770B5072409290AD9C568A1F10A0674 -:1091100006EB4606B440A543B3401D43C56007E0D7 -:10912000056901EB4106B440A543B3401D43056109 -:109130001F23072A09D2446B521E02EB820293407E -:109140009C4391400C43446370BD0D2A09D2046BCB -:10915000D21F02EB820293409C4391400C43046374 -:1091600070BDC46A0D3A02EB820293409C43914069 -:109170000C43C46270BD0000FFFEF0FFFDF7F1FF7D -:1091800001684FF6FE7211400160002101604160EC -:109190008160C1605249524A0839904203D14868FF -:1091A00040F00F0006E04E4A1432904204D1486865 -:1091B00040F0F00048607047494A2832904203D19D -:1091C000486840F47060F5E7454A3C32904203D16C -:1091D000486840F47040EDE7414A5032904203D174 -:1091E000486840F47020E5E73D4A6432904203D17C -:1091F000486840F47000DDE7394A7832904203D184 -:10920000486840F07060D5E7364A111F904203D19C -:10921000086840F00F0006E0324A1432904204D150 -:10922000086840F0F000086070472E4A28329042EB -:1092300003D1086840F47060F5E72A4A3C32904256 -:1092400003D1086840F47040EDE7264A503290425E -:10925000EAD1086840F47020E5E730B5036847F6C6 -:10926000F07293430C6A8A682243D1E904452C4387 -:1092700022438C692243CC6922434C6A22438C6A84 -:1092800022431A430260CA6842600A6882604968E1 -:10929000C16030BD0021016041608160C160016139 -:1092A00041618161C161016241628162704700294F -:1092B000016802D041F0010102E04FF6FE72114058 -:1092C00001607047002A026801D00A4300E08A4327 -:1092D0000260704741607047406880B2704700008C -:1092E0000800024008040240C10002D5024908609B -:1092F0007047024948607047040402400000024081 -:1093000030B51C498379026853B30B6893430B60F3 -:109310000A1D13680468A343136002790A441368A2 -:10932000046823431360134A083213680468A34394 -:109330001360131D1C680568AC431C604479102C35 -:1093400005D021440A68006802430A6030BD1168F4 -:10935000046821431160196800680143196030BD39 -:109360000079084401689143016030BD014914311E -:109370000860704700040140064A01460020126858 -:10938000044B0A4014331B680B4202D0002A00D061 -:1093900001207047000401404A4910B588424FF04F -:1093A000010101D14C0501E04FF48004204600F09A -:1093B0001BF92046BDE81040002100F015B970B53A -:1093C0000446808886B00D4620F03F06684600F0CF -:1093D000A1F83D490298B0FBF1F189B20E43A68095 -:1093E000228822F001022280384B2A689A421CD837 -:1093F0005200B0FBF2F080B2042800D20420491CD5 -:109400002184A083208840F00100208021884FF62D -:10941000F5300140A8886A89104308432080A88954 -:1094200029890843208106B070BDEB88A3F53F462B -:10943000FF3E05D102EB4202B0FBF2F080B208E041 -:1094400002EBC20303EB0212B0FBF2F080B240F475 -:109450008040020501D140F001004FF49672514363 -:109460004FF47A72B1FBF2F140F40040C7E741F2E9 -:1094700088310160002181804BF6FF72C28001813A -:1094800041814FF48041818170470029018802D0D9 -:1094900041F0010101E021F0010101807047002944 -:1094A000018802D041F4807101E021F480710180D3 -:1094B0007047002A828801D00A4300E08A438280F4 -:1094C000704700000054004040420F00A086010099 -:1094D0000029018802D041F4007101E021F40071FB -:1094E000018070470029018802D041F4806101E0C9 -:1094F00021F480610180704701827047008AC0B208 -:10950000704712B141F0010101E001F0FE0101825A -:109510007047000030B53C494A683C4B12F00C04DF -:1095200005D03B4A042C126803D0082C24D00360D9 -:1095300000E002604A680F2303EA1212354B9C5C7C -:109540000268E24042604C68072505EA14241C5D6D -:1095500022FA04F484604C6805EAD4241B5DDA40E6 -:10956000C2604968032303EA91312A4B1B1F595CEF -:10957000B2FBF1F1016130BD4B684C6803F470132C -:109580004FF0020514F4803F05EB934305D04C687F -:10959000A40300D552085A43CBE71F4A5343C6E7FA -:1095A000194A0029516901D0014300E0814351610A -:1095B0007047154A0029916901D0014300E08143B9 -:1095C00091617047104A0029D16901D0014300E040 -:1095D0008143D16170470C4A0029D16801D0014311 -:1095E00000E08143D1607047074A0029116901D02A -:1095F000014300E08143116170470348416A41F033 -:1096000080714162704700000010024000127A0031 -:10961000100400202804002000093D0030B5028815 -:10962000FD4BFE4C98420DD0A0420BD0B0F1804FC4 -:1096300008D0FB4DA84205D0FA4DA84202D0FA4D01 -:10964000A84203D122F070054A882A43F74DA84268 -:1096500006D0F74DA84203D022F44075CA882A43A9 -:1096600002808A8882850A88028598420AD0A042B0 -:1096700008D0F04A904205D0EF4A904202D0EF4A1B -:10968000904201D1097A01860121818230BD30B535 -:10969000028C22F001020284028C8388048B22F067 -:1096A000020224F073050C882C430D8915434A8867 -:1096B0002A43D94DA8420BD0D84DA84208D0DD4D41 -:1096C000A84205D0DC4DA84202D0DC4DA8420DD105 -:1096D00022F008054A8923F440732A4322F0040546 -:1096E0008A882A438D891D43CB892B438380048339 -:1096F000C9888186028430BD70B5028C22F01002C8 -:109700000284028C8488038B0D8823F4E6464FF68E -:10971000FF7303EA052535430E8922F0200203EA90 -:10972000061616434A8803EA02123243BA4EB04282 -:1097300002D0BA4EB04215D122F080064A8924F4F4 -:10974000406403EA0212324322F040068A8803EAA8 -:10975000021232438E8903EA86062643CC8903EA45 -:109760008404344384800583C9880187028470BDE2 -:1097700070B5028C22F480720284028C8488838B00 -:109780000D8823F073031D4322F400730E894FF6F6 -:10979000FF7202EA06261E434B8802EA0323334384 -:1097A0009D4EB04202D09D4EB04215D123F40066CA -:1097B0004B8924F4405402EA0323334323F48066A4 -:1097C0008B8802EA032333438E8902EA0616264376 -:1097D000CC8902EA0414344384808583C988818754 -:1097E000038470BD70B5028C22F480520284048C14 -:1097F0008288838B0D8823F4E6464FF6FF7303EAD5 -:109800000525354324F400560C8903EA0434344317 -:109810004E8803EA063626437F4CA04202D07F4C96 -:10982000A04205D122F480448A8903EA82122243AD -:1098300082808583C988A0F84010068470BD828B21 -:1098400022F440628283828B4FF6FF7303EA012188 -:109850000A4382837047828B22F00C028283828BC0 -:109860000A4382837047028B22F440620283028B98 -:109870004FF6FF7303EA01210A4302837047F0B5F4 -:10988000048C24F010040484078B048C4FF6FF75BD -:1098900027F4734705EA03333B4305EA02221A43E0 -:1098A0005D4B05EA011698420ED05C4B98420BD0F6 -:1098B000B0F1804F08D05A4B984205D0594B98428E -:1098C00002D0594B984205D124F02001314341F098 -:1098D000100104E024F0A0030B4343F010010283C5 -:1098E0000184F0BD028B22F00C020283028B0A433A -:1098F0000283704770B5048C24F001040484058B46 -:10990000048C4FF6FF7606EA0313134325F0F305A4 -:10991000414A2B4390420ED0404A90420BD0B0F1C6 -:10992000804F08D03E4A904205D03E4A904202D035 -:109930003D4A904202D124F0020201E024F00A02E2 -:109940000A4342F001010383018470BD2DE9F05FF9 -:109950000D4604460888304FDFF8C0C0DFF8C080ED -:109960004988AA882B894FF0804960B3042832D0F7 -:109970004FF6FF7E082836D0208C9B4620F480507E -:109980002084A38B268C704600EA022223F47343C2 -:109990001A4300EA0B3010430EEA013EBC420BD0E2 -:1099A000644509D04C4507D0444505D01D4A944232 -:1099B00002D01D4B9C425AD126F4005141EA0E01BF -:1099C00041F4805158E02046FFF794FFE988204693 -:1099D000BDE8F05F86E72046FFF751FFE9882046A3 -:1099E000BDE8F05F3FE7208C20F480702084B4F85D -:1099F0001CA0208C0EEA031313432AF0F30A0EEA8C -:109A0000012B43EA0A03BC4220D064451ED04C45DA -:109A10001CD044451AD013E0002C01400034014012 -:109A20000004004000080040000C0040001000400E -:109A30000014004000400140004401400048014043 -:109A40003D4A944202D03D4A944204D120F4007031 -:109A500040EA0B0002E020F42060084340F48070EC -:109A6000A3832084E9882046BDE8F05FF3E626F46E -:109A700002420A4342F48051A08320462184E988AF -:109A8000BDE8F05FDBE64FF6FF71818000210180C9 -:109A9000C180418001727047002101804180818036 -:109AA000C180018141818181C18170470021018094 -:109AB000418001228280C180018170470029018894 -:109AC00002D041F0010101E021F001010180704765 -:109AD000002930F8441F02D041F4004101E0C1F3F5 -:109AE0000E0101807047002A828901D00A4300E0FC -:109AF0008A4382817047028B22F008020A43028364 -:109B00007047028B4FF6FF7322F4006203EA0121D3 -:109B1000114301837047828B22F008020A4382833B -:109B20007047828B4FF6FF7322F4006203EA012133 -:109B3000114381837047000000080040000C004082 -:109B4000808E7047008F7047808F7047B0F840005C -:109B5000704702460020138A92890B4202EA0102F2 -:109B600002D0002A00D001207047C943018270470B -:109B700030B50446008A85B00D464CF6FF710840AA -:109B8000E98801432182A1894EF6F3100140A8889B -:109B90002A8910436A890A431043A081A08A4FF69C -:109BA000FF410840A9890143A1826846FFF7B2FC42 -:109BB0003048844201D1039800E00298A189090449 -:109BC000002900EBC00101EB0010296802DA4FEA1E -:109BD000410101E04FEA8101B0FBF1F06422B0FBEA -:109BE000F2F14FEA01114FEA11136FF018056B43C0 -:109BF00000EB8300A3891D044FF0320306D503EB6D -:109C0000C000B0FBF2F000F0070005E003EB00102D -:109C1000B0FBF2F000F00F000843208105B030BD2A -:109C20000029818902D041F4005101E021F4005162 -:109C30008181704710B5C1F3421301F01F04012167 -:109C4000A140012B07D0022B07D01430002A026854 -:109C500005D00A4304E00C30F8E71030F6E78A43F9 -:109C6000026010BD002A828A01D00A4300E08A43C4 -:109C7000828270470038014010B58A0721F0030442 -:109C80000649130F21440F228C689A4094438C603C -:109C90008A68984002438A6010BD000000000140BD -:109CA000394838494160394941607047364801694F -:109CB00041F080010161704733490420CA68D2072E -:109CC00001D001207047CA68520701D502207047B1 -:109CD000C968C906FBD50320704700B50346FFF7E6 -:109CE000EBFF02E0FFF7E8FF5B1E012803D0002B2B -:109CF00000D1052000BD002BF4D1FAE770B5054670 -:109D00004FF430263046FFF7E8FF042811D11E4CEF -:109D1000206940F0020020616561206940F0400048 -:109D200020613046FFF7D9FF216941F6FD721140ED -:109D3000216170BDF8B5064600204FF4005C00902C -:109D40000D466046FFF7C9FF042816D10E4C206966 -:109D500040F00100206135806046FFF7BEFF41F60C -:109D6000FE77042806D1B61C280C00963080604689 -:109D7000FFF7B3FF216939402161F8BD0249C8608E -:109D8000704700002301674500200240AB89EFCDFA -:109D900014481549026800608A4203D0134880477E -:109DA00013480047134E4FF0090030601248016815 -:109DB00021F07061016041020160104C18202060A8 -:109DC0000F49104808601048D0F800D0406800479C -:109DD000FEE7FEE7FEE7FEE7FEE7FEE7FEE7FEE75B -:109DE000FEE7FEE7F04F0020EFBEADDE018E00087B -:109DF000ED0000081810024004000140140C01405E -:109E0000000C01404434434400F0FF1F2A4910B5C0 -:109E100088420AD1841401212046FFF7DCFB20464A -:109E2000BDE810400021FFF7D6BB2449884202D18B -:109E30000121041404E0224988420AD10121C413FB -:109E40002046FFF7D1FB2046BDE810400021FFF778 -:109E5000CBBB10BD30B502884C8802F441530A8850 -:109E6000CD8822438C882C4322430C8922434C8981 -:109E700022438C892243CC8922431A430280828B5D -:109E800022F400628283098A018230BD00290188A0 -:109E900002D041F0400101E021F040010180704713 -:109EA00081817047808970470246002012890A42EA -:109EB00000D0012070470000003001400038004011 -:109EC000003C004000487047A8C80008A0F16101AC -:109ED000192900D8203870472DE9F05F99461546BA -:109EE0000F4683464FF0FF36DDF828A011E0A81991 -:109EF000441009FB0470804601465846524690477C -:109F0000002802D004DA254603E04046BDE8F09F71 -:109F10002646A5EB06000128E9DC0020F6E740EA2A -:109F200001039B0703D009E008C9121F08C0042AD7 -:109F3000FAD203E011F8013B00F8013B521EF9D2BE -:109F40007047D2B201E000F8012B491EFBD27047E6 -:109F50000022F6E710B513460A4604461946FFF7F5 -:109F6000F0FF204610BD421E12F8013F002BFBD12E -:109F700011F8013B02F8013B002BF9D1704730B5D5 -:109F800005462A460B4612F8010B13F8014B08B19F -:109F9000A042F8D01CB1002802D06D1CF1E7284681 -:109FA00030BD10B5044604E00B7800F8013B03B166 -:109FB000491C521EF8D2204610BDCAB2401E10F8ED -:109FC000011F8A4202D00029F9D100207047421CAB -:109FD00010F8011B0029FBD1801A70472DE9F041D0 -:109FE0000546002090460E46044600E0641C4445A9 -:109FF0000BD2285D00F03BFB0746305D00F037FBDD -:10A00000381A02D1295D0029F0D1BDE8F08170B580 -:10A01000064600F045FD046805460A220021304648 -:10A0200000F02BFB2C6070BDF0B480EA0102D40F6D -:10A030004200B2EB410F02D20246084611464A00E6 -:10A0400042D0C30DDDB2C1F3C752AD1A202D35DAAF -:10A05000C1F3160141F4000204B15242C5F12006D9 -:10A0600002FA06F12A411044B3EBD05F23D0C4B109 -:10A07000012DA0EBC35009DCF0BC4FF0004202EA16 -:10A08000C35200F50000DBB200F038BB400000F125 -:10A09000807000EBC350A0F1807040EAD17049009D -:10A0A00009E0490841EAC071A0EBC35000F5000087 -:10A0B000400800EBC350F0BC00F017BB6142012226 -:10A0C00002EB4101001BF6E7F0BC704781F0004154 -:10A0D000AAE780F00040A7E780EA010210B502F08D -:10A0E0000043400026D04A0023D04FEA106101EB24 -:10A0F0001261C0F35600C2F3560240F4000042F46D -:10A100000002A0FB0220A1F17F014FEA00401404ED -:10A1100001D000F1010050EA124001D44000491E74 -:10A12000C2B20C0604EBD010401C4008802A02D0BA -:10A1300003E0002010BD20F00100002900DA00201B -:10A14000184310BD30B480EA010202F0004530F03F -:10A15000004221F0004015D0A0B1C0F3C753C2F3B4 -:10A16000C754C2F31601C0F31600E41A41F400010B -:10A1700040F400027D34914201D3641C00E04900A8 -:10A18000002C02DA30BC002070474FF4000000239E -:10A19000914201D3891A034340084FEA4101F7D1A4 -:10A1A00051B1914202D14FF0004105E002D24FF08F -:10A1B000010101E06FF0010103EBC450284430BC01 -:10A1C00000F093BA420005D0C0F3C7525242914208 -:10A1D00001DC0020704700EBC15070472DE9FE4FB5 -:10A1E000804681EA0300C00F0C46009021F0004138 -:10A1F00023F00045B8EB0200A94105D240462146B4 -:10A2000090461C460B46024623F00040104304D102 -:10A210004046214603B0BDE8F08F270DC7F30A0082 -:10A22000C3F30A510290401A0190402866DAC3F342 -:10A23000130040F4801B0098924620B10023D2EB1B -:10A24000030A63EB0B0B01985946C0F140025046DC -:10A2500000F0ECF906460D4650465946019A00F0CA -:10A26000F4F910EB08006141002487EA115284EAF6 -:10A27000E7731A433BD0009A3AB3019A012A4FEA96 -:10A28000075210DC001B61EB02014FF0004202EAB2 -:10A290000752CDE90042001C41F5801132462B46A1 -:10A2A00000F0B3FAB6E7001B61EB0201001C41F5B8 -:10A2B000801300185B412018A2F5001747EB03013B -:10A2C00040EAD570B6196D4111E06D084FEA3606C7 -:10A2D00045EAC0754FEA0752001B61EB0201001C02 -:10A2E00041F5801149084FEA3000001951413246CA -:10A2F0002B4603B0BDE8F04F00F07ABA0098012277 -:10A3000040000023D0EB020263EBE073009821468B -:10A310004FEAE074B8EB000061EB0401E9E783F079 -:10A3200000435BE781F0004158E72DE9FE4F81EAE9 -:10A33000030404F0004421F0004100944FF0000BAE -:10A3400023F0004350EA010402D052EA030404D18E -:10A350000020014603B0BDE8F08FC3F30A54C1F3F7 -:10A360000A552C44A4F2F3340194A0FB0254C1F327 -:10A37000130141F48011C3F3130343F4801301FB71 -:10A38000024400FB034E840A970A44EA815447EAD8 -:10A390008357A4FB076802958D0A05FB07854FEAE2 -:10A3A000932C04FB0C542705029D4FEA065847EAFC -:10A3B0001637B5EB08056EEB070C870E920E47EAD1 -:10A3C000811742EA8312A7FB0201B6EB0B0164EB93 -:10A3D00000042B0D43EA0C335E1844EB1C50DA46A4 -:10A3E0005146E7FB0201C5F313044FEA0B3343EA7E -:10A3F00014534FEA0432019C43EA0603A4F10C040F -:10A400000294009CCDE900B400F0FFF9A2E72DE929 -:10A41000F04D81EA030404F0004B21F0004514469E -:10A420004FF0000A23F0004150EA050220D054EA20 -:10A4300001021DD0C5F30A570246C5F31303C1F349 -:10A440001300C1F30A5640F4801543F48013A7EBC0 -:10A450000608101BD64608F2FD3873EB050002D340 -:10A4600008F1010801E092185B41B8F1000F03DA2E -:10A4700000200146BDE8F08D00204FF48011064613 -:10A4800084460EE0171B73EB050705D3121B63EB25 -:10A49000050306434CEA010C49084FEA30009218C4 -:10A4A0005B4150EA0107EDD152EA030012D082EA83 -:10A4B000040083EA0501084303D100224FF0004362 -:10A4C00008E0101BAB4102D20122002302E06FF032 -:10A4D000010253101AEB06004CEB085110EB0A0076 -:10A4E00041EB0B01BDE8F04D00F082B9C10F80EAED -:10A4F000E0700844CA079623002100F0FFB89623B5 -:10A500000022114600F0FAB80EB5C10F80EAE070E3 -:10A510000844CA07002140F233438DE80E000A4682 -:10A520000B4600F072F903B000BD0EB540F23341A6 -:10A5300002910021CDE900110A460B4600F065F9B1 -:10A5400003B000BD00F0004220F00040C10DC0F398 -:10A55000160040F400007F2901DA00207047962998 -:10A5600003DCC1F19601C84001E096398840002A19 -:10A57000F4D04042704720F00040C10DC0F31600F7 -:10A5800040F400007F2901DA00207047962903DC9F -:10A59000C1F19601C840704796398840704701F074 -:10A5A000004330B421F0004150EA010206D00A0D08 -:10A5B000A2F56072C1F31301002A02DC30BC002056 -:10A5C0007047440F44EAC104C100E01830BC00EBFE -:10A5D000C25000F08AB80000002801DBC0F1004042 -:10A5E000002901DBC1F1004181427047002801DBF5 -:10A5F000C0F10040002901DBC1F1004188427047F1 -:10A6000030B50B46014600202022012409E021FA42 -:10A6100002F59D4205D303FA02F5491B04FA02F53F -:10A620002844151EA2F10102F1DC30BD202A04DB12 -:10A63000203A00FA02F1002070479140C2F1200355 -:10A6400020FA03F3194390407047202A06DBCB170A -:10A65000203A41FA02F043EAE07306E041FA02F3DD -:10A66000D040C2F120029140084319467047A0F142 -:10A670004101192900D8203070472DE9F047914653 -:10A680000F4680460446002614F8015B2DB1FFF703 -:10A6900019FC0068405DC007F6D12B2D02D02D2D8E -:10A6A00018D0641E4A463946204600F049F927B1C1 -:10A6B0003968A14201D1C7F8008071054FF002044A -:10A6C0000BD54042002803DD00F0EAF90460A00742 -:10A6D000BDE8F08746F48066E4E70028F8DA00F089 -:10A6E000DFF904606FF00040F2E70029A8BF70476F -:10A6F000401C490008BF20F00100704710B4B0FAB8 -:10A7000080FC00FA0CF050EA010404BF10BC704752 -:10A7100049B1CCF1200421FA04F411FA0CF118BF6C -:10A72000012121430843A3EB0C01CB1D0106000AC4 -:10A73000002BBEBF002010BC704700EBC35010447C -:10A740000029A4BF10BC7047401C490008BF20F07E -:10A75000010010BC7047F0B4002802DCF0BC0020FF -:10A760007047C0F3C751C0F3160040F40000CA0799 -:10A7700001D14000491E3F2202EB61050022114633 -:10A780004FF4000626FA01F31344D418844201D88A -:10A79000001B1A464000491C1729F3DD5100814275 -:10A7A00002D24FF0FF3100E0002102EBC550F0BCB7 -:10A7B000FFF79BBF10B541000CD0C0F3C7519629DD -:10A7C00008DC7E2909DC06DB410204D000F00040F1 -:10A7D00040F07E5010BD002010BDC1F19604C4F1C0 -:10A7E000200100FA01F1E040FFF77FFFA04010BD1B -:10A7F00010B5002B08DA401C41F1000192185B41B2 -:10A800001A4301D120F0010010BD2DE9F04D924610 -:10A810009B4611B1B1FA81F202E0B0FA80F2203227 -:10A820009046FFF703FF04460F4640EA0A0041EA5C -:10A830000B0153465A46084303D120463946BDE82A -:10A84000F08D114653EA010015D0C8F14002504680 -:10A8500000F066F805460E46504659464246FFF758 -:10A86000E5FE084301D0012000E00020054346EA50 -:10A87000E0762C4337430A984FEA4453A0EB080094 -:10A880004FEAD4240A304FF0000244EA47544FEA1A -:10A89000D72502D500200146D1E7010510196941ED -:10A8A000DDE9084500196941BDE8F04DA0E710B5A4 -:10A8B00000F0004420F00040C20DC0F3160040F448 -:10A8C00000007F2A07DA7D2A00DA7D22763A00FA34 -:10A8D00002F1002008E0962A09DCA2F1760100FAD4 -:10A8E00001F1C2F19602D040FFF7FFFE01E0963A77 -:10A8F0009040002C00D0404210BD0000064C074D97 -:10A9000006E0E06840F0010394E80700984710343F -:10A91000AC42F6D3F5F7EEFBA8D20008C8D2000887 -:10A92000202A04DB203A21FA02F00021704721FAA4 -:10A9300002F3D040C2F1200291400843194670470B -:10A940002DE9F05F82460078002715468B460AF114 -:10A950000104B946302801D09DB113E014F8010B71 -:10A960000127782803D0582801D045B10AE00DB15D -:10A97000102D07D10027102514F8010B02E008253F -:10A9800000E00A250026B0460EE005FB080005FBA6 -:10A9900006F1012701EB10461FFA80F8B6F5803F5B -:10A9A00000D3B94614F8010B294600F018F8002826 -:10A9B000EBDABBF1000F05D00FB1641E00E0544686 -:10A9C000CBF80040B9F1000F06D000F069F8022181 -:10A9D0000160C81EBDE8F09F48EA0640FAE73A2841 -:10A9E00000D2303820F02002412A01D3A2F13700F2 -:10A9F000884201D34FF0FF30704770B501EB02047D -:10AA000010F8015B15F0070301D110F8013B2A1182 -:10AA100006D110F8012B03E010F8016B01F8016B6F -:10AA20005B1EF9D12B0705D40023521E0FD401F869 -:10AA3000013BFAE710F8013B02F10202A1EB03032C -:10AA400003E013F8015B01F8015B521EF9D5A14246 -:10AA5000D6D3002070BD00000FB4054B10B503A97C -:10AA6000044A029800F0E8F810BC5DF814FB0000FE -:10AA700069230008380400204100080218BF0420A0 -:10AA80000A0E18BF40F001004FF07F4232EA010188 -:10AA900008BF40F00200012808BF052070470000F1 -:10AAA000004870473C0400206FF05E010807FFF784 -:10AAB00089BB00002DE9F04D0E4614464FF07F4152 -:10AAC000B1EB440F9EBF4FF0FF313160BDE8F08D18 -:10AAD0004FF0004040EA0421C4F3C75078384311D6 -:10AAE00000F01F00DFF814C1C0F12002FC445CF844 -:10AAF00023500CEB83038540D3F804C02CFA02F7F3 -:10AB00002F439D680CFA00FC25FA02F8DB6805FA71 -:10AB100000F023FA02F240EA02054CEA080CA7FB17 -:10AB20000132ACFB01C0A5FB015101EB0C058D42CC -:10AB300034BF4FF0010C4FF0000CC1186144BCF160 -:10AB4000000F02D0814202D903E0814201D20120EC -:10AB500000E00020104400F120024FEA9218800625 -:10AB6000CA0C40EA42304F03C6F80080FFF7BEFC33 -:10AB700082463846FFF7C3FC6FF01201FFF722FB55 -:10AB800007462846FFF7BBFC6FF02501FFF71AFBCD -:10AB9000834639465046FFF747FA5946FFF744FACD -:10ABA00000F500656FF30B0551462846FFF78EFA56 -:10ABB0003946FFF78BFA5946FFF78BFA1049FFF732 -:10ABC0008BFA07460F492846FFF786FA3946FFF702 -:10ABD0002BFA07460C492846FFF77EFA3946FFF75D -:10ABE00023FA14F0004F08BFBDE8F08DC8F1805182 -:10ABF00080F000403160BDE8F08D0000BC1D000019 -:10AC0000DB0FC92F22AAFD290000C92F02E008C8C6 -:10AC1000121F08C1002AFAD170477047002001E0D6 -:10AC200001C1121F002AFBD17047000001490860D2 -:10AC3000704700003C0400202DE9FF4F8BB09A467E -:10AC40000F4605460026C9E0252837D100246D1C93 -:10AC50006649A04601222B78203B02FA03F0084205 -:10AC600002D004436D1CF6E728782E2817D115F87A -:10AC7000010F44F004042A280ED06FF02F02287828 -:10AC8000A0F1300109290AD808EB880102EB410143 -:10AC900000EB01086D1CF2E757F8048B6D1C287857 -:10ACA00069283FD006DC002871D063280CD06428C6 -:10ACB00004D137E0732811D075284ED052460D9933 -:10ACC000904706F1010688E017F8040B8DF80000A4 -:10ACD00000208DF80100E946012003E057F8049BAD -:10ACE0004FF0FF3061074FF0000401D40AE0641C0C -:10ACF00044450DDA8442FADB19F804100029F6D134 -:10AD000006E0641C8442FCDB19F804100029F8D129 -:10AD1000264404E019F8010B52460D999047641E31 -:10AD2000F8D25AE001CF4FF00A0B002804DAC0F144 -:10AD300000004FF02D0102E0210504D52B218DF8F4 -:10AD40002410012103E0E10705D02021F7E70DF1F0 -:10AD5000200908910CE00021F9E701CF4FF00A0B20 -:10AD6000F9E75946FFF74CFC01F1300209F8012DD3 -:10AD70000028F6D1ADEB090000F1200B600701D4EB -:10AD80004FF00108D84503DDA8EB0B0001E029E0F6 -:10AD900000208046002406E009A85246005D0D9977 -:10ADA0009047761C641C08988442F5DB04E0302050 -:10ADB00052460D999047761CB8F10001A8F10108A0 -:10ADC000F5DC05E019F8010B52460D999047761C09 -:10ADD000BBF10001ABF1010BF4DC6D1C28780028FD -:10ADE0007FF432AF0FB03046BDE8F08F0928010084 -:10ADF0002DE9F0474FF0684202EB40030C46054650 -:10AE0000B3F1654F3CBF02EB4102B2F1654F3FD356 -:10AE10004FF07F42B2EB400F28BFB2EB410F03D29D -:10AE2000BDE8F047FFF700B940EA01035B0008BF47 -:10AE300044F0FF410AD0B2EB400F08BFB2EB410F24 -:10AE400006D125F0804024F0804105460C461FE0E5 -:10AE5000B2EB400F12BF5FEA410245F0FF4004F041 -:10AE6000004115D04FEA410292EA400310D4002A73 -:10AE7000B4BF4FF03E564FF09F463146FFF72CF9D6 -:10AE8000054631462046FFF727F904462846214665 -:10AE9000C0F3C753C1F3C7529A1A1B2A06DD10F03C -:10AEA000004F14BF54485548BDE8F08712F11A0FFF -:10AEB00017DA11F0004F06D010F0004F0CBF5048C9 -:10AEC0005048BDE8F08721462846FFF73BF9044685 -:10AED000FFF7D2FD042808BFFFF7E6FD2046BDE8D6 -:10AEE000F0874200B2EB410F25D910F0004F19BF97 -:10AEF000454F464E464F474E224685F00044154684 -:10AF00000A4680F0004110460A1A5200B2F1807FD2 -:10AF10003ED248404049DFF804A110F0004F18D05D -:10AF20004FF03F483846FFF7D1F8074651463046C4 -:10AF3000FFF7CCF817E011F0004F04BF00263746AA -:10AF4000E2D010F0004F19BF354F364E364F374E16 -:10AF5000DAE74FF07C583846FFF766F80746514667 -:10AF60003046FFF761F8064641462846FFF7B4F839 -:10AF70002146FFF759F8824621464046FFF7ACF8D4 -:10AF80002946FFF7A6F85146FFF7DCF8044604E02F -:10AF900021462846FFF7D6F804460146FFF79CF8FD -:10AFA00080462349FFF798F82249FFF73DF84146CC -:10AFB000FFF792F82049FFF737F84146FFF78CF882 -:10AFC0001E49FFF731F84146FFF786F81C49FFF7A5 -:10AFD0002BF8054641462046FFF77EF82946FFF745 -:10AFE0007BF83146FFF720F82146FFF71DF8394678 -:10AFF000BDE8F047FFF718B8DB0FC9BFDB0FC93F4B -:10B00000DB0F4940DB0F49C00000C9BF22AAFDB9D0 -:10B010000000C93F22AAFD390060ED3EC30ACE37C9 -:10B02000000049C022AA7DBA0000494022AA7D3A08 -:10B030002DAD65BD8FB8D53D0FB511BE61C84C3E75 -:10B04000A8AAAABE2DE9F84304460246504869461C -:10B05000B0EB420F09D94FF0E640B0EB420F94BF7E -:10B0600000204FF0FF30009034E04A4B22F00040C7 -:10B0700083422BD948492046FFF72EF8FFF79AFB69 -:10B080008046FFF75FFA00F0030000904349404616 -:10B09000FFF722F8054642494046FFF71DF80646ED -:10B0A00040494046FFF718F807463F494046FFF73A -:10B0B00013F82146FFF70DF83946FFF707F8314638 -:10B0C000FFF704F82946FFF701F802E01046FFF702 -:10B0D000F1FC04462546009C002C18DA6800B0F10B -:10B0E0007F4F3CBF4FF07E50BDE8F88309D14FF051 -:10B0F0000100FFF79BFDBDE8F84300210846FFF77C -:10B1000021B82846BDE8F8430121FFF75BB829467E -:10B1100014F0010F08461CD0FEF7DEFF0646234957 -:10B12000FEF7DAFF2249FEF7D4FF3146FEF7D4FFDF -:10B130002049FEF779FF3146FEF7CEFF2946FEF79C -:10B14000CBFF2946FEF770FF14F0020F1CD0BDE8BC -:10B15000F883FEF7C1FF05461749FEF7BDFF174903 -:10B16000FEF762FF2946FEF7B7FF1549FEF75CFFC1 -:10B170002946FEF7B1FF4FF07E51FEF755FF14F060 -:10B18000020F08BFBDE8F88380F00040BDE8F883F7 -:10B19000B61F927E490E494683F9223F1A61342C2C -:10B1A0000020A23300A0FD390000C93F336D4C39A7 -:10B1B000DA82083CA0AA2ABEB93AB2BACA9F2A3D8E -:10B1C000DDFFFFBE2DE9F04104464FF019404E4926 -:10B1D000002500EB4400884230D94FF0FF4131EAAE -:10B1E000040018D04FF0CE41B1EB440F84BF4FF0B4 -:10B1F0007E50BDE8F0814549B1EB440F28BF0125E1 -:10B200001CD20220FFF712FD14F0004F0FD0BDE852 -:10B21000F041FFF749BC204614F5000F04BF0020A1 -:10B22000BDE8F0810121BDE8F041FEF7CBBFBDE8EC -:10B23000F04161214FF0E040FEF7C4BF34492046A1 -:10B24000FEF74AFFFFF7B6FA8046FFF77BF906469E -:10B2500030494046FEF740FF07462F494046FEF77B -:10B260003BFF2146FEF735FF3946FEF72FFF044628 -:10B270002A49FEF731FF2A49FEF7D6FE2146FEF79E -:10B280002BFF6FF04141FEF7CFFE2146FEF724FF72 -:10B290002449FEF7C9FE2146FEF71EFF014622485B -:10B2A00006F00304784450F82400FEF715FF1F4908 -:10B2B000794451F82410FEF7B7FE1D49794451F83E -:10B2C0002410FEF7B1FEB110D5B1FEF77BFF0400EC -:10B2D0000BD0B4F1FF4F0FD0FFF7CEFB042808BF0F -:10B2E000FFF7E2FB2046BDE8F0810220FFF79EFC5D -:10B2F000BDE8F041FFF7D8BB0220FFF797FC96E7C7 -:10B30000BDE8F041FEF75EBF0000501E0000A085C2 -:10B310003BAAB840F4FD05370070313E12BB2A3D10 -:10B3200012BB2A3EFFFF7F3F2C15000010150000C6 -:10B33000F41400002DE9F0410026A0F50001B1F160 -:10B34000FE4F22D34FF07F42B2EB400F04D2BDE854 -:10B35000F0410121FEF736BFB0F1FF4F08BFBDE855 -:10B36000F081B0F1004F08D90120FFF75FFCBDE884 -:10B37000F04100210846FEF7E5BE30F000415ED006 -:10B380006FF016061721FEF71DFF00F500226FF083 -:10B390007E0101EBE251C2F3025477184FF07E5266 -:10B3A000A0EBC15602EB045557EA040050D02946E1 -:10B3B0003046FEF739FE804629463046FEF786FEC7 -:10B3C0004146FEF7BFFE05460146FEF785FE804674 -:10B3D0003349FEF781FE3349FEF726FE0646414615 -:10B3E0002846FEF779FE3146FEF776FE06463846D9 -:10B3F000FFF77CF807462C49FEF76EFE2B4979448F -:10B4000051F82410FEF710FE3146FEF70DFE0646F9 -:10B4100001212846FEF7D6FE3146FEF705FE054619 -:10B4200038462349FEF758FE2249794451F8241042 -:10B43000FEF7FAFD2946BDE8F041FEF7F5BD022012 -:10B44000FFF7F4FBBDE8F04100211B48FEF77ABE90 -:10B450004FF07E513046FEF739FE05461749FEF79C -:10B460003BFE1749FEF7E0FD2946FEF735FE15497C -:10B47000FEF7DAFD2946FEF72FFE6FF08241FEF758 -:10B48000D3FD044629460846FEF726FE2146FEF770 -:10B4900023FE01462846BDE8F041FEF7C5BD000089 -:10B4A00066F1CC3EAAAA2A3FF4FD0538021400003A -:10B4B0000070313FB6130000000080BF21ED423E16 -:10B4C0000A1180BEC1ABAA3E70B50546FFF7EFF981 -:10B4D00004464000801C0DD12846FFF76BF9054655 -:10B4E0002046FFF703F82946FFF776F81CBF012036 -:10B4F000FFF79CFB204670BD2DE9F8430446024649 -:10B5000053486946B0EB420F09D94FF0E640B0EB23 -:10B51000420F94BF00204FF0FF30009034E04D4BBD -:10B5200022F0004083422BD94B492046FEF7D4FD40 -:10B53000FFF740F98046FFF705F800F003000090A0 -:10B5400046494046FEF7C8FD054645494046FEF7D8 -:10B55000C3FD064643494046FEF7BEFD0746424945 -:10B560004046FEF7B9FD2146FEF7B3FD3946FEF72A -:10B57000ADFD3146FEF7AAFD2946FEF7A7FD02E024 -:10B580001046FFF797FA04462546009C002C1DDA6A -:10B590006800B0F17F4F09D22846FFF76DFA042802 -:10B5A00008BFFFF781FA2846BDE8F88308D10120DB -:10B5B000FFF73CFBBDE8F84300210846FEF7C2BD9B -:10B5C0002846BDE8F8430121FEF7FCBD294614F0EA -:10B5D000010F08461ED0FEF77FFD05462349FEF702 -:10B5E0007BFD2349FEF720FD2946FEF775FD214925 -:10B5F000FEF71AFD2946FEF76FFD4FF07E51FEF76C -:10B6000013FD14F0020F08BFBDE8F88380F000407E -:10B61000BDE8F883FEF760FD06461749FEF75CFDBE -:10B620001649FEF756FD3146FEF756FD1449FEF762 -:10B63000FBFC3146FEF750FD2946FEF74DFD29463D -:10B64000FEF7F2FC14F0020FE0D1BDE8F883000031 -:10B65000B61F927E490E494683F9223F1A61342C67 -:10B660000020A23300A0FD390000C93FB93AB2BAA8 -:10B67000CA9F2A3DDDFFFFBE336D4C39DA82083C9C -:10B68000A0AA2ABE70B50546FFF765F8044620F06B -:10B690000040C0F1FF40C00F08D025F00040C0F1CD -:10B6A000FF40C00F04BF0120FFF7C0FA204670BD65 -:10B6B0005BC900089BC90008E1C9000858C9000817 -:10B6C0005FC9000801C90008FCC800084CC900088F -:10B6D000F1C80008DBC9000804C90008ACC90008AB -:10B6E000F0C900081BC900087EC9000828C9000865 -:10B6F000EAC8000877C90008000000008CC90008EB -:10B70000CBC9000866C90008E7C90008A1C900083C -:10B71000D0C9000834C9000843C90008C7C90008D7 -:10B7200012C90008B6C90008FAC90008BCC9000857 -:10B7300090C900080FC90008000000000BC90008EC -:10B7400096C9000824C90008B6C90008C7C900087E -:10B750000000000028D10008F4C80008DBC8000879 -:10B760009ED00008E3C8000884CB00080000000059 -:10B7700003D1000856D0000877030008FED0000867 -:10B7800050CF0008CB030008A3CF000804D0000866 -:10B79000E1060008FDCE0008A7CD000893070008C9 -:10B7A000D1CF000828D1000809090008ADCB000856 -:10B7B0001CCD000829090008F8CE000828D100088F -:10B7C000F5090008F4CE000825CF0008450C000854 -:10B7D0005ECF000821D00008B90C000835CB000866 -:10B7E000CCC800083F0D00081ECC0008F4CF0008AC -:10B7F000E3080008CDCF000834D00008790D000818 -:10B80000C6CF0008BACF0008B90E000851CE000814 -:10B8100028D10008650F00087BCB0008020000005B -:10B820007C04002000000000282300000ECA00084D -:10B830000200000080050020B0040000A406000003 -:10B8400063CB00080200000040050020000000005B -:10B85000D00700006FCB0008020000004205002066 -:10B8600000000000D0070000D6CA00080200000057 -:10B870004405002000000000D0070000BECC0008F6 -:10B88000020000008205002000000000D007000038 -:10B89000C7CC000802000000840500200000000062 -:10B8A000D00700008FD000080200000046050020ED -:10B8B00000000000D00700008FCC0008020000004C -:10B8C0004805002000000000D007000014CA00084E -:10B8D000020000004A05002000000000D007000020 -:10B8E0003DCB0008020000004C05002000000000D5 -:10B8F000D0070000DCCB0008020000004E0500204D -:10B9000032000000F2010000CDCB00080200000070 -:10B910005005002032000000F20100009ACD00081E -:10B92000000000008605002000000000010000006B -:10B93000F9CB00080400000090050020B0040000CE -:10B9400000C2010009CC0008040000008C050020A2 -:10B95000B004000000C2010092CB0008000000000B -:10B960007E05002000000000020000001CCB000843 -:10B9700000000000720500200A000000C80000005E -:10B98000F4CA000800000000730500200A0000004F -:10B9900032000000E1CA0008000000007405002029 -:10B9A0000A0000003200000030CD00080000000056 -:10B9B000750500200000000009000000B8CE000856 -:10B9C00000000000520500200000000008000000F8 -:10B9D00004CA000800000000530500200000000019 -:10B9E0000800000049CC00080000000054050020B9 -:10B9F000000000000800000069CE000801000000FF -:10BA000055050020FFFFFFFF01000000A0CB00084C -:10BA100000000000560500200000000005000000A6 -:10BA200083CA000800000000640500200000000038 -:10BA30008000000040CC00080200000058050020F3 -:10BA4000000000000001000073CF000802000000A9 -:10BA50005A05002064000000E803000084CF0008BD -:10BA6000020000005C05002064000000E803000004 -:10BA700089CB0008000000008805002000000000BD -:10BA80000300000041CF0008000000005008002023 -:10BA90000000000001000000CDCA00080000000006 -:10BAA000B60800200000000020000000CACA0008FC -:10BAB00000000000B7080020000000006400000043 -:10BAC00002CD000800000000B808002001000000BE -:10BAD000FA00000007CB000800000000B9080020B1 -:10BAE00000000000010000008DCE000800000000F2 -:10BAF000BA0800200000000064000000B5CB000878 -:10BB0000000000006F08002000000000FA000000A4 -:10BB1000A7CE000800000000700800200000000010 -:10BB2000640000005ECA00080000000071080020E8 -:10BB30000000000064000000AFCE0008000000001C -:10BB40007208002000000000FA000000BDCB0008D1 -:10BB500000000000730800200000000064000000E6 -:10BB600016CC00080000000074080020000000004F -:10BB70006400000007D1000800000000FC0800205D -:10BB800000000000C800000016D1000800000000FE -:10BB9000FD08002000000000C800000051CB000894 -:10BBA00002000000FE080020E8030000D0070000AB -:10BBB00093CA000802000000000900206400000091 -:10BBC000D007000042CD00080100000087050020DA -:10BBD00000000000040000007FCE0008010000000B -:10BBE00002090020FFFFFFFF01000000C3CE000894 -:10BBF0000100000003090020000000000100000017 -:10BC000026CB00080200000004090020000000000C -:10BC1000D007000045CE0008020000000609002001 -:10BC200000000000D0070000F2D000080200000071 -:10BC30000809002000000000D007000028CE0008FE -:10BC4000020000000A09002000000000D0070000E8 -:10BC500066CA0008020000000C0900200000000075 -:10BC6000D0070000D5D00008020000000E09002017 -:10BC700000000000D007000036CE000802000000DF -:10BC80001009002000000000D007000074CA00085E -:10BC9000020000001209002000000000D007000090 -:10BCA000E3D000080200000014090020000000009A -:10BCB000D0070000D0CC00080100000016090020C9 -:10BCC000FFFFFFFF0100000002CF0008010000009D -:10BCD00017090020FFFFFFFF01000000E2CC000871 -:10BCE0000100000018090020FFFFFFFF0100000015 -:10BCF00014CF00080100000019090020FFFFFFFF1A -:10BD00000100000096CF0008000000001C09002080 -:10BD100000000000FF000000D6CD00080100000078 -:10BD20001A0900209CFFFFFF64000000E8CD000816 -:10BD3000010000001B0900209CFFFFFF64000000C1 -:10BD400007CE0008020000001E0900206400000069 -:10BD5000B80B0000B4D00008020000002009002049 -:10BD600064000000B80B00003DCA0008020000009B -:10BD70002209002064000000B80B000018CE000863 -:10BD8000020000002409002064000000B80B00003D -:10BD9000C5D0000802000000260900206400000051 -:10BDA000B80B00004ECA000802000000280900205D -:10BDB00064000000B80B000064CF00080000000021 -:10BDC0007C08002000000000FA000000ADCA000856 -:10BDD000000000007E080020000000006400000059 -:10BDE000BCCA0008000000007D0800200000000020 -:10BDF00064000000F3CC0008000000008C08002064 -:10BE0000000000000100000078CC000803000000E2 -:10BE10007A080020D4FEFFFF2C01000085CD000829 -:10BE20000300000078080020D4FEFFFF2C01000072 -:10BE300023CC0008000000007F0800200000000064 -:10BE40003000000031CC0008050000008008002010 -:10BE5000000000000100000053CD000805000000B4 -:10BE6000840800200000000001000000DCCF000872 -:10BE7000050000008808002000000000010000000C -:10BE800059CE00080300000076080020B0B9FFFF7B -:10BE900050460000E0CE00080000000055080020D9 -:10BEA00000000000C8000000AACC0008000000004C -:10BEB0005F08002000000000C800000029CA000838 -:10BEC000000000006908002000000000C800000019 -:10BED000D5CE000800000000560800200000000039 -:10BEE000C80000009FCC000800000000600800208F -:10BEF00000000000C80000001ECA0008000000008A -:10BF00006A08002000000000C8000000EACE000817 -:10BF1000000000005708002000000000C8000000DA -:10BF2000B4CC000800000000610800200000000000 -:10BF3000C800000033CA0008000000006B080020A1 -:10BF400000000000C8000000ACCF000802000000A4 -:10BF50002A09002000000000D007000053CC000890 -:10BF6000000000002E090020000000000100000079 -:10BF7000F9CD000802000000300900200A0000008E -:10BF8000D0070000A6D000080200000032090020FF -:10BF90000A000000D0070000EBCB00080000000002 -:10BFA0002D090020000000006400000087CC00087C -:10BFB000000000005208002000000000C80000003F -:10BFC00070CC0008000000005C08002000000000A9 -:10BFD000C800000068CC00080000000066080020CF -:10BFE00000000000C800000093CD00080000000021 -:10BFF0005108002000000000C80000007ECD0008AD -:10C00000000000005B08002000000000C8000000E5 -:10C0100077CD000800000000650800200000000047 -:10C02000C800000089D0000800000000530800206C -:10C0300000000000C800000083D0000800000000DD -:10C040005D08002000000000C80000007DD000084E -:10C05000000000006708002000000000C800000089 -:10C06000EECF00080000000054080020000000008F -:10C07000C8000000E8CF0008000000005E080020B3 -:10C0800000000000C8000000D6CF0008000000003B -:10C090006808002000000000C80000006FCD000804 -:10C0A000000000005808002000000000C800000048 -:10C0B00067CD0008000000006208002000000000BA -:10C0C000C80000005FCD0008000000006C080020E0 -:10C0D00000000000C80000004145525431323334A2 -:10C0E000000000000000803F00000000A8AAAA3F56 -:10C0F000000000000000803F000080BFB0AA2ABFFF -:10C10000000000000000803F0000803FB0AA2ABF6E -:10C11000000000000000803F000000000000803FA1 -:10C12000000080BF0000803F000080BF00000000D2 -:10C130000000803F0000803F0000803F00000000C2 -:10C140000000803F0000803F00000000000080BF32 -:10C15000000080BF0000803F000080BF0000803FE3 -:10C16000000080BF0000803F000080BF000080BF53 -:10C170000000803F0000803F0000803F0000803FC3 -:10C180000000803F0000803F0000803F000080BF33 -:10C19000000080BF0000803F0000803F00000000E2 -:10C1A000000000000000803F000080BF0000000091 -:10C1B000000000000000803F00000000A8AAAA3F85 -:10C1C0000000803F0000803F000080BFB0AA2ABF6F -:10C1D000000080BF0000803F0000803FB0AA2ABF5F -:10C1E000000080BF0000803F00000000A8AAAA3F16 -:10C1F000000080BF0000803F000080BFB0AA2ABFBF -:10C200000000803F0000803F0000803FB0AA2ABFAE -:10C210000000803F0000803F000080BFD0B35D3F42 -:10C220000000803F0000803F000080BFD0B35DBFB2 -:10C23000000080BF0000803F0000803FD0B35D3F22 -:10C240000000803F0000803F0000803FD0B35DBF12 -:10C25000000080BF0000803F00000000D0B35DBF41 -:10C260000000803F0000803F00000000D0B35D3F31 -:10C27000000080BF0000803F000000000000803F01 -:10C28000000080BF0000803F000080BF000080BF32 -:10C29000000000000000803F000000000000803F20 -:10C2A0000000803F0000803F0000803F000080BF12 -:10C2B000000000000000803FD0B35DBF0000803F61 -:10C2C0000000803F0000803FD0B35DBF000080BF12 -:10C2D0000000803F0000803FD0B35D3F0000803F02 -:10C2E000000080BF0000803FD0B35D3F000080BFF2 -:10C2F000000080BF0000803FD0B35DBF00000000A1 -:10C30000000080BF0000803FD0B35D3F0000000010 -:10C310000000803F0000803F000080BF0000803FA1 -:10C32000000080BF0000803F000080BF000080BF91 -:10C330000000803F0000803F0000803F0000803F01 -:10C340000000803F0000803F0000803F000080BF71 -:10C35000000080BF0000803F000080BF0000803FE1 -:10C360000000803F0000803F000080BF000080BFD1 -:10C37000000080BF0000803F0000803F0000803F41 -:10C38000000080BF0000803F0000803F000080BFB1 -:10C390000000803F0000803FF704353FF70435BFC1 -:10C3A0000000803F0000803FF70435BFF70435BF31 -:10C3B0000000803F0000803FF70435BFF704353FA1 -:10C3C0000000803F0000803FF704353FF704353F11 -:10C3D0000000803F0000803F00000000000080BFA0 -:10C3E000000080BF0000803F000080BF0000000010 -:10C3F000000080BF0000803F000000000000803F80 -:10C40000000080BF0000803F0000803F000000006F -:10C41000000080BF0000803F0000803F000000BFA0 -:10C420000000803F0000803F000000BF000080BF90 -:10C430000000803F0000803F000080BF0000003F00 -:10C440000000803F0000803F0000003F0000803F70 -:10C450000000803F0000803F0000003F000080BFE0 -:10C46000000080BF0000803F000080BF000000BFD0 -:10C47000000080BF0000803F000000BF0000803F40 -:10C48000000080BF0000803F0000803F0000003FB0 -:10C49000000080BF0000803F000000000000803FDF -:10C4A0000000803F0000803F000080BF000080BF90 -:10C4B000000000000000803F000000000000803FFE -:10C4C000000080BF0000803F0000803F000080BF70 -:10C4D00000000080000000000000000003010000D8 -:10C4E000E4C000080400000014C1000804000000BB -:10C4F00054C100080201000094C1000800010000BE -:10C500000000000006000000B4C1000806000000A2 -:10C5100014C2000801010000000000000400000037 -:10C5200074C2000806000000B4C200080800000041 -:10C5300014C300080800000094C3000808000000AD -:10C5400014C4000801010000000000000001000008 -:10C5500000000000000100000000000004000000D6 -:10C5600094C400080000000000000000524F4C4C32 -:10C570003B50495443483B5941573B414C543B5035 -:10C580006F733B506F73523B4E6176523B4C455636 -:10C59000454C3B4D41473B56454C3B0080250000F8 -:10C5A000004B00000096000000E1000000C2010006 -:10C5B000E1D1000803D200084DD200086FD2000874 -:10C5C000CDD1000825D2000839D2000892D2000847 -:10C5D000B56206010300F00500FF19B5620601030C -:10C5E00000F00300FD15B56206010300F00100FB39 -:10C5F00011B56206010300F00000FA0FB5620601F2 -:10C600000300F00200FC13B56206010300F0040011 -:10C61000FE17B562060103000102010E47B562066E -:10C620000103000103010F49B56206010300010681 -:10C6300001124FB562060103000112011E67B562C7 -:10C640000616080003070300510800008A41B5627E -:10C6500006080600C80001000100DE6A1048494AC9 -:10C660004B4C4D44454647FF2021222324252627B5 -:10C6700048494A4B4C4DFF1048498A8B8C8D848524 -:10C680008687FF202122232425262748498A8B8C50 -:10C690008DFF000068C600085CC6000883C600085D -:10C6A00077C60008000C014008001002000C014091 -:10C6B0001000100200080140001014027D7E0008E6 -:10C6C000197E00084D7E00089B7D0008337E00081F -:10C6D000000000400008014001000000001C0000B4 -:10C6E000000000400008014002000000041C00009F -:10C6F000000000400008014004000000081C000089 -:10C700000000004000080140080000000C1C000070 -:10C71000000400400008014040000000001D00002F -:10C72000000400400008014080000000041D0000DB -:10C7300000040040000C014001000000081D000042 -:10C7400000040040000C0140020000000C1D00002D -:10C75000002C01400008014000010000001B010006 -:10C76000002C014000080140000800000C1B0100E3 -:10C7700000080040000C014040000000001E0000C6 -:10C7800000080040000C014080000000041E000072 -:10C7900000080040000C014000010000081E0000DD -:10C7A00000080040000C0140000200000C1E0000C8 -:10C7B0000004080C0000803F0030983F0000B53FA7 -:10C7C0000040D73F00000000320A7E397F661E39E4 -:10C7D0005B991F390000803FF037983FF304B53F65 -:10C7E000FD44D73F000000000030F13D0070643E82 -:10C7F0000000A33E0090CF3E0090F83E00400F3F67 -:10C8000000E0203F0000000015B78337CDE37B3800 -:10C810000EE1C53860F69138AF5F0F38E1BC3E38A5 -:10C8200023F44739004040404040404040404141AF -:10C8300041414140404040404040404040404040F5 -:10C84000404040404005020202020202020202028F -:10C85000020202020220202020202020202020028C -:10C86000020202020202909090909090101010101C -:10C8700010101010101010101010101010101010B8 -:10C88000020202020202888888888888080808084C -:10C890000808080808080808080808080808080818 -:10C8A000020202024000000025C80008000000004B -:10C8B0006E83F9A22915444ED15727FCC0DD34F50B -:10C8C000999562DB4190433CAB6351FE696E6465B0 -:10C8D0007820283020746F203229004D5055363092 -:10C8E000353000424D4132383000565441494C34C5 -:10C8F000005934004144584C3334350048455836CB -:10C90000005936004F43544F5838004143430033D9 -:10C9100044004641494C5341464500414952504C20 -:10C92000414E45004D41470048454C495F39305F15 -:10C93000444547004759524F5F534D4F4F54484964 -:10C940004E47004C45445F52494E4700464C5949BA -:10C950004E475F57494E47004249005452490047ED -:10C96000494D42414C00494E464C494748545F416D -:10C9700043435F43414C00435553544F4D0048459A -:10C980004C495F3132305F4343504D0050504D00B1 -:10C99000564152494F004241524F00515541445077 -:10C9A000004D4F544F525F53544F50004F43544F1C -:10C9B000464C41545000534F4E415200504F574542 -:10C9C000524D455445520047505300564241540081 -:10C9D000534552564F5F54494C54004845583658B9 -:10C9E0000051554144580053455249414C5258005A -:10C9F0004F43544F464C4154580054454C454D45C7 -:10CA000054525900616C69676E5F616363006D69C0 -:10CA1000647263006E65757472616C336400677074 -:10CA2000735F706F73725F64006770735F706F73B2 -:10CA30005F64006770735F6E61765F640067696D45 -:10CA400062616C5F70697463685F6D6964006769D7 -:10CA50006D62616C5F726F6C6C5F6D6964007468AD -:10CA6000725F6D69640077696E675F6C6566745F9D -:10CA70006D69640077696E675F72696768745F6D7E -:10CA80006964006D6F726F6E5F7468726573686F52 -:10CA90006C64006661696C736166655F646574658A -:10CAA00063745F7468726573686F6C64006163635C -:10CAB00078795F6465616462616E64006163637A62 -:10CAC0005F6465616462616E640079617764656169 -:10CAD0006462616E64006D696E636F6D6D616E643A -:10CAE00000766261746D696E63656C6C766F6C74F0 -:10CAF00061676500766261746D617863656C6C7600 -:10CB00006F6C7461676500616C745F686F6C645F03 -:10CB1000666173745F6368616E67650076626174F5 -:10CB20007363616C65007472695F7961775F6D69C9 -:10CB300064646C650070726F66696C650064656141 -:10CB40006462616E6433645F7468726F74746C6580 -:10CB5000006661696C736166655F7468726F747496 -:10CB60006C65006D696E7468726F74746C65006DCD -:10CB700061787468726F74746C65006C6F6F707438 -:10CB8000696D65004E6F6E65006770735F747970D4 -:10CB9000650073657269616C72785F7479706500A5 -:10CBA0006163635F68617264776172650066656185 -:10CBB000747572650072635F7261746500726F6C88 -:10CBC0006C5F70697463685F72617465007365722D -:10CBD000766F5F70776D5F72617465006D6F746FF3 -:10CBE000725F70776D5F72617465006E61765F73FE -:10CBF0006C65775F726174650073657269616C5F03 -:10CC00006261756472617465006770735F626175FB -:10CC10006472617465007961777261746500736133 -:10CC20007665006261726F5F7461625F73697A65D5 -:10CC3000006261726F5F6E6F6973655F6C70660032 -:10CC40006779726F5F6C706600616C69676E5F6DAB -:10CC50006167006E61765F636F6E74726F6C735F95 -:10CC600068656164696E6700645F70697463680019 -:10CC7000695F7069746368006163635F7472696D92 -:10CC80005F706974636800705F70697463680064E2 -:10CC900065616462616E6433645F686967680067D8 -:10CCA00070735F706F73725F69006770735F706F2E -:10CCB000735F69006770735F6E61765F69006D69AD -:10CCC0006E636865636B006D6178636865636B00B4 -:10CCD00070697463685F646972656374696F6E5FBD -:10CCE0006C00726F6C6C5F646972656374696F6EFF -:10CCF0005F6C006163635F756E61726D6564636133 -:10CD00006C00616C745F686F6C645F7468726F74E0 -:10CD1000746C655F6E65757472616C006C697374B8 -:10CD2000206F72202D76616C206F722076616C000E -:10CD3000706F7765725F6164635F6368616E6E6573 -:10CD40006C00727373695F6175785F6368616E6EA2 -:10CD5000656C006261726F5F63665F76656C00642C -:10CD60005F6C6576656C00695F6C6576656C0070FC -:10CD70005F6C6576656C00645F726F6C6C00695FF8 -:10CD8000726F6C6C006163635F7472696D5F726F68 -:10CD90006C6C00705F726F6C6C00726574617264B1 -:10CDA00065645F61726D007072696E7420636F6E8E -:10CDB000666967757261626C652073657474696E0B -:10CDC000677320696E2061207061737461626C65A5 -:10CDD00020666F726D0067696D62616C5F70697467 -:10CDE00063685F6761696E0067696D62616C5F723D -:10CDF0006F6C6C5F6761696E006E61765F73706502 -:10CE000065645F6D696E0067696D62616C5F706912 -:10CE10007463685F6D696E0067696D62616C5F72F3 -:10CE20006F6C6C5F6D696E0077696E675F6C6566CD -:10CE3000745F6D696E0077696E675F7269676874A9 -:10CE40005F6D696E007472695F7961775F6D696E9D -:10CE50000076657273696F6E006D61675F6465630C -:10CE60006C696E6174696F6E007961775F636F6E74 -:10CE700074726F6C5F646972656374696F6E007958 -:10CE800061775F646972656374696F6E007468725C -:10CE90006F74746C655F616E676C655F636F7272EF -:10CEA000656374696F6E0072635F6578706F00749C -:10CEB00068725F6578706F00616C69676E5F677933 -:10CEC000726F007472695F756E61726D65645F7315 -:10CED0006572766F006770735F706F73725F70005A -:10CEE0006770735F706F735F70006770735F6E6100 -:10CEF000765F70006D61700068656C700064756DC0 -:10CF0000700070697463685F646972656374696FE7 -:10CF10006E5F7200726F6C6C5F64697265637469D6 -:10CF20006F6E5F72006D617070696E67206F662052 -:10CF30007263206368616E6E656C206F72646572E7 -:10CF4000007069645F636F6E74726F6C6C65720001 -:10CF500064657369676E20637573746F6D206D69A6 -:10CF6000786572006163635F6C70665F66616374AD -:10CF70006F72006779726F5F636D70665F66616381 -:10CF8000746F72006779726F5F636D70666D5F6654 -:10CF90006163746F720067696D62616C5F666C617A -:10CFA00067730064656661756C7473006770735FA6 -:10CFB00077705F7261646975730073686F7720734F -:10CFC000797374656D20737461747573007365741F -:10CFD000006578697400645F616C74006261726FEF -:10CFE0005F63665F616C7400695F616C7400705FA1 -:10CFF000616C74007361766520616E642072656295 -:10D000006F6F7400726573657420746F2064656659 -:10D0100061756C747320616E64207265626F6F74E9 -:10D02000006D69786572206E616D65206F72206C8D -:10D03000697374006E616D653D76616C7565206F16 -:10D040007220626C616E6B206F72202A20666F7294 -:10D05000206C69737400666561747572655F6E61DA -:10D060006D6520617578666C6167206F7220626CF7 -:10D07000616E6B20666F72206C69737400645F79F7 -:10D08000617700695F79617700705F79617700642B -:10D0900065616462616E6433645F6C6F77004D4DEF -:10D0A0004138343578006E61765F73706565645F12 -:10D0B0006D61780067696D62616C5F706974636847 -:10D0C0005F6D61780067696D62616C5F726F6C6C37 -:10D0D0005F6D61780077696E675F6C6566745F6D20 -:10D0E00061780077696E675F72696768745F6D6108 -:10D0F00078007472695F7961775F6D617800636D44 -:10D10000697800617578006661696C736166655F56 -:10D1100064656C6179006661696C736166655F6FF7 -:10D1200066665F64656C61790043414D53544142CA -:10D130003B0043414C49423B0047505320484F4C31 -:10D14000443B0048454144465245453B00414E471B -:10D150004C453B0047505320484F4D453B004D4107 -:10D16000473B0043414D545249473B0048454144E9 -:10D1700041444A3B0041524D3B00484F52495A4FAF -:10D180004E3B00564152494F3B004241524F3B00FB -:10D190004245455045523B00474F5645524E4F522F -:10D1A0003B004C4C49474854533B00504153535467 -:10D1B0004852553B004C45444C4F573B004F53445D -:10D1C0002053573B004C45444D41583B0024504DA3 -:10D1D000544B3235312C31393230302A32320D0A4B -:10D1E0000024505542582C34312C312C30303033FF -:10D1F0002C303030312C31393230302C302A32332F -:10D200000D0A0024505542582C34312C312C30302A -:10D2100030332C303030312C33383430302C302A0D -:10D2200032360D0A0024504D544B3235312C3338F0 -:10D230003430302A32370D0A0024504D544B3235E9 -:10D24000312C35373630302A32430D0A0024505500 -:10D2500042582C34312C312C303030332C3030309B -:10D26000312C35373630302C302A32440D0A002428 -:10D27000505542582C34312C312C303030332C3036 -:10D280003030312C3131353230302C302A31450DAF -:10D290000A0024504D544B3235312C313135323067 -:10D2A000302A31460D0A0000C8D2000800000020D4 -:10D2B00040040000FAA90008B8D300084004002088 -:10D2C000D02000001CAC00080192031A7A44CBDC89 -:10D2D0000502A1023701139130025808CBDE050286 -:10D2E000510219030936C3914B75D1CC29491A4D06 -:10D2F0000C290832021A7A0C2908297B1A8A0C296F -:10D300000832041A830C290829991A5E0C2908325C -:10D31000061A430C290832071A6C0C290829591AD5 -:10D32000290C290832091A630C2908320A1A540CEC -:10D330002908320B1A390C2908320C1AAB0C2908AF -:10D34000320D1A900C2908320E1AC50C2908320F1A -:10D350001AB50C290832101AA20C290832111A32F7 -:10D360000C290832121A980C290832131ABD0C29FC -:10D3700008721402B4FFE20152038B803F040116CD -:10D380005A03384AD931E91D12010A1C0274C20835 -:10D39000342C014012401A040412083A405B14A2D3 -:10D3A0004A048B127A33380B020304060708090279 -:08D3B00004063B2910691481F9 +:1039E000A5729BF80500082801D00E2843D1657206 +:1039F00041E0DAF85C005746042801DD401FF86515 +:103A0000052838D2DFE800F0030B151F2A00082034 +:103A1000FE65FDF739FF10B100F067FC58BBF86D8B +:103A2000401CF8650420FDF72FFF10B100F06DFB7E +:103A300008BBF86D401CF8650420FDF725FF10B1A8 +:103A4000FEF7E9FAB8B9F86D401CF8654FF48070DC +:103A5000FDF72FFF10B102F0BAF90CE0F86D401C31 +:103A6000F8651020FDF710FF08B100F0C0FC4FF41E +:103A70000050FDF71EFF04F012F9CAF83400BBF83D +:103A80000C10574611B1BB6DC31A79D40844D946FE +:103A9000B865FEF75CFAFFF7B3F804F000F9786355 +:103AA000398F411AB981B8630820FDF7EDFE20B3C4 +:103AB00087491439B1F9042002F145008A281DD83C +:103AC0006079D8B18048038880480088181A00B20D +:103AD00010F1B40F02DC00F5B47000B2B42802DBC0 +:103AE000A0F5B47000B2637B3BB17A4B5B7A434381 +:103AF0001E2093FBF0F0101A888003E072480188C2 +:103B0000724801800420FDF7BFFE58B3A07948B386 +:103B1000704A92F8690030B36D48B7F91A1014383A +:103B2000B0F90630A3EB010CBCF1000F01DCA1EBF6 +:103B3000030C92F86820944509DDDFF884C18B42BC +:103B4000CCF800507E7200DD5242991809E07A7A72 +:103B500022B1614A1368614A13607D72594A128822 +:103B60001144C18039E0DFF86881B7F91A00A8F183 +:103B70001408B8F90630191A002902DD0B4601E0D5 +:103B8000D7E0C31A92F8682093420FDDBA8B4FF446 +:103B9000FA6C114409B291FBFCF3504A0CFB13116F +:103BA00015681D441560B9837E7207E0797A29B1E2 +:103BB00049490A6849490A60BD837D7241490988BB +:103BC000084400B2A8F80600B9F8D010B9F8D2201D +:103BD000963102F037FDA8F806003E4D95F86A00D0 +:103BE00050B1E07808B9207930B139483C4A1438EE +:103BF000C18812881144C1802020FDF745FEE8B33A +:103C0000E07908B9207AC8B3207BB8B32E4CB4F958 +:103C1000000006F035FE334E314606F0AFFD07F0EA +:103C20006BFD0090B4F9000006F02AFE314606F064 +:103C3000A5FD07F007FB264C064695F8B900303C79 +:103C4000DFF8A4A0A4F11C0810B3A146B4F9020047 +:103C5000241DB4F90210401A01F008FA15F8B92F22 +:103C6000514202F0EFFC618808446080B9F900001D +:103C7000B4F90010401A01F0F9F900E04FE02A7899 +:103C8000514202F0DFFC2188084400B2208001E0AC +:103C9000B4F9000006F0F4FD8346009906F06EFDCD +:103CA0000546B4F9020006F0EBFD8146314606F008 +:103CB00065FD294606F05CFD5546514616E00000BC +:103CC0002C00002028000020A8010020AA010020CC +:103CD00050010020E0070020580000205C00002078 +:103CE0000A00002035FA8E3C0000204106F07CFDE1 +:103CF00006F0D4FDA8F8000044465846314606F0C8 +:103D00003DFD06464846009906F038FD314606F06E +:103D1000DDFC294606F068FD06F0C0FD6080386CC9 +:103D20008047FEF726FDFEF7C4FCBDE8F84FFEF71E +:103D300000BDBDE8F88F03484178002901D000217B +:103D400041707047680A00202DE9F843FE4CFF4B94 +:103D5000FF490026B4F8EE209846A1F1100004F0C7 +:103D6000EAFB08B101260EE0B4F8EE10F84804F0C2 +:103D7000F1FD40B9B4F8EE10F54803F082FD10B93A +:103D8000032004F05FF8F34D5FF0000794F8ED00B6 +:103D900006283CD2DFE800F0070719283303022089 +:103DA000FDF77FFD33E08DF800704FF44870E8496F +:103DB000ADF802001039684602F085FF08B1012015 +:103DC000287094F8ED00012821D06EB1E049B4F8D4 +:103DD000EE204346A1F1100004F0ADFB0220287054 +:103DE00094F8ED0002281DD0D948103804F0ACFC3E +:103DF00028B10320287094F8ED00032812D0D4488D +:103E0000103805F01AFB10B1042028700AE0287859 +:103E100040B994F8ED0010B184F8ED70B6E70220D7 +:103E2000FDF73FFDCA48103004F097FE38B9C84886 +:103E3000103002F0EFFF10B90420FDF732FD022030 +:103E4000FDF722FD28B1C24994F8E3001039096852 +:103E50008847BF4914F8E20F09688847A07803F043 +:103E6000F3F810B90820FDF71CFDBB486421B0F938 +:103E7000262092FBF1F001FB102406B20820FDF78A +:103E800003FDB64D90B1204606F0FAFCB44906F0A9 +:103E900075FC0446304606F0F3FC214606F016FC9D +:103EA000B04906F06BFC2860BDE8F8832F60FBE7A3 +:103EB00070B50546A44890F8060106F0EAFC0446F1 +:103EC000284606F0E6FCA84906F058FCA74906F08B +:103ED0008BFC214606F052FC06F0F9FC80B270BD66 +:103EE00070B500252C46002002F04AFE05440A2049 +:103EF00003F0FEFE641C202CF5D3C5F34F10FFF732 +:103F0000D7FF914A022192F8073100BF03FB01F469 +:103F1000844202D8491C0629F8D39548017092F8CA +:103F2000080148439349088070BD2DE9F05FDFF830 +:103F30002492914E884FB9F80220834C0025C2B3D9 +:103F40008E4900204FF4C878424501D141F82050F5 +:103F500051F8203036F910C0634441F8203026F87B +:103F6000105004EB4003401CA3F8FA500328EBDB8D +:103F7000012A19D10868C83090FBF8F024F8FA0F2C +:103F80004868C83090FBF8F060808868C83090FBC3 +:103F9000F8F1B9F80600081AA0803D850121FA3C25 +:103FA0007D850846FDF7ABFAB9F80210491EA9F85D +:103FB00002100420FDF77DFC002874D0704BDFF860 +:103FC00094816E491A8808F120080C31A8F1180A6A +:103FD000322A05D0F2B300209B46322A14D015E0D5 +:103FE00034F8FA0FA8F800006088A8F80200A0884A +:103FF000A8F80400B7F828C0AAF800C0B7F82AC08B +:10400000FA3CAAF802C0E6E741F8205051F8203007 +:1040100036F910C0634441F8203026F8105004EB04 +:104020004003401CA3F8FA500328D6DB012A1AD11A +:104030005448554B058001201880544B02201870BD +:10404000B8F8000024F8FA0FB8F802006080B8F859 +:10405000040000E00AE0A080BAF800303B85BAF81E +:104060000200FA3C7885521EABF8002048480288CE +:10407000012A18D105800A68322092FBF0F224F858 +:10408000FA2F4A6892FBF0F26280896891FBF0F1A6 +:10409000B9F80600081AA0803D850121FA3C7D850B +:1040A0000846FDF72CFA308834F8FA1F401A3080A1 +:1040B00070886188401A7080B088A188401AB080EA +:1040C000BDE8F09F224810B5103841682A4888475B +:1040D000BDE8104029E730B51E4C1F4AE06892F851 +:1040E0002F200146401C824200D10020294A13683B +:1040F000224A183242F82130274952F820200D6810 +:104100002B449A1A0A60E06030BD70B52348114C08 +:1041100000682169411A01D5002070BD20610C4D55 +:104120006069103578B128698047686880472888B9 +:104130002169084420616A6919491648904700209E +:104140006061022070BD2DE064040020E4080020BE +:10415000440C002074010020E007002034000020FF +:104160008988883C000020413333534000F07F456C +:1041700060010020E600002076000020140B0020E3 +:10418000D2000020D8000020D4000020C000002071 +:10419000D60000209C00002020000020F400002019 +:1041A0001C000020A8688047E8688047FFF793FF5D +:1041B000012060616888216908442061012070BD88 +:1041C0002DE9F05FA24DA88800286AD0DFF884822C +:1041D0000024A3464FF47A79A8F10C06A888484534 +:1041E00007D104EB840208EB820146F824B0C1F841 +:1041F00010B0994F56F8241037F91400014446F8CE +:10420000241006F03DFB014604EB840208EB82001B +:10421000824600F0EFF827F814B0904F27F814B05A +:10422000A888012837D1DAF81000012808DD401EDF +:1042300006F026FB0146DAF80C0006F0D5FA00E09D +:10424000002007F01FFB8246854890F8F800A8B1CF +:1042500006F01FFB514606F04FFB0FD27D49A5F833 +:104260000490C8F810B0C1F824B0C1F838B0C6F84E +:1042700008B0C6F804B0C6F800B00CE056F8240048 +:10428000012200F5FA7090FBF9F027F814000F21D5 +:104290000A20FEF78DFC641C032C9FDBA888401EBF +:1042A000A8806D496D4A002031F8103032F8104076 +:1042B0001B1B21F81030401C0328F5DB00E7654884 +:1042C00010B54C30416864488847BDE8104077E736 +:1042D00010B564481024046002F005FF6148001F17 +:1042E00004605B490120487010BD2DE9F0415E4833 +:1042F000574C0068A169411A02D50020BDE8F08141 +:104300005A490844A0615A4802F0B5FEDFF864C17A +:104310004F4B00269CF80E005549514A26339D1DEF +:1043200088B1A069E061002002EB4007A7F80061B6 +:1043300031F8107023F8107025F81070401C032815 +:10434000F2D38CF80E60607870B10888B2F8007112 +:10435000C01B08804888B2F80271C01B488088885A +:10436000B2F80471C01B8880E06998B3A769381A55 +:10437000414FB84218D23B480838026882F0080220 +:104380000260002031F9102033F91040A24201DA16 +:1043900023F8102035F91040A24201DD25F8102045 +:1043A000401C0328EED315E00020E66133F910101D +:1043B00035F91040214402EB400401EBD17141F387 +:1043C0004F01401CA4F800110328EFD30121084637 +:1043D000FDF795F8012091E710B5012004F001FAEE +:1043E0001020FDF759FA25490020086010BD234828 +:1043F00004F04BBA2DE9F041044600690E46401C1A +:10440000206101281FD006F03BFA25688046294626 +:10441000304606F0ADF90746414606F0E5F9294673 +:1044200006F054F9054660602946304606F0A0F9CA +:104430000146384606F0A2F9A16806F047F9256062 +:10444000E060A0605AE7666000202660F9E700009F +:1044500074010020F80B002070000020A000002054 +:1044600064040020140C0140F4000020A086010028 +:1044700082000020680A002080C3C901A800002033 +:1044800070B5FB4CFB4EC1B20546A170306804F01C +:10449000F5FFE079A1784840E071C5F30721A170EC +:1044A000306804F0EBFFE079A1784840E071C5F393 +:1044B0000741A170306804F0E1FFE079A17848403D +:1044C000E071290EA170306804F0D8FFE079A1787E +:1044D0004840E07170BD70B5E54CE64EC1B205468E +:1044E000E170306804F0CAFFE079E1784840E0719B +:1044F000C5F30721E170306804F0C0FFE079E1788E +:104500004840E07170BD10B50446DA4821460068A5 +:1045100004F0B4FFD648C1796140C17110BDD44ADE +:10452000D548117A405C491C1172704700B5FFF7FD +:10453000F6FF0346FFF7F3FF03EB002080B200BD58 +:1045400010B5FFF7F3FF0446FFF7F0FF04EB004060 +:1045500010BD70B504460D462420FFF7D4FF4D2052 +:10456000FFF7D1FF0CB1212000E03E20FFF7CBFF89 +:10457000BF4C0020E0712846FFF7C5FF607ABDE818 +:104580007040C0E701460020E3E701460120E0E774 +:10459000B748C079B7E770B504460D460846FFF73F +:1045A000F1FF03E014F8010BFFF7ADFF2800A5F1C0 +:1045B0000105EDB2F6D170BD10B5044603E000BFB1 +:1045C000FFF7A1FF641C20780028F9D110BD2DE968 +:1045D000F05FDFF89CB2DFF8989201274FF0000AF5 +:1045E0000BF10C0B00251AE0A3481438405D00EBDA +:1045F00040010BEB8108D8F8040006F03AF80646B3 +:104600000FB1B2440AE0002406E000BFD8F804006D +:10461000005DFFF778FF641CB442F7DB6D1C99F86E +:1046200000008542E0DB002F05D00AF0FF00FFF715 +:10463000A9FF0027D6E7BDE8F09F70B50246032327 +:1046400000218E4803F0D4FC8A49FF2208608A4882 +:104650001421143805F0C7FF874D0020143D0124B4 +:1046600028700220FDF710F920B1012068700220A7 +:10467000A87003240420FDF707F950B10320285542 +:10468000641C4FF40050FDF714F910B104202855B4 +:10469000641C0220FDF7F8F818B90820FDF7F4F8BB +:1046A00040B105202855641C06202855641C0720AD +:1046B0002855641C2020FDF7FCF810B1082028556F +:1046C000641C4FF48070FDF7F4F828B10A202855D7 +:1046D000641C0B202855641C69484079082801D0C7 +:1046E0000E2802D10C202855641C0D202855641C6E +:1046F0000420FDF7DEF810B111202855641C1320AA +:1047000028555B48641C047070BD2DE9F05F584E5D +:10471000DFF864B14FF00008717A594D594C5A4F87 +:10472000C1464FF0010AABF1140B782978D011DCA7 +:104730003046A1F16401007814293BD2DFE801F092 +:10474000FCFBFAF9F8F7F6F5F4F3F2F1F0EFEEED21 +:10475000ECEBEAE94C48CF29407871D014DCCA2947 +:104760005FD008DCA0296CD0A4296BD0C82927D041 +:10477000C9291FD138E0CB2965D0CC2971D0CD29EA +:1047800070D0CE2916D17BE3D4296CD00ADCD02995 +:104790006AD04FF00008D12967D0D22966D0D3293A +:1047A00008D1DFE0EF2918D0F02960D0FA2979D0BC +:1047B000FE2978D00020FFF7E8FEBDE8F05FE7E6CD +:1047C0000024324DFFF7B2FE25F81400641C082CBB +:1047D000F8D30020FFF7D6FEEFE7FFF7A7FE6085CE +:1047E000FFF7A4FE2085F4E7FFF799FEF872FFF7C4 +:1047F00096FE27490870FFF7A3FE264C2060FFF7BE +:104800009FFE6060FFF792FE23490880FFF78EFE4F +:10481000224908802248017841F002010170D8E75E +:1048200061E10023FFF77BFEE5186870FFF777FE74 +:10483000E872FFF774FE5B1C68750A2BF2D3C8E7B9 +:1048400049E04BE35CE300255F4606E0FFF76EFEC0 +:10485000795D6D1C04EB4101C88730788542F5D342 +:10486000B7E721E005E358E1FDE2C9E26BE02BE3A5 +:10487000AC010020D4080020800C0020003801404A +:1048800064040020E0070020680A0020780A002065 +:10489000CB000020440100206E01002070010020A8 +:1048A0005C010020F1E2F2E2FFF739FE04F81F0F8D +:1048B000FFF735FE6070FFF732FE2071FFF72FFE25 +:1048C0006071FFF72CFEA071FFF729FEA070FFF7C3 +:1048D00026FEE0707DE7FFF729FEFFF727FEE935AA +:1048E00025F8190CFFF72CFEFFF720FEA4F8AE0008 +:1048F000FFF71CFEFFF724FEFFF718FE00EB800019 +:104900004000E084FFF70BFE6877FFF708FEE877CA +:1049100013E0D2E150E2B3E1CCE10CE2DAE1B6E13E +:104920009CE183E174E16AE151E13EE120E111E1C2 +:104930000BE1D5E0A1E028E018E0FFF7F0FDA87753 +:10494000FFF7EDFD45E700288AD1FFF7E8FD85F880 +:104950007803022801D985F8788300210020FCF72C +:10496000CEFD36E7FFF7E2FDF94987E20720FFF7C2 +:1049700009FEE620FFF7C7FD6879FFF7C4FD0020B8 +:10498000FFF7C1FD4FF00040B7E20B20FFF7FAFD43 +:10499000F048008800B2FFF79EFD02F0AEFE00B2C4 +:1049A000FFF799FD0220FCF76FFF04460420FCF797 +:1049B0006BFF44EA40040820FCF766FF44EA8004E9 +:1049C0002020FCF761FF44EAC0041020FCF75CFFE4 +:1049D00044EA0010FFF77FFDF9783A79490041EA8F +:1049E0008201BA79002041EAC2017A79367841EA37 +:1049F00042117A7AD44641EA8211D74AD37941EA00 +:104A0000C311137A41EA0321537A41EA4321FB7926 +:104A100041EA83213B7A41EAC321BB7A41EA03316F +:104A2000537B41EA4331937B41EA8331137C41EA72 +:104A30000341137941EA0311537C41EA4341937CDA +:104A4000D27C41EA834141EAC24479785F460C4313 +:104A5000002208E0BB5C0CFA03F3234202D00CFAFC +:104A600002F10843521CB242F4D3FFF709FD95F856 +:104A7000780300BFFFF747FD9FE61220FFF782FD96 +:104A8000B648B74D4FF000040088B0F5806F0BD9E1 +:104A900035F91400C11700EB5170C010FFF71BFD72 +:104AA000641C032CF4D306E035F91400FFF713FD62 +:104AB000641C032CF8D3AB4D002400BF35F914005F +:104AC000FFF709FD641C032CF8D3A74D002400BF99 +:104AD00035F91400FFF7FFFC641C032CF8D36CE6D7 +:104AE0001021A24833E03820FFF74CFD5FF00005AD +:104AF00004EBC50636F96C0FFFF7EDFCB6F90200C2 +:104B0000FFF7E9FCB6F90400FFF7E5FCB079FFF721 +:104B1000FAFC6D1C082DEBD34FE60020FFF732FDA9 +:104B20005FF00005FFF702FD04EBC50626F86C0FE9 +:104B3000FFF7FCFC7080FFF7F9FCB080FFF7EFFC9B +:104B40006D1CB071082DEDD337E610218848FFF7B2 +:104B500022FD32E61020FFF715FD864D002400BF30 +:104B600035F91400FFF7B7FC641C082CF8D324E6D1 +:104B70001020FFF707FDF87AFFF7C5FC7E480078A4 +:104B8000FFF7C1FC7D4C2068FFF77AFC6068FFF7F7 +:104B900077FC7B48008800B2FFF79DFC79480088CD +:104BA00000B2FFF798FC78483DE00520FFF7EAFCEB +:104BB0007648008800B2FFF78EFC7548B0F9000017 +:104BC000FFF789FC7348007800F0010052E70820E5 +:104BD000FFF7D8FC704D002435F91400FFF77BFC7B +:104BE000641C022CF8D36D48B0F90000FFF773FC89 +:104BF0006B48B0F9000000BFFFF76DFCDDE5062053 +:104C0000FFF7C0FC67480068FFF73AFC66480AE017 +:104C10000520FFF7B7FC65480078FFF774FC00201B +:104C2000FFF759FC6248008800B2E5E70720FFF76C +:104C3000A9FC14F81F0FFFF766FC6078FFF763FC10 +:104C40002079FFF760FC6079FFF75DFCA079FFF742 +:104C50005AFCA078FFF757FCE0780BE71E20FFF71F +:104C600091FC002566197078FFF74DFCF07AFFF78C +:104C70004AFC707DFFF747FC6D1C0A2DF2D39CE5C2 +:104C80002F20FFF77FFC4B48FFF796FC95E5400689 +:104C9000000EFFF777FC00255F4607E0785D04EB28 +:104CA0004000B0F93E00FFF716FC6D1C30788542DD +:104CB000F4D382E5FFF78BFC7FE5FFF763FC00246C +:104CC0005D4603E0285DFFF71EFC641C30788442DB +:104CD000F8D372E53220FFF755FC0020FFF7FBFB0D +:104CE00035F9D00FFFF7F7FBB5F90200FFF7F3FB3B +:104CF000B5F90400FFF7EFFBB4F9AE00FFF7EBFBEB +:104D00000020FFF7E8FB0020FFF7BAFBB4F926000C +:104D10000A2190FBF1F000B2FFF7DDFB95F83600B9 +:104D2000FFF7F1FB95F83800FFF7EDFB95F837003A +:104D3000FFF7E9FB62E00820FFF724FC0024601C79 +:104D4000C0B2FFF7E0FB641C082CF8D335E5000087 +:104D5000AA010020CC000020BE0A00207A01002019 +:104D60007C0000206400002082000020AE000020B3 +:104D7000E8080020780A0020CB0000204401002031 +:104D80006E010020700100205E0100206A010020F9 +:104D90006C0100205C01002038000020A8010020E8 +:104DA000DE0000205800002030000020CA00002053 +:104DB000E200002048C60008FFF7B1FB04461220BD +:104DC000FFF7E0FB14B1102C02D004E0954800E09E +:104DD0009548D0E900892046FFF795FB4046FFF74C +:104DE0004FFB4846FFF74CFB90480068FFF748FB35 +:104DF0000020FFF770FB0020FFF76DFB002039E675 +:104E0000FFF78DFB8446FFF79BFB0546FFF798FBFA +:104E10000646FFF795FB0446FFF788FBFFF786FB86 +:104E2000FFF77DFBBCF1000F11D0BCF1100F7FF438 +:104E3000DAAC7D49C1E900560CB17C4804607C4A7B +:104E40000220091D1070784801F01DF8C1E4754872 +:104E5000002CC0E9005687F8078087F80CA0F5D031 +:104E600072480460B5E40028F0D10120FCF7FDFC95 +:104E7000AFE40028EAD16F494FF4C8700880A8E475 +:104E80000028E3D187F80EA0A3E4012166E50820FD +:104E9000FFF778FB68486A4A6A4D016867481268FC +:104EA000B1FBF0F1B2FBF0F000EB4002C2EBC0103E +:104EB00001EBC000E880002435F91400FFF70BFB7C +:104EC000641C042CF8D378E40420FFF75BFBB4F9EE +:104ED0002A00FFF700FBB4F928008DE60C20FFF74D +:104EE00051FB59480068FFF7CBFA5748001D00688E +:104EF000FFF7C6FA544808300068FFF7C1FA5CE4CF +:104F0000524D29780AEB8100C0B2FFF73BFB2878AD +:104F1000FFF7F9FA00244E4E4E4FDFF83C81DFF8E0 +:104F20003C910EE0305DFFF7EEFA385DFFF7EBFAEB +:104F300018F80400FFF7E7FA19F80400FFF7E3FA9E +:104F4000641C28788442EDD337E470B5444C454E58 +:104F50000025607810B3BDE87040FBF7E1BF306812 +:104F600004F09FFAA17951B101291CD002291FD068 +:104F7000032923D0042929D005293FD12CE0242856 +:104F800003D00021A17149B901E00121FAE72328EA +:104F900002D0522832D102E0FBF7C2FF2EE00120FE +:104FA00002F071FF2AE04D2804D10220A07125E013 +:104FB0003C2801D00020F9E70320F7E740281CD85F +:104FC000607125712572E0710420EFE76072E1796C +:104FD0004140E1710520E9E721796279914207D2E8 +:104FE000E2794240E271204A5054491C217105E0A7 +:104FF000E179814201D1FFF788FBA571306804F0A7 +:105000004DFA0028ABD16078002809D14FF4006038 +:10501000FCF74FFC002803D0BDE8704001F0E3B975 +:1050200070BD00004C010020540100205C000020F5 +:10503000C1000020760100200004002040420F0043 +:105040000404002062010020E8F7FF1F7201002025 +:10505000D20A0020E20A0020F20A0020020B0020FF +:10506000AC010020D4080020800C002044F25061E4 +:10507000884201DDA0EB4100FE49884202DA48F691 +:10508000A041084470472DE9F0470646506899460C +:1050900014460D46301A05F0F3FB296805F0A4FB11 +:1050A0002061A768394605F063FB8046F24890F816 +:1050B000B80005F0EEFBF14905F060FB01464FF04A +:1050C0007E5005F091FB2D68294605F0FFFA014658 +:1050D000284605F089FB414605F050FB394605F0AE +:1050E000F5FA2061C4E901600146D9F8080005F02D +:1050F00045FBBDE8F04705F0D1BB2DE9F0411D4669 +:1051000014460E4605F0BCFB696805F037FB3168B4 +:1051100005F034FB216805F0D9FA2060ED680746F8 +:10512000284605F0BBFB064685F0004005F0B6FBBF +:105130000546384605F0B2FB3246294601F082FAB0 +:1051400005F09EFB2060BDE8F04105F0A7BB70B5FF +:10515000CB4CD4E90D01401AFFF788FF0028D4E9B1 +:105160000D01A0EB010002DDFFF780FF02E0FFF779 +:105170007DFF404241F29411884228DAD4E90D01C2 +:10518000401A05F07DFBBF4905F0F8FA0646E06BD2 +:1051900005F07FFB0546304606F0AEFA294605F0DD +:1051A000EDFA05F07BFB00B240F6B83220825142A6 +:1051B00001F048FA616B084448F6A04160648842F7 +:1051C00000DD401A002800DA0844606470BD606B9E +:1051D000FBE72DE9FE4F0546FFF7B9FFA84842F26D +:1051E0002831406C081A05F04BFBA64905F0C6FAB9 +:1051F000044606F027F80190204606F07DFA00905C +:105200000024284605F03CFBDFF874A2DFF8789212 +:10521000DFF878B20AF1300A029099481A3030F972 +:10522000140005F02DFB05465DF82410029805F0EA +:10523000A5FA294605F09CFA05F030FB00B24FF4C0 +:105240007A7255462AF81400514201F0FBF98E4952 +:1052500000B225F81400603900F03CFE04EB84062F +:10526000894B8749074609EB8602904635F91400B9 +:10527000603B2831FFF741FF834B81490744424699 +:1052800035F91400603B2831FFF7FDFE384400B2C9 +:1052900040F6B8325D462BF81400514201F0D2F9C5 +:1052A00025F81400784859F826102838641C40F86E +:1052B0002610022CB1DBBDE8FE8F2DE9F05F704EA9 +:1052C0000024DFF8C4915036DFF8C0B1A6F1360AE9 +:1052D000A9F128096C4956F82400803900F0FAFD3C +:1052E0003AF81410664F401A3037674900B227F871 +:1052F0001400703900F0EEFD054637F9140056F839 +:10530000241004EB840708445F4B5D4909EB8702D6 +:105310009046703B2831FFF7F0FE28445A4B58491D +:105320002BF814005D46424656F82400703B2831A5 +:10533000FFF7A9FE4FF4FA62514201F083F93AF9FE +:1053400014103131622900D8002035F8141040F6CD +:10535000B832084400B225F81400514201F072F945 +:1053600025F81400484859F82710641C40F8271005 +:10537000022CAFDBBDE8F09F70B5054608681968E0 +:105380001446401A05F07CFA3D49C96A05F0F6F961 +:1053900005F084FA01463A48503041602968226895 +:1053A000891A016070BD2DE9F0410F46DDE90685DF +:1053B000116800681E46081A05F062FA0446306853 +:1053C0003968401A05F05CFA2D49C96A05F0D6F92A +:1053D0000646014605F0D2F907462146084605F083 +:1053E000CDF9394605F072F906F04CFA284905F076 +:1053F000C5F905F06CFAC8F8000084F000403146A9 +:1054000005F0F6FD234905F0B9F9234905F05EF9E9 +:1054100005F044FA2860002803DA48F6A041084461 +:105420002860BDE8F0812DE9F0471C48144CD0E914 +:105430000056617804F1480991B34FF07E50A16A9B +:1054400005F0D2F98246D9F80400301A05F018FAAE +:10545000E16A05F093F9514605F090F905F01EFA5E +:1054600007B2D9F8000004F11A08281A05F008FA62 +:10547000514616E0B0B9FFFFE0070020DB0FC9403E +:10548000B4020020D3023739600D00202001002033 +:105490002C7D8E3FA00CB34500A00C46440100209B +:1054A0001AE005F06BF905F0F9F901B204F12400F6 +:1054B000B0F902203A4402EBD27242F34F02A8F84C +:1054C0000220B0F90030194401EBD17141F34F01D2 +:1054D000A8F800104280018001206070C9E90056E0 +:1054E000BDE8F08710B5044605F0CAF9002C01DCD0 +:1054F00080F00040F74905F077F9F74905F03EF9EB +:1055000005F0A0FEF549C86210BD10B5F44CE07A74 +:10551000002811D0F348007805280DD3F249F34A4A +:105520000868106049685160FFF7DCFFF048EB49FC +:10553000008888820120207310BD2DE9F043E749DF +:10554000EC48E74B8E7A012502790024062E29D0FB +:1055500004DC022E09D0032E04D116E0122E33D023 +:10556000302E3DD00020BDE8F083DF4A466856600B +:105570008668166000694FF47A7290FBF2F0DE4A9A +:105580001080C87AD8724D7351E04079C00701D0BD +:10559000032A03D00020C87210B148E00120FAE7C6 +:1055A000DC7244E0C27AD20702D0827A032A03D0A6 +:1055B0000022CA7212B102E00122FAE7DC72C94A83 +:1055C00090F82F00107032E0CC4B828A1A808069EC +:1055D00042F2107290FBF2F0C94A10808D7326E0FF +:1055E000C84B102A1A7001D910221A700022C64E18 +:1055F000C64FDFF81CC3DFF81C931D7815E000BF11 +:1056000002EB420300EB830393F8088006F8028064 +:1056100093F8098007F8028093F80B800CF8028059 +:1056200093F80C8009F80280521CAA42E8DB487B00 +:105630008A7B104097D04C738C73012093E72DE93F +:10564000F041A64900240A4691F809E092F807C003 +:10565000157A0CEB0003D78ADEB22246BEF1090FA1 +:1056600051D2DFE80EF008050F151C233343490023 +:10567000622803D04A72B52802D044E0022033E009 +:10568000012031E003224A720873C87108723AE0BF +:1056900004224A72CE7172190A72887233E00522AE +:1056A0004A72CE7172190A72C8822CE006234B72BC +:1056B000731907EB0020CE7180B20B72C882B0F56F +:1056C000007F01D9CA824A720A831CE0CE71721926 +:1056D0000A720A8BC82A01D2864B9854521C90B287 +:1056E0000883B8420FD1072048720CE008234B72A0 +:1056F000844508D04A7206E04A72854203D1FFF71A +:105700001CFF00B1012420468BE670B50346002043 +:105710000246054611E02E2C04D1521C00290FD060 +:1057200054181D559C5C00EB80004000A4F130062D +:10573000092E01D830382044521C9C5C002CEAD140 +:1057400070BD2DE9F04100268046354637460446B7 +:1057500004F00AFF016800E0641C2078085C20283F +:10576000FAD0404609E01EB106EB86025206160E3C +:1057700010F8012B303E3244D6B2221A022AF2DC53 +:1057800009E01DB105EB85025206150E10F8012B3C +:10579000303D2A44D5B28442F3D820782E280ED149 +:1057A000641C002007EB8702570022788B5C202BBB +:1057B00002D1303F1744641C401C0428F2DB5648D9 +:1057C0000621454307EBC70000EB071005EB8000FF +:1057D000B0FBF1F051494E4300EBC61021E62DE934 +:1057E000F04700273D4C0546242815D0414E204661 +:1057F000F03EC0782C2D13D02A2D11D021460D2D2E +:10580000497964D00A2D62D00F2802D23554401C49 +:10581000E07000295CD0BAE0A770E7702771B6E0AD +:105820003754A0784FF0010928B1A179012921D07E +:1058300002294ED0A2E0A7713078472807D17078AE +:10584000502804D1B078472802D0522809D095E0DA +:10585000F078472804D13079412801D184F80690A6 +:105860008CE0F0784D2804D13079432801D1022012 +:10587000A07183E0DFF8708002280CD003280FD0DD +:10588000042816D0052819D0062849D0072850D05A +:10589000092855D072E01748F038FFF752FF05E0AD +:1058A000307853286AD1D8F800004042C8F8000088 +:1058B00064E01048F038FFF744FF05E030785728DF +:1058C0005CD1D8F804004042C8F8040056E063E018 +:1058D0005AE03BE08096184B35FA8E3CB40200202B +:1058E000680A0020CB000020440100204C01002069 +:1058F000A8010020B00D00206E01002070010020E2 +:105900005E01002072010020D20A0020E20A00207D +:10591000F20A0020020B002040420F002D3101004E +:105920003078302801D9012000E00020FE49C872FB +:1059300024E00021FD48FFF7E8FEFD4908701DE066 +:105940000021FA48FFF7E1FEFA4916E0072802D0E5 +:1059500008280DD012E00121F448FFF7D6FE41F2ED +:10596000184148434FF47A71B0FBF1F0F24904E07A +:105970000121EE48FFF7C9FEF0490880A078401CDD +:10598000A070E7702A2D04D0207968402071002093 +:10599000A6E584F80590FAE70029F8D0307800F001 +:1059A000C7FA0501707800F0C3FA28442179C0B223 +:1059B00088426771EBD1A0790128E8D190E52DE903 +:1059C000FF5FDF49C0B291F81C1119B1012904D061 +:1059D00002297CD1FFF703FF01E0FFF730FE00282A +:1059E00075D0D24C1034A068E06002F072F9A0606B +:1059F0002020FBF751FFD3484FF0000B017801291D +:105A000010D001210170C848C17A00295FD0C8496F +:105A1000097805295BD38246407830B19AF80C109A +:105A200031B108E080F800B0EDE78AF80CB002E090 +:105A300008B1FFF76AFDC44805218E460278C44CC0 +:105A4000521CB2FBF1F301FB1322C049027000208B +:105A500091F90090BC4954F820306831BA4D41F8B2 +:105A60002030BC49783593FBF1F145F82010BA4D50 +:105A700000EB80074D4303EBC51342F2107593FB17 +:105A8000F5F5AEB2B04D403525F81060A74DC835DC +:105A900005EB8707AC4D57F822C0603555F82080DC +:105AA00047F82230A8EB0C0C634445F8203093FBF8 +:105AB000FEF3A94D6D42694303EBC111A24B703354 +:105AC000B9F1010F43F8201007D1B61E00E080E0C5 +:105AD000B6F5797F01D844F82010401C0228B9DBC4 +:105AE00002F0F7F8984D296A401A04F0D2FE9B495B +:105AF00004F07AFEA86202F0ECF82862A86A4FF07F +:105B00007E51884200DB0846A86203A902A8944B94 +:105B1000CDE900011A1F211D8D48FFF744FC0298B2 +:105B20006426B0FBF6F08F498F4A574608800398E9 +:105B300090FBF6F010809AF80C0018B9A1F800B0AC +:105B4000A2F800B0FFF76FFC387A10B9F879002896 +:105B50003FD07D49343101F1080000F11C07CDE947 +:105B600000013B1D3A46211D7948FFF71CFC231D0F +:105B7000774A391D3846FFF7FFFB744C94F9000053 +:105B8000012828D0022824D1784F0121B7F9BE007E +:105B900000F0ABF9FFF71DFB97F8BA00744A18B193 +:105BA000686C90FBF6F01080B7F8B600E96B88429D +:105BB0000BD2D5E90D01401AFFF758FA002800DC96 +:105BC000404242F21071884203DD01202070A88A11 +:105BD0001080BDE8FF9FFFF770FBFAE72DE9F04763 +:105BE000624C607904F055FEDFF88891494604F074 +:105BF000FBFD4E4D20352860E07B04F04AFE49460F +:105C000004F0F2FD5C4EEE606860A07904F041FEA5 +:105C10005A4F394604F0E8FD10352860207C04F026 +:105C200038FE494604F0E0FD6860A07E04F031FED5 +:105C3000DFF82881414604F0D7FDC5E90206E07986 +:105C400004F027FE394604F0CFFD10352860607C53 +:105C500004F01FFE494604F0C7FD6860E07E04F0D2 +:105C600018FE414604F0C0FDC5E9020638E42DE9FE +:105C7000F0412E4C064610340027032527704FF4C0 +:105C80008070FBF716FE002819D0667002F021F82C +:105C9000C4E901702A4890F81C0100B90125FFF7FA +:105CA0009DFF374906EB46002B4651F82020354929 +:105CB000354802F09DF9354948600120207023E500 +:105CC0002DE9F041194C032710341D4A60782F4DFF +:105CD00000EB400192F81C31294E686813B1012B8A +:105CE0001ED105E056F8211003F0DEFB27700BE50E +:105CF0002378012B4CD056F8211003F0D5FBDFF8A8 +:105D00008080002608F13C08686818F8061003F047 +:105D1000B5FB042001F0ECFF761C8C2EF4D3277029 +:105D200000206060F0E40000680A0020C00C002041 +:105D3000CB0000206E010020700100205E010020D9 +:105D4000640400205C010020B4020020C100002097 +:105D50004401002080969800D3CEFEFF00007A44D4 +:105D6000500100206A0100206C010020E0070020A3 +:105D7000AA0100200000C8420000FA4400002041AF +:105D800078C60008BF59000800440040D40800202D +:105D90000027904607EB470056F82010686803F08C +:105DA00083FB98F91D0100EB400006EB8000416881 +:105DB000686803F066FBC82001F09AFF7F1C052F7E +:105DC000E8DB98F81D01607002202070A8E710B58C +:105DD0005E4C207805282AD2DFE800F02903031C56 +:105DE0000600BDE810406BE760680521401C60605C +:105DF0006078401CC0B2B0FBF1F201FB1200607091 +:105E000001F067FF5249A060002008705149C87234 +:105E100001200BE001F05DFFA168401A40F6C411BB +:105E2000884204D92020FBF73CFD0420207010BDDF +:105E30002DE9F05FDFF814A10024474FDFF81C8143 +:105E4000DFF81C910AF1400A25460AF1280B00BF31 +:105E500027F8145028F8145004EB840629F814503D +:105E60000AEB860000F06DF80BEB860000F069F895 +:105E70003648903000EB860000F063F8641C022C7A +:105E8000E6DBBDE8F09F7CB5364C0268226009680D +:105E900061600068FFF726FBA4F1240101F108000E +:105EA000314ECDE90001231D2246311D3046FFF75A +:105EB0007AFAA4F15805331D686B68643246211DD7 +:105EC0002046FFF759FA686BA8632848B0F8BC0071 +:105ED00068827CBD10B50C4604F0D2FC216804F049 +:105EE0004DFCBDE8104004F0D9BC70B51D4C583CC9 +:105EF000E26B21B1B0EB520F0BD3500809E0904296 +:105F000000D31046194900B2B1F8BC10814200DB41 +:105F10000846B4F9125000B2A84208DD1449A06A3C +:105F200004F02CFC04F0BAFC284400B2608270BD7E +:105F30003038C0B2092801D9C01FC0B200F00F002C +:105F4000704700210160416081607047D00C0020E3 +:105F5000CB000020680A002004010020240100205A +:105F6000200100200C03002044010020E007002055 +:105F70000000C842F0B5404A404C1178E9B192F8AF +:105F800005C01779032104F11C035E1816F8015CA3 +:105F9000FD4005F00F05072D09D213F801E016F8B2 +:105FA000016C06EA0C060EEB062644F82560891CF7 +:105FB000C9B21029E9D300211170314907280ED246 +:105FC000937863B151782E4A104490F80A0149B190 +:105FD00054F820004FF4777101EB500006E0B1F85F +:105FE0001401F0BD34F8200000F5777080B2F0BDE8 +:105FF00070B5214C01260546A67001F050FEA1683F +:10600000421AC4E9020241F288300021824200D9DA +:10601000E1701A4AE0781C3215540F2802D0401C57 +:10602000E07070BD17482670018070BD70B50446E1 +:106030001348114990F81221032007252AB1012A9B +:1060400008D108714D71012003E002220A714871E4 +:106050000020487001234FF4E1320B490B4801F056 +:10606000C7FF01460A48C1600CB10A492160457466 +:1060700070BD01480078704734030020780E00207E +:1060800064040020CE000020F15F000800440040BE +:10609000D4080020755F000870B57C4C06460125C9 +:1060A000207880B901F015FEA1683231884207D30B +:1060B0002570012001F027FE01F00BFEA06070BDED +:1060C00020780028FBD001F004FEA168314488420A +:1060D000F5D30020207001F016FE01F0FAFD6C49A6 +:1060E000A060087808B1401E0870657070BDF8B5F2 +:1060F000664D8DF800008DF801108DF802208DF8A6 +:106100000330A8791DF8001044292DD04C2929D03E +:106110004D2925D04E292AD032240026032806D224 +:1061200074B12046FFF7B8FFA879032808D301F01F +:10613000D0FDA968001B884202D95548AE7106708F +:106140006878012801D0002C09D1A879032801D250 +:10615000401CA8716E702E70002001F0D4FDF8BDB7 +:106160006424DAE7C824D8E74FF4FA64D5E70024BA +:10617000D3E72DE9F047DFF81CA10546434C9AF818 +:106180000D004FF00109002610B184F8029000E0E4 +:10619000A6704FF40070FBF78CFB3F4F18B33F49DC +:1061A0003F484FF0020C91F8AC30B0F9000003EB1F +:1061B000830282420FDA97F80180B8F1000F0AD00B +:1061C00084F8049091F8AD10194401EB81018142EB +:1061D00001DA84F804C0824203DA797809B984F8D4 +:1061E00004C000B926712020FBF74EFB40B19AF89D +:1061F0000A1011B99AF80B0008B1F87AA8B1E67044 +:106200002079022814D0012817D0E078012817D06F +:10621000A078012817D0042D19D0022D1ED0012DF1 +:106220001ED0607901281ED022E084F80390E7E7B1 +:106230004E22442311464C200DE04D234C2208E011 +:106240004D234E2201E04D235322532102E04423EB +:106250004D224D215320BDE8F04748E7442305E097 +:1062600044234E22F5E7787810B14E234D22ECE717 +:106270000748007818B1BDE8F04732200CE72670D7 +:10628000BDE8F047002001F03EBD000044030020BF +:10629000C0000020BE0A0020680A0020E00700209D +:1062A000CE00002010B5D84C5E28A26807D05D282B +:1062B0000CD001461046BDE8104003F0DFB85D2168 +:1062C000104603F0DBF83E21A068F4E75D2110469C +:1062D00003F0D4F83D21A068EDE72DE9F04113204B +:1062E00000F04AF9C94C2068002800DC4042C84D43 +:1062F00090FBF5F000B200F051F91B2000F03CF9E2 +:106300002068002800DC40420A2690FBF6F042F2AA +:10631000107790FBF7F107FB110000B200F03EF997 +:10632000232000F029F92068002801DA532000E03A +:106330004E2000F033F9122000F01EF960680028AA +:1063400000DC404290FBF5F000B200F027F91A2083 +:1063500000F012F96068002800DC404290FBF6F083 +:1063600090FBF7F107FB110000B200F017F92220B3 +:1063700000F002F96068002801DA572000E04520AB +:10638000BDE8F04100F00AB910B54FF40040FBF74A +:1063900090FAA04A9C4920B192F82901012806D020 +:1063A00002E0002082F829010868886010BD9A4840 +:1063B000FBE770B5974890F8291111B9974A5278C0 +:1063C0000AB1012400E00024954D2A78944209D0B6 +:1063D00039B914B14FF4165001E0D0F82001FEF79E +:1063E0002CF92C7070BD2DE9F0478A4890F82901EE +:1063F00018B98A48407800287ED08348806803F026 +:106400004DF8002878D101F064FC854D6968401A88 +:106410007D2871D301F05DFC68606878814F401C75 +:10642000DFF80482DFF804926870002404F124008D +:10643000C0B200F0A1F8388804F02BFA064638F90B +:10644000140004F01DFA314604F0CEF9494604F078 +:1064500095F904F023FA00B200F0A0F8641C032CB4 +:10646000E4DB00F096F868784FF06404800724D1EC +:10647000102000F081F86E4E306890FBF4F000B20E +:1064800000F08CF8212000F077F8306890FBF4F1F0 +:1064900004FB110000B200F081F8142000F06CF849 +:1064A0006448B0F9000000F079F81C2000F064F8AE +:1064B000002000F073F800F06CF86878400735D1E0 +:1064C000022000F059F85C484FF00A08B0F90010BB +:1064D00091FBF8F000B200F061F80220FBF7E9F957 +:1064E000E0B100F065F855486E2100784843152169 +:1064F000B0FBF1F63A2000E03CE000F03DF8B6FBDE +:10650000F4F738B200F04AF83B2000F035F804FB0D +:106510001760401DB0FBF8F000F040F82020FBF7BA +:10652000B3F908B1FFF7D9FE00F033F868782828EE +:1065300020D10020687001F0CCFB4FF47A71B0FBE1 +:10654000F1F43C25B4FBF5F6B6FBF5F005FB10675E +:10655000172000F011F8380200B200F01FF81820E0 +:1065600000F00AF805FB164000F018F8BDE8F04707 +:1065700000F00FB8BDE8F08770B5234C05465E21EA +:10658000A06802F07BFF2946A068BDE8704002F0D9 +:1065900075BF1D485E21806802F070BF10B50446CB +:1065A000C0B2FFF77FFEC4F30720BDE8104079E6D4 +:1065B00070B52248224E40F6340200783178184DEA +:1065C000B0FBF1F050432A22B0FBF2F06A88B2FB34 +:1065D000F1F301FB13214FF6FF7202EA011141EAC8 +:1065E0000024C0F3032004430620FFF7C5FF20B2B8 +:1065F000FFF7D4FF68883178401C80B2B0FBF1F21D +:1066000001FB1200688070BDD40800204401002006 +:10661000A086010064040020D0140020680A002035 +:10662000500300207A0100207C00002000007A4402 +:1066300024000020A8010020E0000020CA00002063 +:1066400060010020884201DA084670479042FCDD74 +:10665000104670472DE9F047BD49BD48E831B0F913 +:10666000E600B1F90050B1F9024010B90DB9002CA3 +:106670007ED0B84A0021117004F002F9B64F3946B5 +:1066800004F07CF8DFF8D492494604F0ADF8804677 +:10669000284604F0F5F8394604F070F8494604F04D +:1066A000A3F80646204604F0EBF8394604F066F8F5 +:1066B000494604F099F80746304604F0C3FD044605 +:1066C000404604F0BFFD214604F058F8A44C206079 +:1066D000384604F0B7FD0546404605F00DF829465A +:1066E00004F04CF80546384605F006F88246304678 +:1066F00005F002F88146404604F0A4FD494604F046 +:106700003DF8514604F03AF8294604F031F860604B +:10671000384604F0F1FF0546404604F0EDFF2946F7 +:1067200004F02CF80546384604F08CFD82463046CD +:1067300004F0E2FF8146404604F084FD494604F03F +:106740001DF8514604F01AF8294603F0BFFFA06077 +:10675000304604F077FD0546404604F0CDFF29465B +:1067600004F00CF8E060384604F06CFD054600E0EB +:1067700057E0404604F066FD294603F0FFFF05465A +:10678000384604F0B9FF8246304604F0B5FF814632 +:10679000404604F0B1FF494603F0F0FF514603F0D4 +:1067A000EDFF294603F092FF2061384604F0A4FF74 +:1067B0000546404604F046FD294603F0DFFF054646 +:1067C000384604F03FFD8246304604F095FF81468E +:1067D000404604F091FF494603F0D0FF514603F0D4 +:1067E000CDFF294603F0C4FF6061304604F084FF0A +:1067F00080F00040A061384604F07EFF0546304638 +:1068000004F020FD294603F0B9FFE061384604F0AA +:1068100019FD0546304604F015FD294603F0AEFF8C +:106820002062BDE8F0872DE9F0470546B0F9008009 +:10683000B0F90260B0F9040004F022F8484C824636 +:10684000A16803F09BFF0746304604F019F8814623 +:10685000616803F093FF0646404604F011F8804655 +:10686000216803F08BFF314603F030FF394603F017 +:106870002DFF04F013F828805046616903F07EFF75 +:1068800007464846216903F079FF06464046E1681D +:1068900003F074FF314603F019FF394603F016FF89 +:1068A00003F0FCFF68805046216A03F067FF07464B +:1068B0004846E16903F062FF06464046A16903F0DD +:1068C0005DFF314603F002FF394603F0FFFE03F09F +:1068D000E5FFA880A5E7092A11D2DFE802F010053C +:1068E00009161C21262A2E0002880A80428803E00D +:1068F00042880A8002880CE04A8080888880154897 +:106900000078002822D108468DE7028852420A808A +:1069100042885242F0E7428852420A800288EBE7FE +:10692000028852420A8042880CE042880A8002882B +:1069300008E002880A80428803E0428852420A80C6 +:10694000028852424A8080884042D7E77047000060 +:106950006404002058030020DB0F4940000034434A +:10696000A40E002044490844444990F80A0151F813 +:1069700020004FF4777101EB500080B2704710B5E2 +:10698000044601F08CF93E4902464868131A00207B +:10699000B3F57A6F00D948704A604A780AB90F2C6B +:1069A0000AD1087032B1354B20331344182A03F84A +:1069B000014C02D0521C4A7010BD304A2032D27DA8 +:1069C0000AB901220A70487010BD10B504462A4861 +:1069D00000212A4BB0F814014200A2F5F76200BF73 +:1069E00043F82120491C0829FADB0123254A2649BE +:1069F000264801F0FDFA01462548C1600CB1254941 +:106A000021600821417410BD1D4B10B5187840B1AC +:106A10001A484FF000022030817DC908C90702D012 +:106A20001A70002010BD1C49401C0A8030F8011C5F +:106A3000C1F30A0411490C600488C4F3CA044C6011 +:106A40000468C4F38A348C60B0F80340C4F34A0489 +:106A5000CC608488C4F30A140C614468C4F3CA345B +:106A60004C61B0F80740C4F38A048C610089400986 +:106A7000C8611A70012010BD64040020C80E0020F7 +:106A80005C030020A08601007F69000800440040EC +:106A9000D408002065690008CE0000202DE9F041EF +:106AA0000646007890B008B1012500E00025DFF827 +:106AB000D880404602F0BCFE3448009000243448A0 +:106AC000CDE90104012725B10220CDE9030480208E +:106AD00002E0CDE90374002005904FF48070069029 +:106AE00080000790202008900002CDE90904694643 +:106AF000404602F00AFF0121404602F030FF8DF8C7 +:106B000030500B948DF831704FF46020CDE90D04B6 +:106B10000DB1022000E001201C4C8DF83C004C3CE3 +:106B20000BA9204602F0F0FD032301220421204698 +:106B300002F03FFE2DB1317803230222204602F0FD +:106B400038FE0121204602F008FE0121204602F015 +:106B5000FAFD204602F00BFE204602F00DFE002852 +:106B6000FAD1204602F00FFE204602F011FE002866 +:106B7000FAD10121204602F012FE10B0BDE8F081EA +:106B8000034931F810007047080002404C240140CE +:106B9000640300202DE9FF47DFF86C81814698F8F7 +:106BA0000000D0B300273E463D463C46641CE4B29C +:106BB00002AB08223221532000F063FD9DF808004B +:106BC0009DF80910202C00EB012000B207449DF82D +:106BD0000A009DF80B1000EB012000B206449DF85E +:106BE0000C009DF80D1000EB012000B205449DF84B +:106BF0000F0000F07F0001D20028D7D197FBF4F0FE +:106C0000ADF8000096FBF4F0ADF8020095FBF4F04F +:106C1000ADF8040088F802401EE0FFE702AB062250 +:106C20003221532000F02DFD9DF808009DF8091039 +:106C300000EB0120ADF800009DF80A009DF80B1054 +:106C400000EB0120ADF802009DF80C009DF80D103E +:106C500000EB0120ADF8040098F801204946684691 +:106C6000FFF739FEBDE8FF8770B5274D04464FF0AA +:106C7000080228784FF02D0100284FF053000ED065 +:106C800000F0F9FC0A223121532000F0F4FC0C2220 +:106C90002C21532000F0EFFC9022382108E000F076 +:106CA000EAFC0A223121532000F0E5FC0A222C21C3 +:106CB000532000F0E0FC154940F20910002C088038 +:106CC00000D06C7070BD38B5054600208DF800000E +:106CD0000F480C460F49006888420AD06B460122D3 +:106CE0000021532000F0CDFC18B19DF80000E528EC +:106CF00001D0002038BD044928780870064820607B +:106D000006486060012038BD680300207A01002039 +:106D100004040020001BB700696C0008956B000894 +:106D200010B54FF48044204602F076FE012805D1CC +:106D3000204602F07FFEB9490120087010BD70B5F1 +:106D40000D46B649B64A064688885389B2F91440BA +:106D5000C01A13895843B2F91230C013DB0204443D +:106D600093FBF4F31844D06100EB8000082202EB9F +:106D700040000411886800F0D0F806B13060002DA2 +:106D800000D02C6070BD38B5A44C207810B9608854 +:106D9000401C60806B460322F621772000F071FCD6 +:106DA0009DF800009DF80110000440EA01209DF8C4 +:106DB000021008439A49B1F92010C1F10801C840F6 +:106DC000A06038BD9648342190F8200001EB801077 +:106DD0009249C2B200200870F421772000F04BBC29 +:106DE00038B58E4C207810B96088401C60806B46A6 +:106DF0000222F621772000F044FCBDF8000040BAE2 +:106E0000A08038BD854900202E220870F42177200B +:106E100000F031BC2DE9F04304468248824985B038 +:106E20000068884203D1002005B0BDE8F083DFF898 +:106E3000EC9199F8010008B10120F5E74FF40055F5 +:106E4000ADF80C5002208DF80F001020774E8DF811 +:106E50000E0003A9304601F039FF6F00ADF80C7049 +:106E600004208DF80E0003A9304601F02FFF356194 +:106E70000E21022003F052FA00208DF808000820AD +:106E80008DF809004FF00108019747468DF80A80F8 +:106E900001A802F08BFD28208DF810000F208DF83E +:106EA00011008DF812008DF8137004A802F0F9FBA0 +:106EB000142000F01DFF6B460122D021772000F046 +:106EC000E0FB574F9DF800000321F87539845528E1 +:106ED00001D07561A7E76B460122D121772000F030 +:106EE000D0FB9DF8000000F00F013976000978769C +:106EF00000F05CF889F8018041F27070208046F65D +:106F0000781060804A4860604A48A0604A48E06063 +:106F10004A4820614A4860618EE770B54049CA69B5 +:106F2000B1F90E40A2F57A6202FB02F31D136C4325 +:106F3000E512B1F90240B1F90460544305EBE424D1 +:106F4000B1F9005004EB850591F82040A540564367 +:106F50007213B1F90C601B135E4302EB2642921CC4 +:106F60009210C98802F50042AD1C5143C90B4CF286 +:106F70005032A0EBA500E2405043B0F1004F03D2E5 +:106F80004000B0FBF1F002E0B0FBF1F04000011274 +:106F9000494340F6DE3251432A4A0914424301EB89 +:106FA000224101F6CF6100EB211070BD00B587B022 +:106FB0006B461622AA21772000F063FBBDF8000083 +:106FC00041BA17480180BDF8021049BA4180BDF8A6 +:106FD000041049BA8180BDF8061049BAC180BDF8D5 +:106FE000081049BA0181BDF80A1049BA4181BDF8BB +:106FF0000C1049BA8181BDF80E1049BAC181BDF8A3 +:10700000101049BA0182BDF8121049BA4182BDF888 +:10701000141049BA818207B000BD00006C03002043 +:10702000040F002004040020001BB70000100140E2 +:10703000056E0008E16D0008C56D0008876D000849 +:107040003F6D000843E3FFFF38B5044600208DF88C +:1070500000006B4601220A211E2000F012FB18B12D +:107060009DF80000482801D0002038BD0CB18D48A3 +:107070000470012038BD7FB5054602AB062203210E +:107080001E2000F0FEFABDF8080040BA00B203F07E +:10709000F7FB844C241D216803F070FB03F0FEFB1A +:1070A000ADF80000BDF80A0040BA00B203F0E8FBFA +:1070B000A16803F063FB03F0F1FBADF80400BDF839 +:1070C0000C0040BA00B203F0DBFB616803F056FB32 +:1070D00003F0E4FBADF80200201F29460278684661 +:1070E000FFF7F9FB7FBD2DE9F0476F4800246F499A +:1070F000006825468EB02E464FF0010888420CD11C +:107100004FF48050ADF8280002208DF82B000420A9 +:107110008DF82A000AA9664808E06649884207D126 +:107120004FF48040ADF828000AA9634801F0CEFD75 +:10713000322000F0DDFD112200211E2000F09BFA1C +:10714000602201211E2000F096FA642000F0D0FD9C +:107150006846FFF790FFDFF858A1DFF8609100273D +:107160000AF10C0A012202211E2000F084FA3220CA +:1071700000F0BEFD6846FFF77EFFBDF90210BDF9C5 +:107180000400BDF900200D4414440644814201DA94 +:107190000B4600E00346934201DD104602E08142C7 +:1071A00000DA0846484502DC4FF0000808E0DAF84B +:1071B000001081F01001CAF800107F1C0A2FD1DBEB +:1071C000122200211E2000F056FA0027012202217F +:1071D0001E2000F050FA322000F08AFD6846FFF7CA +:1071E0004AFFBDF90020BDF90210BDF90400A41A40 +:1071F0006D1A361A814201DA0B4600E003469342CB +:1072000001DD104602E0814200DA0846484502DC12 +:107210004FF0000808E0DAF8001081F01001CAF819 +:1072200000107F1C0A2FD1DB204603F029FB244FDE +:107230000146384603F0D8FA1A4C20F00040241DCD +:107240002060284603F01CFB0146384603F0CCFAC8 +:1072500020F000406060304603F012FB0146194800 +:1072600003F0C2FA20F00040A060702200211E202E +:1072700000F001FA202201211E2000F0FCF900227A +:1072800002211E2000F0F7F9642000F031FDB8F172 +:10729000000F04D14FF07E5020606060A0600EB0FF +:1072A000BDE8F087780300200404002000127A0073 +:1072B000000C0140001BB7000010014000F0FFFF70 +:1072C00000406F4601C05E4630B587B005464FF4BA +:1072D0004060ADF8140002208DF817001C208DF8D6 +:1072E000160005A9FB4801F0F1FCFB4CE56000F03D +:1072F00007FAE06802F0A4FB684602F00CFC0022EA +:107300004FF44071E06802F03CFC0025ADF80450F9 +:107310004BF6FF70ADF806004FF48040ADF80C005E +:10732000EE4800900121E06802F003FC6946E06845 +:1073300002F099FB4FF4A06002F0AEF922208DF824 +:1073400010008DF811508DF8125001208DF81300A7 +:1073500004A802F0A6F921208DF810008DF8115034 +:1073600004A802F09EF907B030BD38B5DA4CE068E9 +:10737000818A009111F4706F01D001212170009970 +:1073800011F4E06F25D0018B00224FF4806102F0F0 +:10739000F8FB009880051CD4E0680188890518D4A2 +:1073A0000188C9050CD50188C905FCD4012102F06A +:1073B000D4FBE06801888905FCD4FFF785FF08E06D +:1073C000012102F0CAFB00224FF44071E06802F094 +:1073D000D8FBE068818A21F47061818200202071ED +:1073E00038BDC2E72DE9F041BB4CE068818A4FF01F +:1073F0000105C9B2CA074FF0000627D0018821F461 +:1074000000610180012102F0B2FBE670607A20B1D8 +:10741000607860B9A079FF2809D061790022E0681E +:1074200002F0BCFBA079FF2848D0FF20C9E06570BE +:10743000E079022804D1E068018841F4006101800C +:1074400061790122E06802F0A9FB37E08A074FF476 +:10745000806745D5BFF3508FE079012810D1607A5D +:1074600070B1607860B10021E06802F080FBBFF38A +:10747000508FE068018B012102F06FFBA57018E0CE +:10748000E068008BBFF3508FE079022808D1607A62 +:1074900030B1607820B10021E06802F068FB06E0BE +:1074A000E079032805D1607A18B1607808B100222C +:1074B00000E001223946E06802F063FB94F9031012 +:1074C000E079401C814209D16670A07828B1002281 +:1074D0004FF44071E06802F054FB2671BDE8F08182 +:1074E0004A0753D5A570627A7B494978CAB3C9B3B4 +:1074F000E17902291FD9002102F039FBE06802F08E +:107500004AFB94F9031062695054491CE17001214F +:10751000E06802F022FBA570E06802F03CFB94F901 +:10752000031062695054491CE17001223946E06839 +:1075300002F027FB25E0012102F00FFBE06802F0DA +:107540002AFB94F9031062695054491CE170E06809 +:1075500002F021FB94F9031062695054891CE17018 +:107560000FE000E000E009B9217A31B1012102F019 +:10757000F4FAE078401CE07003E0012102F0E3FA45 +:107580006570E0680188C905FCD497E74A061AD5FA +:1075900002F001FB94F9031062695054491C48B28F +:1075A000E070E179C01C814204D100223946E068D4 +:1075B00002F0E7FAE17994F903008142E5D100F1A4 +:1075C0000100E0707AE70906DFD594F903104B1C3F +:1075D0005AB20BD02369595CE27002F0DAFAE07912 +:1075E00094F9031088423FF45AAF67E7E270A1793B +:1075F00002F0CFFA607A00287FF451AFE0790028DA +:10760000F1D05BE7EEE6B0E6ECE670B5324C4FEA5F +:10761000400047F230556071A171012020720021B5 +:10762000617223616361E27120712170E068818879 +:1076300089050ED40188C90505D401888905FCD4C3 +:10764000012102F080FA01224FF44071E06802F05B +:1076500098FA207910B16D1EFBD104E01DB120789D +:1076600080F0010070BD6089401C6081E068FFF718 +:107670002BFE002070BD07B502AB0122FFF7C5FF4E +:107680000EBD70B5144C4FEA400047F230556071A2 +:10769000A171002020720121617263612361E27196 +:1076A00021712070E068818889050ED40188C905A0 +:1076B00005D401888905FCD4012102F044FA012295 +:1076C0004FF44071E06802F05CFA207940B16D1E21 +:1076D000FBD10AE0000C014088030020801A06005C +:1076E0001DB1207880F0010070BD6089401C608170 +:1076F000E068FFF7E9FD002070BD2A484089704727 +:107700002DE9F84F4FF44067ADF800704FF0020AD2 +:107710008DF803A01420DFF890B08DF802006946C0 +:10772000584601F0D3FA204D10352F60DFF87890DD +:1077300000262C1505F1040809F1080902E00A20C9 +:1077400000F0CAFAD9F800004005F8D5C8F80040A2 +:107750000A2000F0C1FA2C600A2000F0BDFA761C65 +:10776000F6B2082EEED34FF400694646C8F80090F2 +:107770000A2000F0B1FA34600A2000F0ADFA2C6063 +:107780000A2000F0A9FAC5F80090ADF800708DF855 +:1077900003A01C208DF802006946584601F096FAB5 +:1077A000BDE8F88F88030020000C014038B504467E +:1077B0006B4602221B216820FFF763FFBDF8000023 +:1077C00043F2903140BA08444FF48C71B0FBF1F0B1 +:1077D0002330208038BD1FB5044602AB06221D2190 +:1077E0006820FFF74EFFBDF80800214640BA02B2FC +:1077F000D01702EB90708010ADF80000BDF80A00C1 +:1078000040BA02B2D01702EB90708010ADF80200BF +:10781000BDF80C0040BA02B2D01702EB9070801095 +:10782000ADF804002F4842786846FFF754F81FBDB2 +:1078300070B50446192000F05BFA0022152168207B +:10784000FFF719FF10B9032000F0FCFA254D1621AF +:10785000287840F018026820FFF70DFF002217215A +:107860006820FFF708FF01223D216820FFF703FF92 +:1078700001223E216820FFF7FEFE002C00D06C7034 +:1078800070BD70B504460D46192000F031FA002293 +:1078900015216820FFF7EFFE00281CD01248206059 +:1078A000124860601248A0601248E0600D48622DE6 +:1078B00012D004DC0A2D13D0142D05D10EE0BC2DFE +:1078C00006D0B5F5807F01D0032102E0002100E061 +:1078D00001210170012070BD0221FAE70421F8E7BF +:1078E0000521F6E7A003002031780008D7770008CB +:1078F000AD77000818449231FEB5064614460D4691 +:10790000684602F025FC0120ADF804000021ADF826 +:107910000050ADF80610ADF80810ADF80240694609 +:10792000304602F065FBFEBD70B51646D04A02EB4C +:107930000015D04A02EB00140122206801F0EFFA92 +:10794000D4E90101182200F087F9217B3246206832 +:1079500000F03FF9A07B18B10121206802F00AFC79 +:107960000121206802F0FCFB207B30B1042807D005 +:1079700008280AD00C2806D10AE02068343001E03B +:10798000206838302860284670BD20683C30F9E710 +:1079900020684030F6E72DE9F0410546B4480F462F +:1079A00000EB0516B348B27100EB05142822D4E9A8 +:1079B000010100F051F9217B00222068FFF79CFFB4 +:1079C00001224FF6FF71204601F0C6FA3A462946D9 +:1079D000204601F087FA3046BDE8F08170B5A64830 +:1079E0000024028942810181891A8BB240F68C21E0 +:1079F0008B4201D9C47070BD9F49A3F2EF2540F2BC +:107A0000DB569E4AC978B5421BD2082919D2984D37 +:107A1000E035042925F8113007D2C588AB4204D9D6 +:107A2000012305798B402B43037103790F2B08D178 +:107A30000471B2F90030142B02DD143B138000E016 +:107A40001480491CC170148070BD70B5884A894B80 +:107A500002EB001203EB0013D47918681B7B8CB186 +:107A600051811489824D091B91819479E03525F863 +:107A700014100024D47122461946FFF73DFF7F48B9 +:107A8000048070BD11810121D171BDE870400222D6 +:107A9000194631E72DE9F0470446774DE18900208A +:107AA000E980A17901B10220617801B1401C7449DB +:107AB000DFF8D081002651F820704FF47A79BA5D52 +:107AC00002F00F0002F0F001FF2A65D0A2781AB18F +:107AD00002285ED003285CD0E2783AB1042858D05E +:107AE000052856D0062854D0072852D0E2790AB18A +:107AF00082424ED011F0300F02D0227802B900211C +:107B0000227932B1A27922B9082801D0092800D1FE +:107B1000802162792AB1A2791AB9021F032A00D8FA +:107B20008021CA0605D500225749FFF734FF0820F7 +:107B300008E08A0608D5AA785449FFF72CFFA878F0 +:107B400000F10100A87024E04A0612D52289B8FB92 +:107B5000F2F1A28989B202B94A46FFF7E5FE014671 +:107B6000434A2878F03242F8201000F101002870D2 +:107B70000FE009060DD56289B8FBF2F189B24A46D9 +:107B8000FFF7D2FE0146424A687842F82010401CB6 +:107B90006870761C0E2E92DB0020BDE8F087364A16 +:107BA0001278904205D23A4A303A52F820000068E2 +:107BB00001807047304A5278904204D2344A52F8D9 +:107BC00020000068018070473149403931F81000C9 +:107BD00070477FB5064615460C46684602F0AEFA79 +:107BE0007020ADF800000120ADF802000020ADF8D3 +:107BF00004000220ADF80800C001ADF80650ADF851 +:107C00000C0074B1042C15D0082C1CD00C2C07D1FE +:107C10006946304602F038F90821304602F0D3FABE +:107C20007FBD6946304602F084F80821304602F0F4 +:107C3000B4FA7FBD6946304602F0B0F808213046FC +:107C400002F0B1FA7FBD6946304602F0E3F8082140 +:107C5000304602F0B2FA7FBD08B5ADF800108DF8DD +:107C6000022002218DF80310694601F02FF808BDAB +:107C7000280F0020B4C70008A2030020CE00002077 +:107C800078C7000840420F00DD7900084B7A0008F1 +:107C90004810002080484168491C4160704710B579 +:107CA0007D484FF0E02341689A694468A142FAD1C7 +:107CB0000368006803EB4304C4EBC313C2EBC302C5 +:107CC000B2FBF0F001EB4102C2EBC11100EBC100CD +:107CD00010BD71484068704730B50546FFF7DFFFBB +:107CE0004FEA0004FFF7DBFF001BA842FAD330BDC8 +:107CF00030B504464FF47A7502E02846FFF7ECFFF2 +:107D0000641EFAD230BD6449896808474FF4805137 +:107D100008B1624801E06148001F016070474FF4FC +:107D2000805110B15D48001F00E05C480160704761 +:107D30002DE9F04F8DB018225949684602F041FCF8 +:107D4000032701F002FC0121564801F08DFF0121BB +:107D500044F61D2001F07FFF0121084601F072FF6B +:107D600001F09DFF4FF6FF70ADF818004B484FF043 +:107D7000000A8DF81AA006A9143800F0A7FF06A97A +:107D8000494800F0A3FF06A9484800F09FFF484873 +:107D9000416841F000714160464DDFF81C813E4E64 +:107DA0002968414501D1454800E04548B0600020C0 +:107DB000FFF7A9FF3C490820103108601020086037 +:107DC000A946002483466D46D9F80010414506D1E6 +:107DD00005EBC4008179142901D180F806B005EBC8 +:107DE000C401091D55F8340000F070FF641CBC424A +:107DF000EAD307A801F0E0FE32490798B0FBF1F0A2 +:107E0000306031484FF47A710068B0FBF1F0B0F1A6 +:107E1000807F0CD220F07F414FF0E020491E41616D +:107E20002A4AF0211170C0F818A0072101612848E2 +:107E3000FFF74AFA00F0B5FF6420FFF759FF0DB0D5 +:107E4000BDE8F08F184A1021143211600821121F6A +:107E500011600446151F40F2DB104443286880F08F +:107E600010002860286880F008002860A01EFFF736 +:107E70003FFF0120FFF747FF1920FFF739FF0020E0 +:107E8000FFF741FFEAE710B11349124808600F49B4 +:107E90001248173908607047B003002014080140E9 +:107EA00088C7000807004000000C01400010014096 +:107EB0000000014004040020001BB7001F7D0008E3 +:107EC0000D7D000840420F000004002023ED00E07B +:107ED00000580040EFBEADDEF04F00200400FA0570 +:107EE0007CB5FA4C0D46FA492160A060A4F53070CB +:107EF000606100F58070A0614FF48070E0602061E7 +:107F0000F4482063F348012114386063880301F0CA +:107F1000A2FE02208DF803000002ADF80000182038 +:107F20008DF80200EC4EA80703D56946304600F0F4 +:107F3000CDFE4FF48060ADF8000048208DF80200BF +:107F4000E80703D06946304600F0C0FE0E208DF8E9 +:107F5000040001208DF805008DF806008DF807005B +:107F600001A801F09EFB20467CBD2DE9FC41D74CC9 +:107F70000D464C34D6492160A0608020E06040204E +:107F80002061A4F5867060618030A061D348012132 +:107F9000A064480401F068FE02268DF80360042006 +:107FA000ADF8000018208DF80200CB4FA80703D5CC +:107FB0006946384600F08AFE0820ADF800004820E7 +:107FC0008DF80200E80703D06946384600F07EFECF +:107FD00026208DF8040001208DF805008DF806603C +:107FE0008DF8070001A801F05CFB2046BDE8FC818C +:107FF0002DE9F04389460646B9490024B7488FB0B9 +:108000001D4617468E4204D119461046FFF768FFF9 +:1080100005E0864204D119461046FFF7A6FF044644 +:108020004FF00008C4F82080C4F81C80C4F82880F1 +:10803000C4F82C90C4F82480A6642571A760ADF81C +:108040003080ADF834800B97ADF83280ADF83880D1 +:10805000ADF83680E80702D00420ADF83600A80756 +:1080600005D5BDF8360040F00800ADF836000BA984 +:10807000304602F0CFF80121304602F023F968467D +:1080800001F060FC301D00904FF48050CDE90908EC +:108090008020CDF81080CDE905084746CDF81C803A +:1080A000E80723D0206BD8B1E068CDE9027020202A +:1080B000089060690190206B01F0BAFB6946206B63 +:1080C00001F023FC0121206B01F049FC0122402139 +:1080D000304602F019F9206B01F056FC206405E0EF +:1080E000012240F22551304602F0F6F8A80724D5C7 +:1080F000606BE0B120690390102008970290606BDC +:1081000001F096FB6946606B01F0FFFB0122022142 +:10811000606B01F02FFC0021606B01F033FC606BA1 +:10812000476001228021304602F0EEF805E001228E +:1081300040F22771304602F0CFF80FB02046BDE87C +:10814000F0837FB504460020ADF80400ADF80800C8 +:108150000091ADF80600ADF80C00ADF80A002079EA +:108160000D46C00702D00420ADF80A002079800730 +:1081700005D5BDF80A0040F00800ADF80A006946D0 +:10818000A06C02F047F8A5607FBD826A8169114446 +:10819000426BD160D0E9092100238A4205D9511AE6 +:1081A000426B5160416A816204E00269511A426B7C +:1081B0005160836280F84430406B012101F0CFBBF5 +:1081C000016B11B14968006C01E01C3003C88142A9 +:1081D00001D00120704700207047416B11B190F829 +:1081E00044007047243003C8814201D10120704708 +:1081F0000020704710B50146036BC268406943B167 +:108200000B6CD21A805C5B1E0B6401D1CA680A64D5 +:1082100010BD0B6AC05C5B1CB3FBF2F402FB1432B2 +:108220000A6210BD436A8269D154416A0269491CDD +:10823000B1FBF2F302FB13114162416B19B1096802 +:10824000C90706D1A1E7806C012240F2277102F034 +:1082500043B8704710B51D4C4FF4005001F097FB28 +:108260000021606B01F07BFBD4E90901884203D057 +:108270002046BDE8104088E7012084F8440010BD86 +:108280001249886C028812060ED5D1E909329A4249 +:108290000BD08B699A5C8280886A0A69401CB0FBAB +:1082A000F2F302FB130088627047002240F227714C +:1082B00002F012B870B5054C4C34A06C0588A906C4 +:1082C0001CD58088E16A69B1884717E0281300202F +:1082D000A0C70008580002400008014000440040C8 +:1082E00000380140E26961698854E069E16800F1A1 +:1082F0000100B0FBF1F201FB1200E06128060FD58E +:10830000D4E9091088420CD0A169085CA16C88806E +:10831000A06A2169401CB0FBF1F201FB1200A062CF +:1083200070BDA06CBDE87040002240F2277101F0E2 +:10833000D3BF0000FEB52C4C0125207878B1012870 +:1083400023D0022820D164208DF8000027488DF822 +:10835000015000264078E0B38DF802503CE07A20CE +:108360008DF8000022486B460222B0F90000FF2180 +:10837000C0F1B40000EBD070C0F347008DF80100ED +:108380006D20FFF742F92570FEBD1A4E79208DF859 +:108390000000B6F900000A2590FBF5F05A30B4222F +:1083A0000021FEF74FF98DF80100B6F90200B42262 +:1083B00090FBF5F05A300021FEF744F98DF80200E9 +:1083C0006B460322FF216D20FFF71FF9022020706A +:1083D000FEBDFFE78DF802606B460322FF216D2092 +:1083E000FFF713F92670F3E7BC030020680A0020AA +:1083F000A8010020380000201FB5044602AB062269 +:1084000043216820FFF73DF9BDF80800214640BA36 +:1084100002B2D01702EB90708010ADF80000BDF8EA +:108420000A0040BA02B2D01702EB90708010ADF88B +:108430000200BDF80C0040BA02B2D01702EB9070F7 +:108440008010ADF804007C4842786846FEF743FA95 +:108450001FBD38B504464FF40050ADF800000220AF +:108460008DF8030004208DF80200744874490068F8 +:10847000884202D16946734804E07349884203D1B7 +:108480006946724800F022FC80226B216820FFF7C9 +:10849000F2F80520FFF72CFC002219216820FFF7D5 +:1084A000EAF803226B216820FFF7E5F80222372162 +:1084B0006820FFF7E0F8604D1A2168202A78FFF75E +:1084C000DAF818221B216820FFF7D5F810221C21AA +:1084D0006820FFF7D0F8002C00D06C7038BD1FB5B5 +:1084E000044602AB06223B216820FFF7CAF8BDF81C +:1084F0000800214640BAADF80000BDF80A0040BAB5 +:10850000ADF80200BDF80C0040BAADF804004A48CE +:1085100082786846FEF7DFF91FBD47494C4ACB78A1 +:1085200013B14FF4FF6301E04FF480531380002830 +:1085300000D0887070472DE9FE4F814698469246DC +:108540000D462320FFF7D4FB6B46012275216820DE +:10855000FFF797F8002804D09DF80000682802D0A3 +:108560000020BDE8FE8F062201AB11466820FFF710 +:1085700088F89DF809009DF80710C007400F01F02A +:10858000010140EA41009DF805102B4C01F001016A +:1085900008434FF001064FF0000704D0012833D004 +:1085A00002280DD02CE06B4601220C216820FFF739 +:1085B00068F89DF8000010F00F0021D0042823D0A7 +:1085C000E7702449C9F8001023492448C9F8041069 +:1085D0002860234868602348E860B8F1000F02D0A3 +:1085E000E17888F800105046BAF1620F19D00DDC1E +:1085F00005281ED00A281AD0BAF1140F0BD114E0A6 +:108600000520FFF71FFCDCE7E670DAE7BC2806D0A0 +:10861000BAF5807F01D0032004E0277003E02670C4 +:1086200001E00220207001209BE70420FAE70520EA +:10863000F8E70620F6E70000BD0300200404002050 +:1086400000127A00000C0140001BB700001001402E +:108650007A0100201B850008DF840008538400088D +:10866000F9830008194492311FB5044602AB062273 +:1086700001211C20FFF705F8BDF80800214640BA8B +:1086800040F38D02D01702EB90708010ADF800001F +:10869000BDF80A0040BA40F38D02D01702EB90708B +:1086A0008010ADF80200BDF80C0040BA40F38D0216 +:1086B000D01702EB90708010ADF8040033480278B8 +:1086C0006846FEF708F91FBD38B504462020ADF80E +:1086D000000002208DF8030004208DF80200694696 +:1086E0002B4800F0F3FA00222A211C20FEF7C3FFDA +:1086F00002220E211C20FEF7BEFF03220F211C20A8 +:10870000FEF7B9FF12222B211C20FEF7B4FF022234 +:108710002C211C20FEF7AFFF01222D211C20FEF78B +:10872000AAFF00222E211C20FEF7A5FF05222A21E8 +:108730001C20FEF7A0FF17494FF48070002C088022 +:1087400001D01248047038BD38B5044600208DF8B9 +:10875000000011481149006888420CD06B46012284 +:108760000D211C20FEF78DFF28B19DF800002A285E +:1087700003D01A2801D0002038BD094921600949D9 +:10878000616002494870012038BD0000C10300202B +:10879000000801407A01002004040020001BB700FB +:1087A000C986000869860008434810B50068434C34 +:1087B000A188084203D0FFF772FAA0600AE0FFF731 +:1087C0006EFAA168884205D9401A3B2190FBF1F06E +:1087D00061690860E068BDE8104001F02BB9E3E78B +:1087E000E2E7FEB50125354C022110B1012810D178 +:1087F00009E04FF4807060804000A080E0600920B4 +:108800002070172004E06580A180E16025700720BA +:1088100060706088ADF800001026274F8DF8026068 +:108820008DF80310083F6946384600F04FFAA088DB +:10883000ADF8000004208DF802006946384600F0CB +:1088400045FA2178012001F069FDE06801F0F2F8B5 +:10885000E068019000208DF808008DF809608DF81F +:108860000A5001A801F0A2F894F9010000F01F01DC +:108870008D4040094FF0E02101EB8000C0F800512D +:10888000FFF727FA3C382061FEBD70B50546FFF7BB +:1088900020FA0A4C21693C3188420CD3C4E9040512 +:1088A00005496088083108600B20FFF715FA024976 +:1088B00060880C31086070BD080C0140C4030020C2 +:1088C0001FB5044602AB0622A8216820FEF7D9FE98 +:1088D000BDF80800214640BA02B2D01702EB9070F2 +:1088E0008010ADF80000BDF80A0040BA02B2D017FF +:1088F00002EB90708010ADF80200BDF80C0040BA99 +:1089000002B2D01702EB90708010ADF80400264838 +:1089100042786846FDF7DFFF1FBD70B5044664204E +:10892000FFF7E6F9F02223216820FEF7A4FE10B934 +:108930000320FFF787FA0520FFF7DAF91A4D202107 +:10894000287840F00F026820FEF795FE002C00D03A +:108950006C7070BD38B504460D461920FFF7C8F994 +:108960006B4601220F216820FEF78BFE9DF8000068 +:10897000D32801D0002038BD0C4820600C4860602E +:108980000C48E0600848362D05D04E2D07D05D2DEF +:1089900007D0002100E040210170012038BD802176 +:1089A000FAE7C021F8E70000DC0300201B8900087B +:1089B000C1880008DDE9A7312DE9F04FB74C8346A7 +:1089C0008E46608926890102B5484FF0000A40684A +:1089D000421AA6FB027CA0884FEAE2754FEA1041DA +:1089E0004FEA00430AFB02C006FB05064FEAD71018 +:1089F00040EA466013EB000941EBE611E688638824 +:108A0000A6FB02C84FEA53404FEAC3370AFB028372 +:108A100006FB05364FEA1C2343EA0663FB1840EBCE +:108A20002620A689A6FB027C0AFB02C206FB0524BF +:108A30004FEAD75242EA44224FF4FA654FEAE4542F +:108A4000521944F10004A246551B74F1000448DA9F +:108A5000944D5519A5FB05674AF1FF3404FB0577D2 +:108A600005FB047C0525A6FB05480CFB05850027B6 +:108A700006FB07556F104FEA340CB9EB0C0961EB9C +:108A80000701A40844EA85741B1B60EBA500864D12 +:108A9000551B7AF1FF3424DA40F2DC555619A6FB57 +:108AA00006474AF1000505FB067706FB0575072614 +:108AB000A4FB06C805FB0686002704FB0767B9EB85 +:108AC0000C0961EB07010B27A4FB07C805FB078511 +:108AD000002604FB065464104FEA3C055B1B60EB68 +:108AE00004006F4CA5680024A5FB036704FB037317 +:108AF00005FB0030740D44EAC0244015B4EB0903B3 +:108B000060EB0100410441EAD330BBF1000F01D01A +:108B1000CBF80000BEF1000F01D0CEF80020BDE878 +:108B2000F08F10B500F072F85D49886010BD5C48A8 +:108B3000012200784030C1B27720FEF79CBD10B50D +:108B400000F064F85649486010BD5548012200788D +:108B50005030C1B27720FEF78EBD2DE9FE430546A9 +:108B600052485349006888420FD04FF40054ADF882 +:108B7000004002208DF8030010204E4E8DF80200B8 +:108B80006946304600F0A2F874610A20FFF7B0F899 +:108B900001AB0122A0217720FEF773FD002823D02E +:108BA00001221E217720FEF766FD4FF42F60FFF7AC +:108BB00093F80024DFF8E4802646A02707EB440062 +:108BC000C1B202AB022277200296FEF75AFDBDF831 +:108BD000080040BA28F81400641C082CEEDB2F486B +:108BE00000F026F810B10020BDE8FE8342F21070BC +:108BF00028806880304868603048A8603048E86065 +:108C000030482861304868610120EDE708B56B46BF +:108C1000032200217720FEF734FD9DF800009DF827 +:108C20000110000440EA01209DF80210084308BD2D +:108C3000F0B5C289002102F47F4502F00F04012340 +:108C4000C5810A4630F8126006B10023521C082A7A +:108C5000F8DB4FF0FF36F3B90022D30722F001030F +:108C600002D0C35C594002E0C35A81EA13210823B1 +:108C70000F0401D581F4C05149005B1E002BF7DCC5 +:108C8000521C102AE9DB2543C581C1F3033084421D +:108C900001D10020F0BD3046F0BD0000C01300201F +:108CA000E003002030F8FFFF24FAFFFF0404002057 +:108CB000001BB700001001404B8B00083F8B0008E1 +:108CC0002F8B0008238B0008B9890008F0B500231A +:108CD0004FF0010C0A880CFA03F52A4228D04FEA1B +:108CE000D30200EB82064FEA437491F802E04FEAA8 +:108CF000D46734680EF00F025FEACE6E03D591F8A8 +:108D000003E04EEA02024FF00F0E0EFA07FE24EACD +:108D10000E04BA40224332608A78282A02D0482AB8 +:108D200003D005E0C268AA4301E0C2682A43C260DA +:108D30005B1C102BCED3F0BD4FF4805108B14E48D0 +:108D400001E04D48001F016070472DE9F0410446E5 +:108D50004A4817460D460088484E0C3E1CE015B1A7 +:108D600015F8010B00E0FF2080460221304601F09B +:108D7000EDFB0028F9D04146304601F0E3FB01212C +:108D8000304601F0E3FB0028F9D0304601F0DCFB6F +:108D9000C0B20CB104F8010B7F1EE0D20120BDE887 +:108DA000F081F0B501218C0389B0204600F05CFF12 +:108DB0000121204600F06AFF18208DF816004FF4BC +:108DC0002040ADF814002C4E03208DF81700143EFF +:108DD00005A93046FFF77AFFADF8144004208DF85E +:108DE000160005A93046FFF771FFA010ADF814007A +:108DF00010258DF8165005A93046FFF767FF1F4E66 +:108E00000C3E304601F054FB4FF48270ADF8020086 +:108E100068010024ADF80A000720ADF81000ADF895 +:108E200004400220ADF80E40ADF806000127ADF871 +:108E30000040ADF80870ADF80C506946304601F0BE +:108E40005BFB0121304601F073FB0DA0006806902A +:108E50000120FFF771FF042206A907A8FFF775FF9D +:108E60000020FFF769FF9DF81D00EF2802D0204683 +:108E700009B0F0BD3846FBE7140C01400C38004047 +:108E80009F0000002DE9F04180461D4616460C4625 +:108E9000084600F0E7F80746404600F0D8F807EB30 +:108EA0008000C0B2102805D2734901EB0010856024 +:108EB00004710673BDE8F08151B104290BD0082973 +:108EC0000CD00C290DD101225FF0100101F05DB929 +:108ED00001220221FAE701220421F7E701220821F9 +:108EE000F4E7704770B50D460446017B13460068F1 +:108EF0002A46FFF7C7FF217B2068BDE87040DBE70B +:108F000008B58DF8000000208DF8010001208DF8D3 +:108F100002008DF80300684600F0C3FB08BDFEB5F3 +:108F2000064614460D46684601F0FFF853486D1E8C +:108F300044435348ADF8045069460068B0FBF4F070 +:108F4000401EADF800000020ADF80600ADF80200AC +:108F5000304600F0B5FEFEBD10B504460068FFF7D0 +:108F6000DEFF0121206801F0FBF8607BBDE81040C6 +:108F7000C6E770B50546084600F074F80446284672 +:108F800000F065F804EB80003B49C0B201EB001033 +:108F900070BD70B50546022101F028F9012825D0E1 +:108FA0000421284601F022F901282CD00821284666 +:108FB00001F01CF9012833D01021284601F016F9E0 +:108FC00001283AD11021284601F01CF90C2128462D +:108FD000FFF7CFFF0446284601F005F9A2680146D5 +:108FE000002A2AD0207BBDE8704010470221284685 +:108FF00001F008F900212846FFF7BBFF0446284688 +:1090000001F0EBF8EAE70421284601F0FBF804211F +:109010002846FFF7AEFF0446284601F0E0F8DDE7FA +:109020000821284601F0EEF808212846FFF7A1FFA5 +:109030000446284601F0D5F8D0E770BD1148A8E7EE +:109040004FF08040A5E71048A3E71048A1E701468C +:1090500000200F4A01E0401CC0B252F820308B4281 +:10906000F9D17047014600200A4A01E0401CC0B215 +:10907000135C8B42FAD17047D013002040420F009E +:1090800000040020002C01400004004000080040C3 +:10909000EC03002094C80008016B4A689268896854 +:1090A0000A4290F8441204D00020002900D1012087 +:1090B000704701200029FBD100207047D0F83431DF +:1090C00001299A685B6801D021B107E090F8440259 +:1090D00030B103E090F84402012801D05A61704792 +:1090E0001A6170470189406889B2482200F052B97C +:1090F00070B5044601EB4100AC491646B1FBF0F0F7 +:1091000081B21D4603222046FFF726FF2A4631463C +:109110002046BDE87040FFF7E5BE0189406889B28E +:10912000102200F037B900B50346032083F83C0253 +:109130001846FFF7B1FF30B1B3F8400293F8391287 +:109140000843A3F8400293F83902400083F839023B +:1091500093F83E02401E10F0FF0083F83E0205D156 +:10916000012083F83802022083F83C0200BDC26867 +:10917000016A521E914201D3002100E0491C0162A4 +:10918000704710B50124034680F83C42FFF784FF86 +:1091900001280FD1002083F8380283F83A4293F86F +:1091A0004002A3F840021A6A59698854BDE8104089 +:1091B0001846DCE710BD00B50346FFF76DFF01213F +:1091C00001280BD003F23A2300201870D880042025 +:1091D00098700820187103F8011C00BD83F83C1238 +:1091E00000BD90F83C12491E11F0FF0180F83C12BE +:1091F00008D190F83A1201B1DDE790F8381201B1C8 +:10920000BFE790E77047D0E90910814201D1012002 +:1092100070470020704730B5044690F83B020025A7 +:10922000F8B194F83D02401E10F0FF0084F83D02B2 +:1092300016D1B4F8420200F001014008A4F842023D +:109240002046FFF73BFF032084F83D0294F83F02DD +:10925000401E10F0FF0084F83F0201D184F83B5219 +:1092600030BD2046FFF7CFFF0028F9D1A16AA269DF +:10927000481CA062515C2269904200D3A5624FF461 +:10928000007004F23B2440EA4100A4F807000A20E1 +:1092900020710120A070207030BD00EBC00101EBF7 +:1092A000801010B5424901EBC0042046FFF7B3FF20 +:1092B0002046BDE8104094E770B53D4C06463D4859 +:1092C000206003202071A66084F844123A4820638D +:1092D0001030C4F83401002504F1340125626161C5 +:1092E0004FF48070E060206104F59C71C4E90615BC +:1092F000A562656284F83B52012084F83A0284F842 +:10930000385284F83C02206BFFF7ECFED4F83401AD +:10931000FFF703FF01212046FFF7D0FE3220FEF7C2 +:10932000E7FCAFF289032A463146206BBDE8704066 +:10933000DEE6D0E90721914202D14FF000007047EC +:1093400002D9A1EB020003E0C0680844A0EB0200D0 +:10935000C0B2704700B50346FFF7EBFF00280BD003 +:109360005969D869095CDA68521E904201D2401CE2 +:1093700000E00020D861084600BD436A8269D154EC +:10938000416A0269491CB1FBF2F302FB131141620D +:109390007047704708B5ADF800108DF80220022123 +:1093A0008DF803106946FFF791FC08BDC0C62D007B +:1093B000D014002098C80008F4C700081FB5044660 +:1093C00002AB062202211820FEF75BF99DF8080087 +:1093D0009DF80910800800EB0120ADF800009DF811 +:1093E0000A009DF80B10800800EB0120ADF8020088 +:1093F0009DF80C009DF80D10800800EB0120ADF8E1 +:1094000004001A48214602786846FDF764FA1FBD39 +:1094100010B5044608220F211820FEF72CF90E2261 +:1094200010211820FEF727F911494FF48050002C25 +:10943000088001D00D48047010BD38B504460020E6 +:109440008DF8000001466B4601221820FEF719F93D +:1094500018B19DF80000FB2801D0002038BD054858 +:10946000206005486060012038BD0000FC0300203A +:109470007A01002011940008BD9300080268126868 +:10948000104770B50C46054603E02A682846126866 +:10949000904714F8011B0029F7D170BD0168496895 +:1094A00008470168896808470268D2681047016860 +:1094B000096908476E48016841F00101016041688F +:1094C0006C4A1140416001686B4A114001600168BB +:1094D00021F480210160416821F4FE0141604FF4D4 +:1094E0001F0181606549C00308607047604A10B57C +:1094F0005068634B10F00C01624803D0042903D07C +:10950000082903D0036016E0416813E051685368EE +:1095100001F470114FF0020413F4803F04EB914109 +:1095200006D053689B03436800D55B084B43E9E7CB +:10953000554B594301605168524AC1F30311083237 +:10954000515C0268CA40026010BD3EB40021009127 +:109550004FF4E01301914648CDE901314B4A0468CC +:1095600044F480340460846944F0100484614FF44E +:10957000A064056805F400350195009D6D1C0095FB +:10958000019D15B9009DA542F3D10568AD0301D534 +:10959000022114E0056845F00105056000910168AD +:1095A00001F0020101910099491C0091019911B942 +:1095B0000099A142F3D10168890739D501210291AF +:1095C00033490C6844F010040C600C6824F0030468 +:1095D0000C600C6844F002040C6041684160416812 +:1095E0004160416841F480614160116821F070413F +:1095F0001160244C22496160416821F47C11416072 +:10960000116841F0004111602049091FCA6822F425 +:109610000042CA608968090403D51E494FF48013CB +:10962000616002990193012908D002290AD100E062 +:10963000FEE7416843F48032114302E0416841F49F +:1096400060114160016841F0807101600168890129 +:10965000FCD5416821F003014160416841F00201FD +:1096600041604168C1F381010229FAD13EBC3DE766 +:10967000001002400000FFF8FFFFF6FE08ED00E0DA +:1096800000127A000004002000093D00041001408F +:1096900000200240001BB700184908431849086021 +:1096A0007047F0B50F21C478027801234FF0E0260F +:1096B000DCB1134C2468457804F4E064C4F5E0643C +:1096C000240AC4F10407E1408478BD400C402C43D7 +:1096D00021010C4C1155007800F01F018B4040090E +:1096E00006EB8000C0F80031F0BD02F01F0083409F +:1096F000500906EB8000C0F88031F0BD0000FA058B +:109700000CED00E000E400E010B54268464B0C7937 +:109710001A400B6842EA0422134343608368434AB9 +:109720001340D1E9024222434C7943EA44031A43ED +:109730008260C26A097C22F47002491EC9B242EA00 +:109740000151C16210BD0029816802D041F00101C0 +:1097500001E021F00101816070470029816802D099 +:1097600041F4807101E021F480718160704781686B +:1097700041F00801816070470146002089680907AF +:1097800000D501207047816841F004018160704775 +:10979000014600208968490700D50120704700294B +:1097A000816802D041F4A00101E021F4A0018160B0 +:1097B000704770B5072409290AD9C568A1F10A06BE +:1097C00006EB4606B440A543B3401D43C56007E021 +:1097D000056901EB4106B440A543B3401D43056153 +:1097E0001F23072A09D2446B521E02EB82029340C8 +:1097F0009C4391400C43446370BD0D2A09D2046B15 +:10980000D21F02EB820293409C4391400C430463BD +:1098100070BDC46A0D3A02EB820293409C439140B2 +:109820000C43C46270BD0000FFFEF0FFFDF7F1FFC6 +:1098300001684FF6FE721140016000210160416035 +:109840008160C1605749574A0839904203D148683E +:1098500040F00F0006E0534A1432904204D14868A9 +:1098600040F0F000486070474E4A2832904203D1E1 +:10987000486840F47060F5E74A4A3C32904203D1B0 +:10988000486840F47040EDE7464A5032904203D1B8 +:10989000486840F47020E5E7424A6432904203D1C0 +:1098A000486840F47000DDE73E4A7832904203D1C8 +:1098B000486840F07060D5E73B4A111F904203D1E1 +:1098C000086840F00F0006E0374A1432904204D195 +:1098D000086840F0F00008607047334A2832904230 +:1098E00003D1086840F47060F5E72F4A3C3290429B +:1098F00003D1086840F47040EDE72B4A50329042A3 +:10990000EAD1086840F47020E5E730B5036847F60F +:10991000F07293430C6A8A682243D1E904452C43D0 +:1099200022438C692243CC6922434C6A22438C6ACD +:1099300022431A430260CA6842600A68826049682A +:10994000C16030BD0021016041608160C160016182 +:1099500041618161C1610162416281627047002998 +:10996000016802D041F0010102E04FF6FE721140A1 +:1099700001607047002A026801D00A4300E08A4370 +:109980000260704741607047406880B27047C10014 +:1099900003D50549091F0860704702490839486026 +:1099A00070470000080002400804024030B5234917 +:1099B0008379026853B30B6893430B600A1D1368E5 +:1099C0000468A343136002790A44136804682343BC +:1099D00013601A4A083213680468A3431360131D06 +:1099E0001C680568AC431C604479102C05D02144E8 +:1099F0000A68006802430A6030BD116804682143A8 +:109A00001160196800680143196030BD007908448D +:109A100001689143016030BD084A01460020126888 +:109A2000064B0A4014331B680B4202D0002A00D0B8 +:109A3000012070470149143108607047000401405B +:109A40005A4910B588424FF0010101D14C0501E09F +:109A50004FF48004204600F019F92046BDE810407C +:109A6000002100F013B970B50446808886B00D4619 +:109A700020F03F06684600F09FF84D490298B0FB81 +:109A8000F1F189B20E43A680228822F001022280E1 +:109A9000484B2A689A421CD85200B0FBF2F080B2C0 +:109AA000042800D20420491C2184A083208840F08F +:109AB0000100208021884FF6F5300140A8886A898E +:109AC000104308432080A88929890843208106B0D3 +:109AD00070BDEB88A3F53F46FF3E05D102EB420285 +:109AE000B0FBF2F080B208E002EBC20303EB02121B +:109AF000B0FBF2F080B240F48040020501D140F0AA +:109B000001004FF4967251434FF47A72B1FBF2F1B7 +:109B100040F40040C7E741F28831016000218180B4 +:109B20004BF6FF72C280018141814FF480418181F7 +:109B300070470029018802D041F0010101E021F0C5 +:109B40000101018070470029018802D041F4807131 +:109B500001E021F48071018070470029018802D062 +:109B600041F4007101E021F4007101807047002987 +:109B7000018802D041F4806101E021F4806101801C +:109B80007047002A828801D00A4300E08A4382801D +:109B9000704701827047008AC0B2704712B141F02D +:109BA000010101E001F0FE01018270470054004014 +:109BB00040420F00A086010030B53C494A683C4B4A +:109BC00012F00C0405D03B4A042C126803D0082C78 +:109BD00024D0036000E002604A680F2303EA1212F7 +:109BE000354B9C5C0268E24042604C68072505EA00 +:109BF00014241C5D22FA04F484604C6805EAD42421 +:109C00001B5DDA40C2604968032303EA91312A4BA5 +:109C10001B1F595CB2FBF1F1016130BD4B684C6810 +:109C200003F470134FF0020514F4803F05EB9343E7 +:109C300005D04C68A40300D552085A43CBE71F4A0D +:109C40005343C6E7194A0029516901D0014300E096 +:109C5000814351617047154A0029916901D0014340 +:109C600000E0814391617047104A0029D16901D019 +:109C7000014300E08143D16170470C4A0029D1685B +:109C800001D0014300E08143D1607047074A0029B9 +:109C9000116901D0014300E081431161704703481D +:109CA000416A41F08071416270470000001002403B +:109CB00000127A00040400201C04002000093D006A +:109CC00030B50288FD4BFE4C98420DD0A0420BD01F +:109CD000B0F1804F08D0FB4DA84205D0FA4DA84204 +:109CE00002D0FA4DA84203D122F070054A882A43D7 +:109CF000F74DA84206D0F74DA84203D022F4407594 +:109D0000CA882A4302808A8882850A880285984206 +:109D10000AD0A04208D0F04A904205D0EF4A9042C3 +:109D200002D0EF4A904201D1097A01860121818255 +:109D300030BD30B5028C22F001020284028C83888F +:109D4000048B22F0020224F073050C882C430D8949 +:109D500015434A882A43D94DA8420BD0D84DA84272 +:109D600008D0DD4DA84205D0DC4DA84202D0DC4D24 +:109D7000A8420DD122F008054A8923F440732A43F2 +:109D800022F004058A882A438D891D43CB892B4301 +:109D900083800483C9888186028430BD70B5028CBB +:109DA00022F010020284028C8488038B0D8823F435 +:109DB000E6464FF6FF7303EA052535430E8922F088 +:109DC000200203EA061616434A8803EA02123243C7 +:109DD000BA4EB04202D0BA4EB04215D122F080063F +:109DE0004A8924F4406403EA0212324322F0400616 +:109DF0008A8803EA021232438E8903EA86062643E2 +:109E0000CC8903EA8404344384800583C9880187AC +:109E1000028470BD70B5028C22F480720284028CC0 +:109E20008488838B0D8823F073031D4322F4007311 +:109E30000E894FF6FF7202EA06261E434B8802EA9D +:109E4000032333439D4EB04202D09D4EB04215D104 +:109E500023F400664B8924F4405402EA032333437D +:109E600023F480668B8802EA032333438E8902EA57 +:109E700006162643CC8902EA041434438480858381 +:109E8000C9888187038470BD70B5028C22F480522A +:109E90000284048C8288838B0D8823F4E6464FF677 +:109EA000FF7303EA0525354324F400560C8903EAC1 +:109EB000043434434E8803EA063626437F4CA042DE +:109EC00002D07F4CA04205D122F480448A8903EA63 +:109ED0008212224382808583C988A0F840100684BC +:109EE00070BD828B22F440628283828B4FF6FF73B7 +:109EF00003EA01210A4382837047828B22F00C021D +:109F00008283828B0A4382837047028B22F44062F1 +:109F10000283028B4FF6FF7303EA01210A43028397 +:109F20007047F0B5048C24F010040484078B048C73 +:109F30004FF6FF7527F4734705EA03333B4305EA01 +:109F400002221A435D4B05EA011698420ED05C4B83 +:109F500098420BD0B0F1804F08D05A4B984205D0B0 +:109F6000594B984202D0594B984205D124F0200118 +:109F7000314341F0100104E024F0A0030B4343F00F +:109F8000100102830184F0BD028B22F00C020283D7 +:109F9000028B0A430283704770B5048C24F00104DD +:109FA0000484058B048C4FF6FF7606EA03131343F3 +:109FB00025F0F305414A2B4390420ED0404A90428F +:109FC0000BD0B0F1804F08D03E4A904205D03E4AB7 +:109FD000904202D03D4A904202D124F0020201E0B8 +:109FE00024F00A020A4342F001010383018470BD98 +:109FF0002DE9F05F0D4604460888304FDFF8C0C0F9 +:10A00000DFF8C0804988AA882B894FF0804960B367 +:10A01000042832D04FF6FF7E082836D0208C9B468D +:10A0200020F480502084A38B268C704600EA022204 +:10A0300023F473431A4300EA0B3010430EEA013E47 +:10A04000BC420BD0644509D04C4507D0444505D0EF +:10A050001D4A944202D01D4B9C425AD126F4005115 +:10A0600041EA0E0141F4805158E02046FFF794FF89 +:10A07000E9882046BDE8F05F86E72046FFF751FFFC +:10A08000E9882046BDE8F05F3FE7208C20F480702F +:10A090002084B4F81CA0208C0EEA031313432AF08A +:10A0A000F30A0EEA012B43EA0A03BC4220D06445BE +:10A0B0001ED04C451CD044451AD013E0002C014062 +:10A0C000003401400004004000080040000C004043 +:10A0D00000100040001400400040014000440140D6 +:10A0E00000480140494A944202D0494A944204D16E +:10A0F00020F4007040EA0B0002E020F420600843E6 +:10A1000040F48070A3832084E9882046BDE8F05F96 +:10A11000F3E626F402420A4342F48051A08320462B +:10A120002184E988BDE8F05FDBE64FF6FF718180AE +:10A1300000210180C18041800172704700210180AF +:10A1400041808180C180018141818181C1817047CD +:10A1500000210180418001228280C18001817047FD +:10A160000029018802D041F0010101E021F0010144 +:10A1700001807047002930F8441F02D041F40041AB +:10A1800001E0C1F30E0101807047002A828901D0ED +:10A190000A4300E08A4382817047028B22F0080262 +:10A1A0000A4302837047028B4FF6FF7322F400626A +:10A1B00003EA0121114301837047828B22F00802D8 +:10A1C0000A4382837047828B4FF6FF7322F400624A +:10A1D00003EA0121114381837047808E7047008F0D +:10A1E0007047808F7047B0F84000704702460020EB +:10A1F000138A92890B4202EA010202D0002A00D09F +:10A2000001207047C94301827047000000080040E8 +:10A21000000C004030B50446008A85B00D464CF66F +:10A22000FF710840E98801432182A1894EF6F310AD +:10A230000140A8882A8910436A890A431043A081F3 +:10A24000A08A4FF6FF410840A9890143A1826846D0 +:10A25000FFF7B2FC3048844201D1039800E0029835 +:10A26000A1890904002900EBC00101EB0010296855 +:10A2700002DA4FEA410101E04FEA8101B0FBF1F05F +:10A280006422B0FBF2F14FEA01114FEA11136FF0B3 +:10A2900018056B4300EB8300A3891D044FF03203C4 +:10A2A00006D503EBC000B0FBF2F000F0070005E0BC +:10A2B00003EB0010B0FBF2F000F00F000843208128 +:10A2C00005B030BD0029818902D041F4005101E080 +:10A2D00021F400518181704710B5C1F3421301F0A0 +:10A2E0001F040121A140012B07D0022B07D01430FD +:10A2F000002A026805D00A4304E00C30F8E7103069 +:10A30000F6E78A43026010BD002A828A01D00A4320 +:10A3100000E08A43828270470038014010B58A0706 +:10A3200021F003040649130F21440F228C689A4040 +:10A3300094438C608A68984002438A6010BD000094 +:10A34000000001403948384941603949416070474F +:10A350003648016941F080010161704733490420AA +:10A36000CA68D20701D001207047CA68520701D5D8 +:10A3700002207047C968C906FBD50320704700B5A5 +:10A380000346FFF7EBFF02E0FFF7E8FF5B1E012843 +:10A3900003D0002B00D1052000BD002BF4D1FAE73B +:10A3A00070B505464FF430263046FFF7E8FF042825 +:10A3B00011D11E4C206940F00200206165612069C6 +:10A3C00040F0400020613046FFF7D9FF216941F697 +:10A3D000FD721140216170BDF8B5064600204FF4B2 +:10A3E000005C00900D466046FFF7C9FF042816D1B7 +:10A3F0000E4C206940F00100206135806046FFF777 +:10A40000BEFF41F6FE77042806D1B61C280C009644 +:10A4100030806046FFF7B3FF216939402161F8BD04 +:10A420000249C860704700002301674500200240D0 +:10A43000AB89EFCD14481549026800608A4203D009 +:10A440001348804713480047134E4FF0090030600F +:10A450001248016821F07061016041020160104CF6 +:10A46000182020600F49104808601048D0F800D02C +:10A4700040680047FEE7FEE7FEE7FEE7FEE7FEE78F +:10A48000FEE7FEE7FEE7FEE7F04F0020EFBEADDEA1 +:10A49000B5940008ED0000081810024004000140C7 +:10A4A000140C0140000C01404434434400F0FF1FF1 +:10A4B0002A4910B588420AD1841401212046FFF7A9 +:10A4C000DCFB2046BDE810400021FFF7D6BB244945 +:10A4D000884202D10121041404E0224988420AD1B1 +:10A4E0000121C4132046FFF7D1FB2046BDE81040F0 +:10A4F0000021FFF7CBBB10BD30B502884C8802F4B9 +:10A5000041530A88CD8822438C882C4322430C89EE +:10A5100022434C8922438C892243CC8922431A430B +:10A520000280828B22F400628283098A018230BD1C +:10A530000029018802D041F0400101E021F04001F2 +:10A5400001807047818170478089704702460020F2 +:10A5500012890A4200D001207047000000300140FB +:10A5600000380040003C004000487047A0C9000887 +:10A57000A0F16101192900D8203870472DE9F05F5A +:10A58000994615460F4683464FF0FF36DDF828A062 +:10A5900011E0A819441009FB047080460146584692 +:10A5A00052469047002802D004DA254603E0404690 +:10A5B000BDE8F09F2646A5EB06000128E9DC002057 +:10A5C000F6E740EA01039B0703D009E008C9121F20 +:10A5D00008C0042AFAD203E011F8013B00F8013B5D +:10A5E000521EF9D27047D2B201E000F8012B491E89 +:10A5F000FBD270470022F6E710B513460A46044620 +:10A600001946FFF7F0FF204610BD421E12F8013F29 +:10A61000002BFBD111F8013B02F8013B002BF9D1D3 +:10A62000704730B505462A460B4612F8010B13F861 +:10A63000014B08B1A042F8D01CB1002802D06D1C1B +:10A64000F1E7284630BD10B5044604E00B7800F869 +:10A65000013B03B1491C521EF8D2204610BDCAB2BC +:10A66000401E10F8011F8A4202D00029F9D10020B3 +:10A670007047421C10F8011B0029FBD1801A70475B +:10A680002DE9F0410546002090460E46044600E0C4 +:10A69000641C44450BD2285D00F058F90746305D34 +:10A6A00000F054F9381A02D1295D0029F0D1BDE833 +:10A6B000F08170B5064600F0F3FA046805460A22F8 +:10A6C0000021304600F048F92C6070BDF0B480EAFB +:10A6D0000102D40F4200B2EB410F02D202460846FB +:10A6E00011464A0042D0C30DDDB2C1F3C752AD1AC4 +:10A6F000202D35DAC1F3160141F4000204B15242B3 +:10A70000C5F1200602FA06F12A411044B3EBD05FEE +:10A7100023D0C4B1012DA0EBC35009DCF0BC4FF035 +:10A72000004202EAC35200F50000DBB200F055B966 +:10A73000400000F1807000EBC350A0F1807040EA4F +:10A74000D170490009E0490841EAC071A0EBC3504B +:10A7500000F50000400800EBC350F0BC00F034B935 +:10A760006142012202EB4101001BF6E7F0BC704799 +:10A7700081F00041AAE780F00040A7E780EA0102EB +:10A7800010B502F00043400026D04A0023D04FEA23 +:10A79000106101EB1261C0F35600C2F3560240F49F +:10A7A000000042F40002A0FB0220A1F17F014FEA69 +:10A7B0000040140401D000F1010050EA124001D41D +:10A7C0004000491EC2B20C0604EBD010401C4008E9 +:10A7D000802A02D003E0002010BD20F001000029F3 +:10A7E00000DA0020184310BD30B480EA010202F004 +:10A7F000004530F0004221F0004015D0A0B1C0F378 +:10A80000C753C2F3C754C2F31601C0F31600E41ACB +:10A8100041F4000140F400027D34914201D3641CF4 +:10A8200000E04900002C02DA30BC002070474FF4F1 +:10A8300000000023914201D3891A034340084FEAE4 +:10A840004101F7D151B1914202D14FF0004105E0F1 +:10A8500002D24FF0010101E06FF0010103EBC4509F +:10A86000284430BC00F0B0B8420005D0C0F3C75255 +:10A870005242914201DC0020704700EBC15070470A +:10A88000C10F80EAE0700844CA079623002100F057 +:10A89000A4B896230022114600F09FB800F00042B1 +:10A8A00020F00040C10DC0F3160040F400007F29E5 +:10A8B00001DA00207047962903DCC1F19601C840F7 +:10A8C00001E096398840002AF4D04042704720F0D9 +:10A8D0000040C10DC0F3160040F400007F2901DAEA +:10A8E00000207047962903DCC1F19601C8407047EB +:10A8F0009639884070470000002801DBC0F1004015 +:10A90000002901DBC1F1004181427047002801DBD1 +:10A91000C0F10040002901DBC1F1004188427047CD +:10A9200030B50B46014600202022012409E021FA1F +:10A9300002F59D4205D303FA02F5491B04FA02F51C +:10A940002844151EA2F10102F1DC30BDA0F1410145 +:10A95000192900D8203070472DE9F04791460F465D +:10A9600080460446002614F8015B2DB1FFF7FCFD7C +:10A970000068405DC007F6D12B2D02D02D2D18D0D8 +:10A98000641E4A463946204600F0DAF827B1396895 +:10A99000A14201D1C7F8008071054FF002040BD528 +:10A9A0004042002803DD00F07BF90460A007BDE809 +:10A9B000F08746F48066E4E70028F8DA00F070F9E2 +:10A9C00004606FF00040F2E70029A8BF7047401C08 +:10A9D000490008BF20F00100704710B4B0FA80FCB5 +:10A9E00000FA0CF050EA010404BF10BC704749B1F2 +:10A9F000CCF1200421FA04F411FA0CF118BF012162 +:10AA000021430843A3EB0C01CB1D0106000A002BD8 +:10AA1000BEBF002010BC704700EBC350104400299B +:10AA2000A4BF10BC7047401C490008BF20F00100C3 +:10AA300010BC7047F0B4002802DCF0BC0020704766 +:10AA4000C0F3C751C0F3160040F40000CA0701D19B +:10AA50004000491E3F2202EB6105002211464FF4DF +:10AA6000000626FA01F31344D418844201D8001BCF +:10AA70001A464000491C1729F3DD5100814202D2D9 +:10AA80004FF0FF3100E0002102EBC550F0BCFFF7B2 +:10AA90009BBF10B541000CD0C0F3C751962908DC0C +:10AAA0007E2909DC06DB410204D000F0004040F0C2 +:10AAB0007E5010BD002010BDC1F19604C4F12001EC +:10AAC00000FA01F1E040FFF77FFFA04010BD10B594 +:10AAD00000F0004420F00040C20DC0F3160040F426 +:10AAE00000007F2A07DA7D2A00DA7D22763A00FA12 +:10AAF00002F1002008E0962A09DCA2F1760100FAB2 +:10AB000001F1C2F19602D040FFF75EFF01E0963AF4 +:10AB10009040002C00D0404210BD0000064C074D74 +:10AB200006E0E06840F0010394E80700984710341D +:10AB3000AC42F6D3F5F7DEFAB0D20008D0D2000866 +:10AB40002DE9F05F82460078002715468B460AF112 +:10AB50000104B946302801D09DB113E014F8010B6F +:10AB60000127782803D0582801D045B10AE00DB15B +:10AB7000102D07D10027102514F8010B02E008253D +:10AB800000E00A250026B0460EE005FB080005FBA4 +:10AB900006F1012701EB10461FFA80F8B6F5803F59 +:10ABA00000D3B94614F8010B294600F018F8002824 +:10ABB000EBDABBF1000F05D00FB1641E00E0544684 +:10ABC000CBF80040B9F1000F06D000F069F802217F +:10ABD0000160C81EBDE8F09F48EA0640FAE73A283F +:10ABE00000D2303820F02002412A01D3A2F13700F0 +:10ABF000884201D34FF0FF30704770B501EB02047B +:10AC000010F8015B15F0070301D110F8013B2A1180 +:10AC100006D110F8012B03E010F8016B01F8016B6D +:10AC20005B1EF9D12B0705D40023521E0FD401F867 +:10AC3000013BFAE710F8013B02F10202A1EB03032A +:10AC400003E013F8015B01F8015B521EF9D5A14244 +:10AC5000D6D3002070BD00000FB4054B10B503A97A +:10AC6000044A029800F0E8F810BC5DF814FB0000FC +:10AC7000C92200082C0400204100080218BF04204B +:10AC80000A0E18BF40F001004FF07F4232EA010186 +:10AC900008BF40F00200012808BF052070470000EF +:10ACA00000487047300400206FF05E010807FFF78E +:10ACB000DBBD00002DE9F04D0E4614464FF07F41FC +:10ACC000B1EB440F9EBF4FF0FF313160BDE8F08D16 +:10ACD0004FF0004040EA0421C4F3C75078384311D4 +:10ACE00000F01F00DFF814C1C0F12002FC445CF842 +:10ACF00023500CEB83038540D3F804C02CFA02F7F1 +:10AD00002F439D680CFA00FC25FA02F8DB6805FA6F +:10AD100000F023FA02F240EA02054CEA080CA7FB15 +:10AD20000132ACFB01C0A5FB015101EB0C058D42CA +:10AD300034BF4FF0010C4FF0000CC1186144BCF15E +:10AD4000000F02D0814202D903E0814201D20120EA +:10AD500000E00020104400F120024FEA9218800623 +:10AD6000CA0C40EA42304F03C6F80080FFF788FD66 +:10AD700082463846FFF78DFD6FF01201FFF774FD34 +:10AD800007462846FFF785FD6FF02501FFF76CFDAC +:10AD9000834639465046FFF799FC5946FFF796FC23 +:10ADA00000F500656FF30B0551462846FFF7E0FC00 +:10ADB0003946FFF7DDFC5946FFF7DDFC1049FFF788 +:10ADC000DDFC07460F492846FFF7D8FC3946FFF758 +:10ADD0007DFC07460C492846FFF7D0FC3946FFF7B3 +:10ADE00075FC14F0004F08BFBDE8F08DC8F180512C +:10ADF00080F000403160BDE8F08D0000B41C000020 +:10AE0000DB0FC92F22AAFD290000C92F02E008C8C4 +:10AE1000121F08C1002AFAD170477047002001E0D4 +:10AE200001C1121F002AFBD17047000001490860D0 +:10AE300070470000300400202DE9FF4F8BB09A4688 +:10AE40000F4605460026C9E0252837D100246D1C91 +:10AE50006649A04601222B78203B02FA03F0084203 +:10AE600002D004436D1CF6E728782E2817D115F878 +:10AE7000010F44F004042A280ED06FF02F02287826 +:10AE8000A0F1300109290AD808EB880102EB410141 +:10AE900000EB01086D1CF2E757F8048B6D1C287855 +:10AEA00069283FD006DC002871D063280CD06428C4 +:10AEB00004D137E0732811D075284ED052460D9931 +:10AEC000904706F1010688E017F8040B8DF80000A2 +:10AED00000208DF80100E946012003E057F8049BAB +:10AEE0004FF0FF3061074FF0000401D40AE0641C0A +:10AEF00044450DDA8442FADB19F804100029F6D132 +:10AF000006E0641C8442FCDB19F804100029F8D127 +:10AF1000264404E019F8010B52460D999047641E2F +:10AF2000F8D25AE001CF4FF00A0B002804DAC0F142 +:10AF300000004FF02D0102E0210504D52B218DF8F2 +:10AF40002410012103E0E10705D02021F7E70DF1EE +:10AF5000200908910CE00021F9E701CF4FF00A0B1E +:10AF6000F9E75946FFF7DCFC01F1300209F8012D41 +:10AF70000028F6D1ADEB090000F1200B600701D4E9 +:10AF80004FF00108D84503DDA8EB0B0001E029E0F4 +:10AF900000208046002406E009A85246005D0D9975 +:10AFA0009047761C641C08988442F5DB04E030204E +:10AFB00052460D999047761CB8F10001A8F101089E +:10AFC000F5DC05E019F8010B52460D999047761C07 +:10AFD000BBF10001ABF1010BF4DC6D1C28780028FB +:10AFE0007FF432AF0FB03046BDE8F08F0928010082 +:10AFF0002DE9F0474FF0684202EB40030C4605464E +:10B00000B3F1654F3CBF02EB4102B2F1654F3FD354 +:10B010004FF07F42B2EB400F28BFB2EB410F03D29B +:10B02000BDE8F047FFF752BB40EA01035B0008BFF1 +:10B0300044F0FF410AD0B2EB400F08BFB2EB410F22 +:10B0400006D125F0804024F0804105460C461FE0E3 +:10B05000B2EB400F12BF5FEA410245F0FF4004F03F +:10B06000004115D04FEA410292EA400310D4002A71 +:10B07000B4BF4FF03E564FF09F463146FFF77EFB80 +:10B08000054631462046FFF779FB0446284621460F +:10B09000C0F3C753C1F3C7529A1A1B2A06DD10F03A +:10B0A000004F14BF54485548BDE8F08712F11A0FFD +:10B0B00017DA11F0004F06D010F0004F0CBF5048C7 +:10B0C0005048BDE8F08721462846FFF78DFB04462F +:10B0D000FFF7D2FD042808BFFFF7E6FD2046BDE8D4 +:10B0E000F0874200B2EB410F25D910F0004F19BF95 +:10B0F000454F464E464F474E224685F00044154682 +:10B100000A4680F0004110460A1A5200B2F1807FD0 +:10B110003ED248404049DFF804A110F0004F18D05B +:10B120004FF03F483846FFF723FB0746514630466D +:10B13000FFF71EFB17E011F0004F04BF0026374653 +:10B14000E2D010F0004F19BF354F364E364F374E14 +:10B15000DAE74FF07C583846FFF7B8FA0746514611 +:10B160003046FFF7B3FA064641462846FFF706FB8E +:10B170002146FFF7ABFA824621464046FFF7FEFA2A +:10B180002946FFF7F8FA5146FFF72EFB044604E084 +:10B1900021462846FFF728FB04460146FFF7EEFA52 +:10B1A00080462349FFF7EAFA2249FFF78FFA414622 +:10B1B000FFF7E4FA2049FFF789FA4146FFF7DEFA84 +:10B1C0001E49FFF783FA4146FFF7D8FA1C49FFF7FB +:10B1D0007DFA054641462046FFF7D0FA2946FFF79B +:10B1E000CDFA3146FFF772FA2146FFF76FFA39467A +:10B1F000BDE8F047FFF76ABADB0FC9BFDB0FC93FF5 +:10B20000DB0F4940DB0F49C00000C9BF22AAFDB9CE +:10B210000000C93F22AAFD390060ED3EC30ACE37C7 +:10B22000000049C022AA7DBA0000494022AA7D3A06 +:10B230002DAD65BD8FB8D53D0FB511BE61C84C3E73 +:10B24000A8AAAABE2DE9F84304460246504869461A +:10B25000B0EB420F09D94FF0E640B0EB420F94BF7C +:10B2600000204FF0FF30009034E04A4B22F00040C5 +:10B2700083422BD948492046FFF780FAFFF709FCA3 +:10B280008046FFF70BFB00F0030000904349404667 +:10B29000FFF774FA054642494046FFF76FFA064643 +:10B2A00040494046FFF76AFA07463F494046FFF7E4 +:10B2B00065FA2146FFF75FFA3946FFF759FA31463A +:10B2C000FFF756FA2946FFF753FA02E01046FFF758 +:10B2D000F1FC04462546009C002C18DA6800B0F109 +:10B2E0007F4F3CBF4FF07E50BDE8F88309D14FF04F +:10B2F0000100FFF79BFDBDE8F84300210846FFF77A +:10B3000073BA2846BDE8F8430121FFF7ADBA2946D4 +:10B3100014F0010F08461CD0FFF730FA0646234907 +:10B32000FFF72CFA2249FFF726FA3146FFF726FAF3 +:10B330002049FFF7CBF93146FFF720FA2946FFF7FE +:10B340001DFA2946FFF7C2F914F0020F1CD0BDE820 +:10B35000F883FFF713FA05461749FFF70FFA174965 +:10B36000FFF7B4F92946FFF709FA1549FFF7AEF9D7 +:10B370002946FFF703FA4FF07E51FFF7A7F914F0C3 +:10B38000020F08BFBDE8F88380F00040BDE8F883F5 +:10B39000B61F927E490E494683F9223F1A61342C2A +:10B3A0000020A23300A0FD390000C93F336D4C39A5 +:10B3B000DA82083CA0AA2ABEB93AB2BACA9F2A3D8C +:10B3C000DDFFFFBE2DE9F04104464FF019404E4924 +:10B3D000002500EB4400884230D94FF0FF4131EAAC +:10B3E000040018D04FF0CE41B1EB440F84BF4FF0B2 +:10B3F0007E50BDE8F0814549B1EB440F28BF0125DF +:10B400001CD20220FFF712FD14F0004F0FD0BDE850 +:10B41000F041FFF749BC204614F5000F04BF00209F +:10B42000BDE8F0810121BDE8F041FFF71DBABDE89C +:10B43000F04161214FF0E040FFF716BA3449204651 +:10B44000FFF79CF9FFF725FB8046FFF727FA064632 +:10B4500030494046FFF792F907462F494046FFF72B +:10B460008DF92146FFF787F93946FFF781F9044640 +:10B470002A49FFF783F92A49FFF728F92146FFF700 +:10B480007DF96FF04141FFF721F92146FFF776F989 +:10B490002449FFF71BF92146FFF770F901462248BE +:10B4A00006F00304784450F82400FFF767F91F49B9 +:10B4B000794451F82410FFF709F91D49794451F8EE +:10B4C0002410FFF703F9B110D5B1FFF7CDF904004F +:10B4D0000BD0B4F1FF4F0FD0FFF7CEFB042808BF0D +:10B4E000FFF7E2FB2046BDE8F0810220FFF79EFC5B +:10B4F000BDE8F041FFF7D8BB0220FFF797FC96E7C5 +:10B50000BDE8F041FFF7B0B90000501E0000A08573 +:10B510003BAAB840F4FD05370070313E12BB2A3D0E +:10B5200012BB2A3EFFFF7F3F2414000008140000D6 +:10B53000EC1300002DE9F0410026A0F50001B1F167 +:10B54000FE4F22D34FF07F42B2EB400F04D2BDE852 +:10B55000F0410121FFF788B9B0F1FF4F08BFBDE806 +:10B56000F081B0F1004F08D90120FFF75FFCBDE882 +:10B57000F04100210846FFF737B930F000415ED0B6 +:10B580006FF016061721FFF76FF900F500226FF034 +:10B590007E0101EBE251C2F3025477184FF07E5264 +:10B5A000A0EBC15602EB045557EA040050D02946DF +:10B5B0003046FFF78BF8804629463046FFF7D8F82B +:10B5C0004146FFF711F905460146FFF7D7F88046D7 +:10B5D0003349FFF7D3F83349FFF778F80646414679 +:10B5E0002846FFF7CBF83146FFF7C8F8064638463D +:10B5F000FFF746F907462C49FFF7C0F82B49794475 +:10B6000051F82410FFF762F83146FFF75FF806465D +:10B6100001212846FFF728F93146FFF757F805467C +:10B6200038462349FFF7AAF82249794451F82410F3 +:10B63000FFF74CF82946BDE8F041FFF747B8022074 +:10B64000FFF7F4FBBDE8F04100211B48FFF7CCB841 +:10B650004FF07E513046FFF78BF805461749FFF74C +:10B660008DF81749FFF732F82946FFF787F8154993 +:10B67000FFF72CF82946FFF781F86FF08241FFF7BA +:10B6800025F8044629460846FFF778F82146FFF7D3 +:10B6900075F801462846BDE8F041FFF717B80000ED +:10B6A00066F1CC3EAAAA2A3FF4FD0538FA12000042 +:10B6B0000070313FAE120000000080BF21ED423E1D +:10B6C0000A1180BEC1ABAA3E70B50546FFF7FFF96F +:10B6D00004464000801C0DD12846FFF7DAF90546E4 +:10B6E0002046FFF7CDF82946FFF706F91CBF0120D9 +:10B6F000FFF79CFB204670BD2DE9F8430446024647 +:10B7000053486946B0EB420F09D94FF0E640B0EB21 +:10B71000420F94BF00204FF0FF30009034E04D4BBB +:10B7200022F0004083422BD94B492046FFF726F8F0 +:10B73000FFF7AFF98046FFF7B1F800F00300009083 +:10B7400046494046FFF71AF8054645494046FFF787 +:10B7500015F8064643494046FFF710F807464249A8 +:10B760004046FFF70BF82146FFF705F83946FEF78C +:10B77000FFFF3146FEF7FCFF2946FEF7F9FF02E026 +:10B780001046FFF797FA04462546009C002C1DDA68 +:10B790006800B0F17F4F09D22846FFF76DFA042800 +:10B7A00008BFFFF781FA2846BDE8F88308D10120D9 +:10B7B000FFF73CFBBDE8F84300210846FFF714B84B +:10B7C0002846BDE8F8430121FFF74EB8294614F09A +:10B7D000010F08461ED0FEF7D1FF05462349FEF7AC +:10B7E000CDFF2349FEF772FF2946FEF7C7FF214927 +:10B7F000FEF76CFF2946FEF7C1FF4FF07E51FEF7C2 +:10B8000065FF14F0020F08BFBDE8F88380F0004028 +:10B81000BDE8F883FEF7B2FF06461749FEF7AEFF14 +:10B820001649FEF7A8FF3146FEF7A8FF1449FEF7B8 +:10B830004DFF3146FEF7A2FF2946FEF79FFF29463E +:10B84000FEF744FF14F0020FE0D1BDE8F8830000DA +:10B85000B61F927E490E494683F9223F1A61342C65 +:10B860000020A23300A0FD390000C93FB93AB2BAA6 +:10B87000CA9F2A3DDDFFFFBE336D4C39DA82083C9A +:10B88000A0AA2ABE70B50546FFF7D4F8044620F0FA +:10B890000040C0F1FF40C00F08D025F00040C0F1CB +:10B8A000FF40C00F04BF0120FFF7C0FA204670BD63 +:10B8B00053CA0008A3CA0008E9CA000850CA000811 +:10B8C00057CA0008F9C90008F4C9000844CA0008AA +:10B8D000E9C90008E3CA0008FCC90008B4CA0008A6 +:10B8E000F8CA000813CA000881CA000820CA000864 +:10B8F000E2C900087ACA0008000000008FCA0008E8 +:10B90000D3CA00085ECA0008EFCA0008A9CA000826 +:10B91000D8CA00082CCA00083BCA0008CFCA0008D1 +:10B920000ACA0008BECA000802CB0008C4CA000840 +:10B9300093CA000807CA00086FCA00080000000088 +:10B940009ECA000803CA000899CA00081CCA000859 +:10B95000BECA0008CFCA00080000000031D10008AC +:10B96000ECC90008D3C90008F1D00008DBC9000801 +:10B9700053CC0008000000000CD100089FD0000844 +:10B980003303000807D1000899CF00088703000897 +:10B99000ECCF00084DD00008A906000869CF0008C8 +:10B9A00080CE00085B0700081AD0000831D10008DB +:10B9B000D10800087CCC0008EBCD0008F108000895 +:10B9C00064CF000831D10008BD09000860CF00082D +:10B9D0006ECF0008E9090008A7CF00086AD0000868 +:10B9E000730C000804CC0008C4C90008F70C000858 +:10B9F000F1CC00083DD00008AB08000816D00008C4 +:10BA00007DD00008310D00080FD0000803D00008D9 +:10BA1000710E0008BDCE000831D100081B0F0008D0 +:10BA20004ACC000802000000700400200000000062 +:10BA30002823000016CB0008020000007805002033 +:10BA4000B0040000A406000032CC00080200000090 +:10BA50003405002000000000D00700003ECC0008A4 +:10BA6000020000003605002000000000D0070000A2 +:10BA7000B4CB0008020000003805002000000000E0 +:10BA8000D00700009BCD0008020000007A050020CE +:10BA900000000000D0070000A4CD00080200000054 +:10BAA0007C05002000000000D0070000E2D0000864 +:10BAB000020000003A05002000000000D00700004E +:10BAC0006CCD0008020000003C05002000000000D2 +:10BAD000D00700001CCB0008020000003E0500203B +:10BAE00000000000D00700000CCC0008020000009D +:10BAF0004005002000000000D0070000ABCC00088B +:10BB0000020000004205002032000000F2010000A7 +:10BB10009CCC000802000000440500203200000018 +:10BB2000F201000073CE0008000000007E05002036 +:10BB30000000000001000000CCCC00080400000060 +:10BB400084050020B004000000C20100C8CC000839 +:10BB5000040000008805002080250000004B000044 +:10BB600045CB0008000000008C050020000000000C +:10BB70000100000058CC00080000000080050020F3 +:10BB80000000000003000000DCCC00080100000001 +:10BB900081050020FFFFFFFF0400000061CC0008CA +:10BBA00000000000760500200000000002000000F8 +:10BBB000BCCD0008000000008D0500200000000042 +:10BBC00001000000FACB0008000000006A05002018 +:10BBD0000A000000C8000000D2CB000800000000EE +:10BBE0006B0500200A00000032000000BFCB0008F7 +:10BBF000000000006C0500200A0000003200000078 +:10BC0000FFCD0008000000006D05002000000000CE +:10BC10000900000024CF00080000000046050020B5 +:10BC200000000000080000000CCB0008000000002D +:10BC30004705002000000000080000001CCD00089F +:10BC4000000000004805002000000000080000007F +:10BC500046CE0008030000004A0500204CFFFFFF0D +:10BC6000680100003BCD0008030000004C050020E7 +:10BC70004CFFFFFF68010000C6D000080300000071 +:10BC80004E0500204CFFFFFF68010000D5CE0008E4 +:10BC90000100000050050020FFFFFFFF0100000031 +:10BCA0006FCC0008000000005105002000000000DB +:10BCB0000500000061CB0008000000005C050020CA +:10BCC000000000008000000013CD0008020000000A +:10BCD000520500200000000000010000BCCF000859 +:10BCE000020000005405002064000000E80300008A +:10BCF000CDCF0008020000005605002064000000BF +:10BD0000E80300008ACF000800000000E0070020E0 +:10BD10000000000001000000ABCB000800000000A4 +:10BD2000460800200000000020000000A8CB00080A +:10BD30000000000047080020000000006400000030 +:10BD4000D1CD0008000000004808002001000000DC +:10BD5000FA000000E5CB00080000000049080020C0 +:10BD60000000000001000000F9CE00080000000003 +:10BD70004A080020000000006400000084CC000895 +:10BD800000000000FF07002000000000FA00000093 +:10BD900013CF000800000000000800200000000091 +:10BDA0006400000059CB00080000000001080020DA +:10BDB00000000000640000001BCF0008000000002D +:10BDC0000208002000000000FA0000008CCC0008EF +:10BDD00000000000030800200000000064000000D4 +:10BDE000E9CC00080000000004080020000000006A +:10BDF0006400000010D10008000000008C08002042 +:10BE000000000000C80000001FD100080000000072 +:10BE10008D08002000000000C800000020CC0008B1 +:10BE2000020000008E080020E8030000D007000098 +:10BE300071CB0008020000009008002064000000A0 +:10BE4000D007000011CE0008010000007F0500208F +:10BE50000000000004000000EBCE0008010000001C +:10BE600092080020FFFFFFFF010000002FCF000815 +:10BE70000100000093080020000000000100000005 +:10BE8000DFCF000800000000940800200000000040 +:10BE9000FF000000ADCF0008000000000C080020EB +:10BEA00000000000FA0000008BCB0008000000003A +:10BEB0000E08002000000000640000009ACB00087B +:10BEC000000000000D0800200000000064000000D9 +:10BED000ADCD0008000000001C080020000000009C +:10BEE0000100000055CD0008030000000A080020F2 +:10BEF000D4FEFFFF2C0100005ECE0008030000000E +:10BF000008080020D4FEFFFF2C010000F6CC00083A +:10BF1000000000000F0800200000000030000000BA +:10BF200004CD0008050000001008002000000000FB +:10BF30000100000022CE00080500000014080020C7 +:10BF4000000000000100000025D0000805000000EE +:10BF5000180800200000000001000000C5CE000805 +:10BF60000300000006080020B0B9FFFF50460000A3 +:10BF70004CCF000800000000E50700200000000092 +:10BF8000C800000087CD000800000000EF07002077 +:10BF900000000000C800000031CB000800000000D5 +:10BFA000F907002000000000C800000041CF000891 +:10BFB00000000000E607002000000000C8000000AC +:10BFC0007CCD000800000000F00700200000000009 +:10BFD000C800000026CB000800000000FA0700207F +:10BFE00000000000C800000056CF0008000000005C +:10BFF000E707002000000000C800000091CD000805 +:10C0000000000000F107002000000000C800000050 +:10C010003BCB000800000000FB07002000000000F0 +:10C02000C8000000F5CF00080200000096080020BC +:10C0300000000000D007000026CD0008000000002E +:10C040009A0800200000000001000000AFCE0008A8 +:10C05000020000009C0800200A000000D007000039 +:10C06000F9D00008020000009E0800200A0000002D +:10C07000D0070000BACC000800000000990800209A +:10C08000000000006400000064CD00080000000013 +:10C09000E207002000000000C80000004DCD0008AD +:10C0A00000000000EC07002000000000C8000000B5 +:10C0B00045CD000800000000F60700200000000049 +:10C0C000C80000006CCE000800000000E10700205E +:10C0D00000000000C800000057CE0008000000006B +:10C0E000EB07002000000000C800000050CE000850 +:10C0F00000000000F507002000000000C80000005C +:10C10000DCD0000800000000E30700200000000071 +:10C11000C8000000D6D0000800000000ED07002095 +:10C1200000000000C8000000D0D00008000000009F +:10C13000F707002000000000C800000037D000080A +:10C1400000000000E407002000000000C80000001C +:10C1500031D0000800000000EE07002000000000C1 +:10C16000C80000001FD0000800000000F8070020F1 +:10C1700000000000C80000003ECE000800000000E3 +:10C18000E807002000000000C800000036CE0008CC +:10C1900000000000F207002000000000C8000000BE +:10C1A0002ECE000800000000FC0700200000000068 +:10C1B000C8000000414552543132333400000000C1 +:10C1C0000000803F00000000A8AAAA3F0000000075 +:10C1D0000000803F000080BFB0AA2ABF000000001E +:10C1E0000000803F0000803FB0AA2ABF000000008E +:10C1F0000000803F000000000000803F000080BF82 +:10C200000000803F000080BF000000000000803F71 +:10C210000000803F0000803F000000000000803FE1 +:10C220000000803F00000000000080BF000080BFD1 +:10C230000000803F000080BF0000803F000080BF02 +:10C240000000803F000080BF000080BF0000803FF2 +:10C250000000803F0000803F0000803F0000803FE2 +:10C260000000803F0000803F000080BF000080BFD2 +:10C270000000803F0000803F000000000000000040 +:10C280000000803F000080BF0000000000000000B0 +:10C290000000803F00000000A8AAAA3F0000803FE5 +:10C2A0000000803F000080BFB0AA2ABF000080BF0E +:10C2B0000000803F0000803FB0AA2ABF000080BF7E +:10C2C0000000803F00000000A8AAAA3F000080BF35 +:10C2D0000000803F000080BFB0AA2ABF0000803F5E +:10C2E0000000803F0000803FB0AA2ABF0000803FCE +:10C2F0000000803F000080BFD0B35D3F0000803F62 +:10C300000000803F000080BFD0B35DBF000080BF51 +:10C310000000803F0000803FD0B35D3F0000803FC1 +:10C320000000803F0000803FD0B35DBF000080BFB1 +:10C330000000803F00000000D0B35DBF0000803FE0 +:10C340000000803F00000000D0B35D3F000080BFD0 +:10C350000000803F000000000000803F000080BF20 +:10C360000000803F000080BF000080BF0000000090 +:10C370000000803F000000000000803F0000803F80 +:10C380000000803F0000803F000080BF00000000F0 +:10C390000000803FD0B35DBF0000803F0000803FC1 +:10C3A0000000803FD0B35DBF000080BF0000803F31 +:10C3B0000000803FD0B35D3F0000803F000080BFA1 +:10C3C0000000803FD0B35D3F000080BF000080BF11 +:10C3D0000000803FD0B35DBF00000000000080BFC0 +:10C3E0000000803FD0B35D3F000000000000803FB0 +:10C3F0000000803F000080BF0000803F000080BF41 +:10C400000000803F000080BF000080BF0000803F30 +:10C410000000803F0000803F0000803F0000803F20 +:10C420000000803F0000803F000080BF000080BF10 +:10C430000000803F000080BF0000803F0000803F80 +:10C440000000803F000080BF000080BF000080BF70 +:10C450000000803F0000803F0000803F000080BF60 +:10C460000000803F0000803F000080BF0000803F50 +:10C470000000803FF704353FF70435BF0000803FE0 +:10C480000000803FF70435BFF70435BF0000803F50 +:10C490000000803FF70435BFF704353F0000803FC0 +:10C4A0000000803FF704353FF704353F0000803F30 +:10C4B0000000803F00000000000080BF000080BF3F +:10C4C0000000803F000080BF00000000000080BF2F +:10C4D0000000803F000000000000803F000080BF9F +:10C4E0000000803F0000803F00000000000080BF8F +:10C4F0000000803F0000803F000000BF0000803F40 +:10C500000000803F000000BF000080BF0000803FAF +:10C510000000803F000080BF0000003F0000803F1F +:10C520000000803F0000003F0000803F0000803F8F +:10C530000000803F0000003F000080BF000080BF7F +:10C540000000803F000080BF000000BF000080BFEF +:10C550000000803F000000BF0000803F000080BF5F +:10C560000000803F0000803F0000003F000080BFCF +:10C570000000803F000000000000803F0000803F7E +:10C580000000803F000080BF000080BF000000006E +:10C590000000803F000000000000803F000080BFDE +:10C5A0000000803F0000803F000080BF000000804E +:10C5B000000000000000000003010000C0C10008EE +:10C5C00004000000F0C100080400000030C20008B0 +:10C5D0000201000070C2000800010000000000001D +:10C5E0000600000090C2000806000000F0C200082B +:10C5F00001010000000000000400000050C300081A +:10C600000600000090C3000808000000F0C3000806 +:10C610000800000070C4000808000000F0C4000812 +:10C620000101000000000000000100000000000007 +:10C6300000010000000000000400000070C50008B8 +:10C640000000000000000000524F4C4C3B50495489 +:10C6500043483B5941573B414C543B506F733B500F +:10C660006F73523B4E6176523B4C4556454C3B4DA9 +:10C6700041473B56454C3B0000C2010078D20008C0 +:10C680009BD2000800E1000056D2000842D2000808 +:10C69000009600000CD200082ED20008004B0000CB +:10C6A000EAD10008D6D100088025000031D1000869 +:10C6B00031D10008B56206010300F00500FF19B58D +:10C6C0006206010300F00300FD15B56206010300D8 +:10C6D000F00100FB11B56206010300F00000FA0F43 +:10C6E000B56206010300F00200FC13B56206010307 +:10C6F00000F00400FE17B562060103000102010EFE +:10C7000047B562060103000103010F49B562060146 +:10C710000300010601124FB5620601030001120178 +:10C720001E67B562061608000307030051080000E3 +:10C730008A41B56206080600C80001000100DE6AF1 +:10C740001048494A4B4C4D44454647FF202122237F +:10C750002425262748494A4B4C4DFF1048498A8BCF +:10C760008C8D84858687FF20212223242526274837 +:10C77000498A8B8C8DFF00004CC7000840C7000819 +:10C7800067C700085BC70008000C014008001002E2 +:10C79000000C0140100010020008014000101402BB +:10C7A00025820008C1810008F58100084381000846 +:10C7B000DB8100080000004000080140010000008B +:10C7C000001C0000000000400008014002000000C2 +:10C7D000041C0000000000400008014004000000AC +:10C7E000081C000000000040000801400800000094 +:10C7F0000C1C000000040040000801404000000044 +:10C80000001D0000000400400008014080000000FE +:10C81000041D000000040040000C01400100000065 +:10C82000081D000000040040000C01400200000050 +:10C830000C1D0000002C0140000801400001000018 +:10C84000001B0100002C014000080140000800000E +:10C850000C1B010000080040000C014040000000DB +:10C86000001E000000080040000C01408000000095 +:10C87000041E000000080040000C01400001000000 +:10C88000081E000000080040000C014000020000EB +:10C890000C1E00000004080C7B9300083393000872 +:10C8A0005593000893930008079200080000803F0A +:10C8B0000030983F0000B53F0040D73F0000000027 +:10C8C000320A7E397F661E395B991F390000803F2E +:10C8D000F037983FF304B53FFD44D73F0000000018 +:10C8E0000030F13D0070643E0000A33E0090CF3E5A +:10C8F0000090F83E00400F3F00E0203F00000000A5 +:10C9000015B78337CDE37B380EE1C53860F6913833 +:10C91000AF5F0F38E1BC3E3823F447390040404058 +:10C920004040404040404141414141404040404002 +:10C9300040404040404040404040404040050202AE +:10C94000020202020202020202020202022020206D +:10C9500020202020202020020202020202029090C9 +:10C9600090909090101010101010101010101010C7 +:10C97000101010101010101002020202020288881B +:10C980008888888808080808080808080808080827 +:10C99000080808080808080802020202400000000F +:10C9A0001DC90008000000006E83F9A22915444E3D +:10C9B000D15727FCC0DD34F5999562DB4190433CAB +:10C9C000AB6351FE696E64657820283020746F2057 +:10C9D0003229004D50553630353000424D41323805 +:10C9E0003000565441494C34005934004144584CAD +:10C9F0003334350048455836005936004F43544FBC +:10CA0000583800414343003344004641494C5341A8 +:10CA1000464500414952504C414E45004D4147006A +:10CA200048454C495F39305F444547004759524FAC +:10CA30005F534D4F4F5448494E47004C45445F5259 +:10CA4000494E4700464C59494E475F57494E4700AB +:10CA50004249005452490047494D42414C00494E19 +:10CA6000464C494748545F4143435F43414C005360 +:10CA70004F465453455249414C00435553544F4D32 +:10CA80000048454C495F3132305F4343504D0050C0 +:10CA9000504D00564152494F004241524F004759B4 +:10CAA000524F005155414450004D4F544F525F5327 +:10CAB000544F50004F43544F464C41545000534F35 +:10CAC0004E415200504F5745524D45544552004734 +:10CAD0005053005642415400534552564F5F5449FB +:10CAE0004C5400484558365800515541445800535D +:10CAF000455249414C5258004F43544F464C4154C3 +:10CB0000580054454C454D4554525900616C696775 +:10CB10006E5F616363006D69647263006E65757456 +:10CB200072616C3364006770735F706F73725F64FF +:10CB3000006770735F706F735F64006770735F6E20 +:10CB400061765F6400736F667473657269616C5FB0 +:10CB5000696E766572746564007468725F6D69648D +:10CB6000006D6F726F6E5F7468726573686F6C646E +:10CB7000006661696C736166655F646574656374A2 +:10CB80005F7468726573686F6C6400616363787961 +:10CB90005F6465616462616E64006163637A5F64AF +:10CBA00065616462616E6400796177646561646285 +:10CBB000616E64006D696E636F6D6D616E640076A9 +:10CBC0006261746D696E63656C6C766F6C746167BD +:10CBD0006500766261746D617863656C6C766F6C0C +:10CBE0007461676500616C745F686F6C645F666137 +:10CBF00073745F6368616E67650076626174736306 +:10CC0000616C650070726F66696C65006465616473 +:10CC100062616E6433645F7468726F74746C650013 +:10CC20006661696C736166655F7468726F74746C59 +:10CC300065006D696E7468726F74746C65006D6107 +:10CC4000787468726F74746C65006C6F6F7074695F +:10CC50006D65004E6F6E65006770735F7479706507 +:10CC60000073657269616C72785F747970650061D8 +:10CC700063635F68617264776172650066656174A1 +:10CC80007572650072635F7261746500726F6C6CBF +:10CC90005F70697463685F72617465007365727652 +:10CCA0006F5F70776D5F72617465006D6F746F7226 +:10CCB0005F70776D5F72617465006E61765F736C33 +:10CCC00065775F7261746500736F6674736572690E +:10CCD000616C5F6261756472617465006770735F37 +:10CCE00062617564726174650079617772617465FF +:10CCF0000073617665006261726F5F7461625F7379 +:10CD0000697A65006261726F5F6E6F6973655F6CEF +:10CD10007066006779726F5F6C706600616C69673E +:10CD20006E5F6D6167006E61765F636F6E74726FC8 +:10CD30006C735F68656164696E6700616C69676EDA +:10CD40005F626F6172645F706974636800695F70CD +:10CD500069746368006163635F7472696D5F7069B1 +:10CD600074636800705F706974636800646561640F +:10CD700062616E6433645F68696768006770735FDF +:10CD8000706F73725F69006770735F706F735F6954 +:10CD9000006770735F6E61765F69006D696E6368CE +:10CDA00065636B006D6178636865636B00616363E5 +:10CDB0005F756E61726D656463616C0074656C654E +:10CDC0006D657472795F736F667473657269616C97 +:10CDD00000616C745F686F6C645F7468726F747408 +:10CDE0006C655F6E65757472616C006C697374203C +:10CDF0006F72202D76616C206F722076616C0070EE +:10CE00006F7765725F6164635F6368616E6E656CA6 +:10CE100000727373695F6175785F6368616E6E65D8 +:10CE20006C006261726F5F63665F76656C00645F61 +:10CE30006C6576656C00695F6C6576656C00705F2B +:10CE40006C6576656C00616C69676E5F626F6172BC +:10CE5000645F726F6C6C00695F726F6C6C00616311 +:10CE6000635F7472696D5F726F6C6C00705F726F7C +:10CE70006C6C0072657461726465645F61726D00F0 +:10CE80007072696E7420636F6E6669677572616235 +:10CE90006C652073657474696E677320696E2061B8 +:10CEA000207061737461626C6520666F726D006ED4 +:10CEB00061765F73706565645F6D696E007665723B +:10CEC00073696F6E006D61675F6465636C696E6145 +:10CED00074696F6E007961775F636F6E74726F6CE7 +:10CEE0005F646972656374696F6E007961775F640E +:10CEF0006972656374696F6E007468726F74746CC4 +:10CF0000655F616E676C655F636F7272656374699C +:10CF10006F6E0072635F6578706F007468725F6532 +:10CF200078706F00616C69676E5F6779726F00740B +:10CF300072695F756E61726D65645F736572766F3D +:10CF4000006770735F706F73725F70006770735FFC +:10CF5000706F735F70006770735F6E61765F7000F3 +:10CF60006D61700068656C700064756D70006D6156 +:10CF70007070696E67206F66207263206368616EEF +:10CF80006E656C206F72646572007069645F636FB8 +:10CF90006E74726F6C6C65720064657369676E2085 +:10CFA000637573746F6D206D69786572006163637A +:10CFB0005F6C70665F666163746F72006779726F31 +:10CFC0005F636D70665F666163746F72006779722C +:10CFD0006F5F636D70666D5F666163746F7200672B +:10CFE000696D62616C5F666C616773006465666140 +:10CFF000756C7473006770735F77705F72616469DA +:10D0000075730073686F772073797374656D20731F +:10D010007461747573007365740065786974006475 +:10D020005F616C74006261726F5F63665F616C74F4 +:10D0300000695F616C7400705F616C74007361768D +:10D040006520616E64207265626F6F740072657333 +:10D05000657420746F2064656661756C74732061FB +:10D060006E64207265626F6F74006D6978657220FE +:10D070006E616D65206F72206C697374006E616DF6 +:10D08000653D76616C7565206F7220626C616E6BB8 +:10D09000206F72202A20666F72206C69737400669C +:10D0A0006561747572655F6E616D65206175786626 +:10D0B0006C6167206F7220626C616E6B20666F72AC +:10D0C000206C69737400616C69676E5F626F617276 +:10D0D000645F79617700695F79617700705F79617A +:10D0E00077006465616462616E6433645F6C6F775E +:10D0F000004D4D4138343578006E61765F73706550 +:10D1000065645F6D617800636D69780061757800B2 +:10D110006661696C736166655F64656C6179006600 +:10D1200061696C736166655F6F66665F64656C619B +:10D13000790043414D535441423B0043414C4942E5 +:10D140003B0047505320484F4C443B004845414426 +:10D15000465245453B00414E474C453B00475053E6 +:10D1600020484F4D453B004D41473B0043414D5406 +:10D170005249473B004845414441444A3B004152E3 +:10D180004D3B00484F52495A4F4E3B005641524981 +:10D190004F3B004241524F3B004245455045523BB8 +:10D1A00000474F5645524E4F523B004C4C49474862 +:10D1B00054533B0050415353544852553B004C4547 +:10D1C000444C4F573B004F53442053573B004C4572 +:10D1D000444D41583B0024504D544B3235312C3195 +:10D1E000393230302A32320D0A0024505542582C40 +:10D1F00034312C312C303030332C303030312C3134 +:10D20000393230302C302A32330D0A002450554246 +:10D21000582C34312C312C303030332C30303031EC +:10D220002C33383430302C302A32360D0A0024505A +:10D230004D544B3235312C33383430302A32370D9F +:10D240000A0024504D544B3235312C3537363030AE +:10D250002A32430D0A0024505542582C34312C31C7 +:10D260002C303030332C303030312C3537363030B4 +:10D270002C302A32440D0A0024505542582C3431A7 +:10D280002C312C303030332C303030312C313135A2 +:10D290003230302C302A31450D0A0024504D544B89 +:10D2A0003235312C3131353230302A31460D0A00D9 +:10D2B000D0D200080000002034040000FAAB0008BF +:10D2C000C0D30008340400202C2500001CAE000848 +:10D2D0000192031A7A44CBDC0502A10237011391B3 +:10D2E00030025C08021A030936B3914B7ED1BC2987 +:10D2F000491A560C290832021A830C2908297C1A6B +:10D30000930C290832041A8C0C290832051A670C70 +:10D31000290832061A4C0C290832071A750C2908FC +:10D3200029591A320C290832091A6C0C2908320AB8 +:10D330001A5D0C2908320B1A420C2908320C1AB457 +:10D340000C2908320D1A990C2908320E1ACE0C2914 +:10D3500008320F1ABE0C290832101AAB0C290832F9 +:10D36000111A3B0C290832121AA10C290832131A7F +:10D37000C60C2908721402A7FF021001E20452032E +:10D380008B803F0401165A03494AD931E91D120125 +:10D390000A1C0285C208342C01401A408C1A40191C +:10D3A0003A405B14A24A048B127A33380B0203040E +:10D3B000060708090204063B2910691481000000D1 :04000005080000ED02 :00000001FF From 35f0a8e4b043a59d99ead4341a7df5c35198dece Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Wed, 30 Oct 2013 11:57:54 +0000 Subject: [PATCH 23/56] old altitude calculation used again, added lpf for accZ by Luggi09 git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@462 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/config.c | 4 ++-- src/imu.c | 39 ++++++++++++++++++++++++--------------- 2 files changed, 26 insertions(+), 17 deletions(-) diff --git a/src/config.c b/src/config.c index fe2b5d7eb..7e715675a 100755 --- a/src/config.c +++ b/src/config.c @@ -227,9 +227,9 @@ static void resetConf(void) cfg.P8[YAW] = 85; cfg.I8[YAW] = 45; cfg.D8[YAW] = 0; - cfg.P8[PIDALT] = 50; + cfg.P8[PIDALT] = 40; cfg.I8[PIDALT] = 25; - cfg.D8[PIDALT] = 80; + cfg.D8[PIDALT] = 60; cfg.P8[PIDPOS] = 11; // POSHOLD_P * 100; cfg.I8[PIDPOS] = 0; // POSHOLD_I * 100; cfg.D8[PIDPOS] = 0; diff --git a/src/imu.c b/src/imu.c index 13c73d13e..b70bbd160 100755 --- a/src/imu.c +++ b/src/imu.c @@ -172,17 +172,21 @@ int32_t applyDeadband(int32_t value, int32_t deadband) return value; } +#define F_CUT_ACCZ 20.0f +static const float fc_acc = 0.5f / (M_PI * F_CUT_ACCZ); + // rotate acc into Earth frame and calculate acceleration in it void acc_calc(uint32_t deltaT) { static int32_t accZoffset = 0; + static float accz_smooth; float rpy[3]; t_fp_vector accel_ned; // the accel values have to be rotated into the earth frame rpy[0] = -(float)anglerad[ROLL]; rpy[1] = -(float)anglerad[PITCH]; - rpy[2] = -(float)heading * RADX10 * 10.0f; + rpy[2] = -(float)heading * RAD; accel_ned.V.X = accSmooth[0]; accel_ned.V.Y = accSmooth[1]; @@ -198,19 +202,21 @@ void acc_calc(uint32_t deltaT) accel_ned.V.Z -= accZoffset / 64; // compensate for gravitation on z-axis } else accel_ned.V.Z -= acc_1G; + + accz_smooth = accz_smooth + (deltaT / (fc_acc + deltaT)) * (accel_ned.V.Z - accz_smooth); // low pass filter // apply Deadband to reduce integration drift and vibration influence - accel_ned.V.Z = applyDeadband(accel_ned.V.Z, cfg.accz_deadband); - accel_ned.V.X = applyDeadband(accel_ned.V.X, cfg.accxy_deadband); - accel_ned.V.Y = applyDeadband(accel_ned.V.Y, cfg.accxy_deadband); + accel_ned.V.Z = applyDeadband(lrintf(accz_smooth), cfg.accz_deadband); + accel_ned.V.X = applyDeadband(lrintf(accel_ned.V.X), cfg.accxy_deadband); + accel_ned.V.Y = applyDeadband(lrintf(accel_ned.V.Y), cfg.accxy_deadband); // sum up Values for later integration to get velocity and distance accTimeSum += deltaT; accSumCount++; - accSum[0] += accel_ned.V.X; - accSum[1] += accel_ned.V.Y; - accSum[2] += accel_ned.V.Z; + accSum[X] += lrintf(accel_ned.V.X); + accSum[Y] += lrintf(accel_ned.V.Y); + accSum[Z] += lrintf(accel_ned.V.Z); } void accSum_reset(void) @@ -317,7 +323,6 @@ static void getEstimatedAttitude(void) int getEstimatedAltitude(void) { - static int32_t baroGroundPressure; static uint32_t previousT; uint32_t currentT = micros(); uint32_t dTime; @@ -326,11 +331,12 @@ int getEstimatedAltitude(void) int32_t vel_tmp; int32_t BaroAlt_tmp; float dt; - float PressureScaling; float vel_acc; static float vel = 0.0f; static float accAlt = 0.0f; static int32_t lastBaroAlt; + static int32_t baroGroundAltitude = 0; + static int32_t baroGroundPressure = 0; dTime = currentT - previousT; if (dTime < UPDATE_INTERVAL) @@ -338,17 +344,20 @@ int getEstimatedAltitude(void) previousT = currentT; if (calibratingB > 0) { - baroGroundPressure = baroPressureSum / (cfg.baro_tab_size - 1); - calibratingB--; + baroGroundPressure -= baroGroundPressure / 8; + baroGroundPressure += baroPressureSum / (cfg.baro_tab_size - 1); + baroGroundAltitude = (1.0f - powf((baroGroundPressure / 8) / 101325.0f, 0.190295f)) * 4433000.0f; + vel = 0; accAlt = 0; + calibratingB--; } // calculates height from ground via baro readings // see: https://github.com/diydrones/ardupilot/blob/master/libraries/AP_Baro/AP_Baro.cpp#L140 - PressureScaling = (float)baroPressureSum / ((float)baroGroundPressure * (float)(cfg.baro_tab_size - 1)); - BaroAlt_tmp = 153.8462f * (baroTemperature + 27315) * (1.0f - expf(0.190259f * logf(PressureScaling))); // in cm - BaroAlt = (float)BaroAlt * cfg.baro_noise_lpf + (float)BaroAlt_tmp * (1.0f - cfg.baro_noise_lpf); // additional LPF to reduce baro noise + BaroAlt_tmp = lrintf((1.0f - powf((float)(baroPressureSum / (cfg.baro_tab_size - 1)) / 101325.0f, 0.190295f)) * 4433000.0f); // in cm + BaroAlt_tmp -= baroGroundAltitude; + BaroAlt = lrintf((float)BaroAlt * cfg.baro_noise_lpf + (float)BaroAlt_tmp * (1.0f - cfg.baro_noise_lpf)); // additional LPF to reduce baro noise dt = accTimeSum * 1e-6f; // delta acc reading time in seconds @@ -391,7 +400,7 @@ int getEstimatedAltitude(void) vel = constrain(vel, -1000, 1000); // limit max velocity to +/- 10m/s (36km/h) // D - vel_tmp = vel; + vel_tmp = lrintf(vel); vel_tmp = applyDeadband(vel_tmp, 5); vario = vel_tmp; BaroPID -= constrain(cfg.D8[PIDALT] * vel_tmp / 16, -150, 150); From 639f534c3150eaea53a3e3dd37f5499ab47a3d37 Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Wed, 30 Oct 2013 13:39:05 +0000 Subject: [PATCH 24/56] mag headfree fix after sensor unfucking thx Luggi09 git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@463 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/mw.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/mw.c b/src/mw.c index 19dd864c1..968788476 100755 --- a/src/mw.c +++ b/src/mw.c @@ -818,6 +818,7 @@ void loop(void) dif += 360; if (dif >= +180) dif -= 360; + dif *= -mcfg.yaw_control_direction; if (f.SMALL_ANGLES_25) rcCommand[YAW] -= dif * cfg.P8[PIDMAG] / 30; // 18 deg } else From 609df47cd4bf0361d32e37cd19e84692078f05cb Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Fri, 1 Nov 2013 00:47:05 +0000 Subject: [PATCH 25/56] tri gyro data reading fix - closes issue #18 git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@464 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- obj/baseflight.hex | 6487 ++++++++++++++++++++++---------------------- src/imu.c | 6 +- 2 files changed, 3304 insertions(+), 3189 deletions(-) diff --git a/obj/baseflight.hex b/obj/baseflight.hex index 9223a1b61..953d0d249 100644 --- a/obj/baseflight.hex +++ b/obj/baseflight.hex @@ -1,20 +1,20 @@ :020000040800F2 -:100000006029002035A4000875A4000823250008F5 -:1000100079A400087BA400087DA40008000000006B -:100020000000000000000000000000007FA40008A5 -:1000300081A400080000000083A40008957C00084B -:1000400087A4000887A4000887A4000887A40008E4 -:1000500087A4000887A4000887A40008DF87000899 -:1000600087A4000887A4000887A4000887A40008C4 -:1000700087A4000887A400085582000887A4000808 -:1000800087A4000887A4000887A4000887A40008A4 -:1000900087A4000887A4000887A40008E187000857 -:1000A00087A4000887A4000887A400083D900008E2 -:1000B00041900008479000084B9000080576000822 -:1000C000E3730008097600080776000887A4000893 -:1000D00087A4000881820008B582000887A4000870 -:1000E000216D000887A4000887A40008DFF80CD061 -:1000F0000AF014FD00480047E522000860290020AE +:10000000682900208DA40008CDA400086F250008F1 +:10001000D1A40008D3A40008D5A400080000000063 +:10002000000000000000000000000000D7A400084D +:10003000D9A4000800000000DBA40008ED7C000843 +:10004000DFA40008DFA40008DFA40008DFA4000884 +:10005000DFA40008DFA40008DFA400083788000838 +:10006000DFA40008DFA40008DFA40008DFA4000864 +:10007000DFA40008DFA40008AD820008DFA40008A8 +:10008000DFA40008DFA40008DFA40008DFA4000844 +:10009000DFA40008DFA40008DFA4000839880008F6 +:1000A000DFA40008DFA40008DFA400089590000882 +:1000B000999000089F900008A39000085D760008C2 +:1000C0003B740008617600085F760008DFA4000832 +:1000D000DFA40008D98200080D830008DFA400080F +:1000E000796D0008DFA40008DFA40008DFF80CD059 +:1000F0000AF016FE00480047312300086829002056 :1001000070B51546B0FBF5F40646A84203D3204669 :10011000FFF7F6FF014605FB1460FCA2105C0870B7 :10012000481C70BD70B50C46911E232900D30A22CD @@ -23,71 +23,71 @@ :10015000044600E0641C20782028FBD00928F9D050 :100160004FF07E58C1B247462D2902D02B2801D02E :1001700001E0F04F641C0026DFF8BC930CE000BFE8 -:100180000AF07EFB0546494630460AF0F7FA294652 -:100190000AF09CFA0646641C207830380928EFD90A -:1001A00020782E2815D14D460EE000BF0AF068FBDE -:1001B00029460AF019FB31460AF088FA06464946F4 -:1001C00028460AF0DBFA054614F8010F30380928F2 +:100180000AF0AAFB0546494630460AF023FB2946F9 +:100190000AF0C8FA0646641C207830380928EFD9DE +:1001A00020782E2815D14D460EE000BF0AF094FBB2 +:1001B00029460AF045FB31460AF0B4FA064649469C +:1001C00028460AF007FB054614F8010F30380928C5 :1001D000ECD921784046652901D0452935D114F85C :1001E000011F4FF000082D2902D02B2902D002E078 :1001F0004FF00108641C00256FF02F0206E000BFDD :1002000005EB850302EB4303CD18641C2178A1F1B3 :100210003003092BF4D94FF49A718D4204D90D465D -:10022000C6490AF0ABFA083D082DF9D203E0494669 -:100230000AF0A4FA6D1E002DF9D1B8F1000F04D018 -:10024000014630460AF0D0FA03E0014630460AF093 -:1002500095FA3946BDE8F0470AF090BAF0B587B094 +:10022000C6490AF0D7FA083D082DF9D203E049463D +:100230000AF0D0FA6D1E002DF9D1B8F1000F04D0EC +:10024000014630460AF0FCFA03E0014630460AF067 +:10025000C1FA3946BDE8F0470AF0BCBAF0B587B03C :1002600000260D46B74900960196B5A70296B0F54F -:10027000000F02DB0AF02AFA01E00AF079FAB2492B -:100280000AF07CFA0AF00AFB041E00DC60420A2233 +:10027000000F02DB0AF056FA01E00AF0A5FAB249D3 +:100280000AF0A8FA0AF036FB041E00DC60420A22DB :1002900003A9FFF747FF002C01DB202000E02D2001 -:1002A0008DF8000003A80AF0E4F9302401280AD0F0 -:1002B00003A80AF0DEF902280CD003A80AF0D9F945 +:1002A0008DF8000003A80AF010FA302401280AD0C3 +:1002B00003A80AF00AFA02280CD003A80AF005FAEB :1002C00003280CD00DE08DF801408DF802408DF828 :1002D000034006E08DF801408DF8024001E08DF802 -:1002E000014003A968460AF090F968460AF0C1F98E -:1002F000C01EC4B22246694628460AF0A4F92E550B -:10030000394628460AF081F90DEB040128460AF027 -:100310007CF907B02846F0BD70B505460C46086864 -:100320000AF0A7F9024621682868BDE870400AF083 -:10033000A7B970B506460AF09CF9844D10F0FF0F7E -:100340000FD030460AF0B5F90446142815DA2021FA -:1003500030460AF084F90AF0ACF905EB4401C8878D +:1002E000014003A968460AF0BCF968460AF0EDF936 +:1002F000C01EC4B22246694628460AF0D0F92E55DF +:10030000394628460AF0ADF90DEB040128460AF0FB +:10031000A8F907B02846F0BD70B505460C46086838 +:100320000AF0D3F9024621682868BDE870400AF057 +:10033000D3B970B506460AF0C8F9844D10F0FF0F26 +:100340000FD030460AF0E1F90446142815DA2021CE +:1003500030460AF0B0F90AF0D8F905EB4401C88735 :1003600070BD002405EB44002146C28F78A00AF03E -:1003700073FC641C142CF5DB70BDBDE870401421C7 -:1003800076A00AF069BC2DE9F041002588B0074647 -:100390002E460AF06EF97B4C10F0FF0FA84652D0A3 -:1003A000052279A138460AF06BF900287ED0042294 -:1003B00077A138460AF064F9002878D038460AF068 -:1003C00078F9461E0C2E73DA202138460AF047F9D8 +:1003700005FE641C142CF5DB70BDBDE87040142133 +:1003800076A00AF0FBBD2DE9F041002588B00746B4 +:100390002E460AF09AF97B4C10F0FF0FA84652D077 +:1003A000052279A138460AF097F900287ED0042268 +:1003B00077A138460AF090F9002878D038460AF03C +:1003C000A4F9461E0C2E73DA202138460AF073F980 :1003D000070007D0781C0746FFF7B8FE04EB0611AC -:1003E00001250861202138460AF039F9070007D0B5 +:1003E00001250861202138460AF065F9070007D089 :1003F000471C3846FFF7AAFE04EB06116D1C486146 -:10040000202138460AF02BF9070007D0471C384650 +:10040000202138460AF057F9070007D0471C384624 :10041000FFF79CFE04EB06116D1C88612021384615 -:100420000AF01DF930B1401CFFF790FE04EB0611F5 +:100420000AF049F930B1401CFFF790FE04EB0611C9 :100430006D1CC861042D67D057A000BF00F070FF8D :1004400008B0BDE8F08163A000F06AFF5FF000052E :1004500004EB0517386910F0FF4F2BD0761C691C90 -:1004600067A00AF0F9FB03A93869FFF7F7FE014618 -:1004700065A00AF0F1FB03A97869FFF7EFFE0146DA -:1004800061A00AF0E9FB03A9B869FFF7E7FE01469E -:100490005DA00AF0E1FB03A9F869FFF7DFFE014662 -:1004A0005AA00AF0D9FB6D1C0C2D02E0C8E0D0E088 +:1004600067A00AF08BFD03A93869FFF7F7FE014684 +:1004700065A00AF083FD03A97869FFF7EFFE014646 +:1004800061A00AF07BFD03A9B869FFF7E7FE01460A +:100490005DA00AF073FD03A9F869FFF7DFFE0146CE +:1004A0005AA00AF06BFD6D1C0C2D02E0C8E0D0E0F4 :1004B000F5E0CDDBCDF80880CDF804800025CDF83F -:1004C000008011E004EB0517009879690AF0FEF846 -:1004D0000090B96901980AF0F9F80190F969029859 -:1004E0000AF0F4F86D1C0290B542EBDB49A000F075 +:1004C000008011E004EB0517009879690AF02AF919 +:1004D0000090B96901980AF025F90190F96902982C +:1004E0000AF020F96D1C0290B542EBDB49A000F048 :1004F00017FF4C4E00246D4655F8240020F00040B4 :10050000B04202DD48A092E0C4E08FE030313233E7 :100510003435363738394142434445464748494ADD :100520004B4C4D4E4F505152535455565758595AA3 :1005300000000000000080BF0000204120BCBE4C35 -:100540002E0000006F12033A00007A44E0070020FA +:100540002E0000006F12033A00007A44E8070020F2 :100550006175782025752025750D0A00496E766134 :100560006C6964204665617475726520696E6465A6 :10057000783A206D757374206265203C2025750DD6 -:100580000A000000640400207265736574000000B6 +:100580000A0000006C0400207265736574000000AE :100590006C6F61640000000057726F6E67206E75AB :1005A0006D626572206F6620617267756D656E742D :1005B000732C206E6565647320696478207468729A @@ -100,68 +100,68 @@ :100620003A0900000AD7233C4E470900FDA000F01C :1006300077FE641C032CFFF65FAFAFF24000FDE6CF :100640000020414604EB0012401C11610C28F9DB2C -:10065000F6E6202138460AF002F80028F8D0401CBF -:1006600006460AF006F8F04DC7B2002455F82410EB -:1006700031B13A4630460AF003F818B1641CF5E788 -:10068000EAA0DBE6204601F0EFFF55F82410EDA0CC -:100690000AF0E2FAAFF26810FFF775FED0E60C211F -:1006A000EDA00AF0D9FACBE610B5F5A000F038FEBF +:10065000F6E6202138460AF02EF80028F8D0401C93 +:1006600006460AF032F8F04DC7B2002455F82410BF +:1006700031B13A4630460AF02FF818B1641CF5E75C +:10068000EAA0DBE6204602F015F855F82410EDA0AC +:100690000AF074FCAFF26810FFF775FED0E60C218B +:1006A000EDA00AF06BFCCBE610B5F5A000F038FE2B :1006B000012001F0DAF8F9A000F032FE0A2007F07C -:1006C00017FBBDE81040002007F0DDBB7CB50446F9 +:1006C00043FBBDE81040002007F009BC7CB50446A0 :1006D0000D4600790021062814D2DFE800F0030659 :1006E0000A0D111EA06801780CE0A06890F90010B6 :1006F00008E0A068018805E0A068B0F9001001E0FA -:10070000A0680168E9A00AF0A7FA002D04D0D4E996 -:100710000312E7A00AF0A0FA7CBDA0686946006851 -:10072000FFF79CFD0146E4A00AF096FA002DF3D0F5 -:10073000E0680AF0A5F86946FFF790FD0146DFA0E2 -:100740000AF08AFA20690AF09BF86946FFF786FDED -:100750000146DAA00AF080FA7CBD2DE9FF47D8A057 -:100760000AF07AFAD0A0FFF7E4FDE14DAE496879CE -:1007700001EB800050F8041CDEA00AF06DFA286935 +:10070000A0680168E9A00AF039FC002D04D0D4E902 +:100710000312E7A00AF032FC7CBDA06869460068BD +:10072000FFF79CFD0146E4A00AF028FC002DF3D061 +:10073000E0680AF0D1F86946FFF790FD0146DFA0B6 +:100740000AF01CFC20690AF0C7F86946FFF786FD2D +:100750000146DAA00AF012FC7CBD2DE9FF47D8A0C3 +:100760000AF00CFCD0A0FFF7E4FDE14DAE4968793A +:1007700001EB800050F8041CDEA00AF0FFFB2869A2 :1007800010F0FF4F4CD0DFF878A3002405EB0410E5 :10079000066916F0FF4F3FD0D0E90598C769611C84 -:1007A000D8A00AF059FA564502D3D8A00AF054FA54 -:1007B00069463046FFF752FD0146BFA00AF04CFAE9 -:1007C0005646B14502D3D1A00AF046FA69464846DA -:1007D000FFF744FD0146B8A00AF03EFAB04502D347 -:1007E000CAA00AF039FA69464046FFF737FD0146CC -:1007F000B1A00AF031FAB74202D3C4A00AF02CFA31 +:1007A000D8A00AF0EBFB564502D3D8A00AF0E6FB2E +:1007B00069463046FFF752FD0146BFA00AF0DEFB56 +:1007C0005646B14502D3D1A00AF0D8FB6946484647 +:1007D000FFF744FD0146B8A00AF0D0FBB04502D3B4 +:1007E000CAA00AF0CBFB69464046FFF737FD014639 +:1007F000B1A00AF0C3FBB74202D3C4A00AF0BEFB0B :1008000069463846FFF72AFD0146AFF200200AF09C -:1008100023FA641C0C2CB9DB611CBDA00AF01CFA85 +:10081000B5FB641C0C2CB9DB611CBDA00AF0AEFB5F :1008200001F054F8804E002407464C3656F8241048 -:1008300021B1BCA00AF010FA641CF7E700244FF0C5 +:1008300021B1BCA00AF0A2FB641CF7E700244FF032 :10084000010800BF56F8241041B108FA04F03842FC -:1008500002D0B8A00AF000FA641CF3E7B94A0020FD +:1008500002D0B8A00AF092FB641CF3E7B94A00206A :1008600069462C18135C94F80A41401C08280B5563 -:10087000F7DB00220A54B4A00AF0EEF9B54D0024CB +:10087000F7DB00220A54B4A00AF080FBB54D002437 :1008800004EB840005EB800655F82010B2A00AF0B6 -:10089000E3F900213046FFF719FF6EA000F040FD9C +:1008900075FB00213046FFF719FF6EA000F040FD08 :1008A000641C612CECD3BDE8FF8710B5ADA000F04F :1008B00037FD0121002000F022FEADA000F030FD48 -:1008C0000A2007F015FABDE81040002007F0DBBA57 +:1008C0000A2007F041FABDE81040002007F007BBFE :1008D00010B50446AAA000F023FDAF480021017026 :1008E000AE480160AE4801702046BDE81040DCE72C -:1008F0002DE9F047064609F0BCFE054600F0E6FF8C +:1008F0002DE9F047064609F0E8FE054600F0E6FF60 :10090000DFF8248107464FF0010908F14C0855B182 -:100910002A46A4A1304609F0B3FEC8B130780027BA +:100910002A46A4A1304609F0DFFEC8B1307800278E :100920002D2824D026E0A1A000F0FAFC00244D469A :100930004FEA080656F8241041B105FA04F038428F -:1009400002D09FA00AF088F9641CF3E741A01EE0E2 +:1009400002D09FA00AF01AFB641CF3E741A01EE04E :100950009CA000F0E5FC00244FEA080555F824109F -:100960000029F3D096A00AF077F9641CF6E7012776 +:100960000029F3D096A00AF009FB641CF6E70127E2 :10097000761C6D1E5FF0000458F8241031B12A4631 -:10098000304609F07DFE30B1641CF5E793A0BDE868 +:10098000304609F0A9FE30B1641CF5E793A0BDE83C :10099000F04700F0C5BC09FA04F01FB100F091FF68 :1009A00095A002E000F00CFE96A000F0B9FC58F80B -:1009B0002410BDE8F04761A00AF04EB970B50024DC +:1009B0002410BDE8F04761A00AF0E0BA70B5002449 :1009C00093A000F0ADFC634DB5F1A80504EB440025 -:1009D00005EB80014A6855F8201093A00AF03CF915 -:1009E000641C0E2CF2D370BD3EB5054609F041FEE5 -:1009F000082815D10024285D09F0BAFD2855641C8B -:100A0000082CF8D300244F48295D09F028FE28B1AE -:100A10002819295D401C09F022FE00B108E10BE114 -:100A200011E100004F4B0900B0B80008496E766133 +:1009D00005EB80014A6855F8201093A00AF0CEFA82 +:1009E000641C0E2CF2D370BD3EB5054609F06DFEB9 +:1009F000082815D10024285D09F0E6FD2855641C5F +:100A0000082CF8D300244F48295D09F054FE28B182 +:100A10002819295D401C09F04EFE00B108E10BE1E8 +:100A200011E100004F4B0900ECBE0008496E7661F1 :100A30006C6964206D6978657220747970652E2EFA :100A40002E0D0A004C6F61646564202573206D696A :100A5000782E2E2E0D0A00004D6F746F72206E7569 @@ -174,18 +174,18 @@ :100AC00043757272656E7420436F6E6669673A2073 :100AD000436F70792065766572797468696E6720F6 :100AE00062656C6F7720686572652E2E2E0D0A0088 -:100AF000640400206D697865722025730D0A00007A +:100AF0006C0400206D697865722025730D0A000072 :100B000000008080636D697820256400200000006B :100B1000636D697820256420302030203020300D2E :100B20000A00000066656174757265202D25730DDD :100B30000A000000666561747572652025730D0AF0 -:100B400000000000B4C100086D61702025730D0A1B -:100B50000000000020BA0008736574202573203D52 +:100B400000000000F0C700086D61702025730D0AD9 +:100B5000000000005CC00008736574202573203D10 :100B600020000000536176696E672E2E2E00000073 :100B70000D0A5265626F6F74696E672E2E2E00002B :100B80000D0A4C656176696E6720434C49206D6F94 -:100B900064652E2E2E0D0A00340400200000002073 -:100BA000AD0100206C69737400000000456E616245 +:100B900064652E2E2E0D0A003C040020000000206B +:100BA000B50100206C69737400000000456E61623D :100BB0006C65642066656174757265733A20000027 :100BC00025732000417661696C61626C6520666501 :100BD0006174757265733A2000000000496E766199 @@ -197,57 +197,57 @@ :100C3000F7A000F075FB3EBD641C082CFFF4E3AE8A :100C4000284600F0A7FBFAA000F06AFBFE4BFF4A23 :100C50000020694615181C5C95F80A51401C0828AC -:100C60004C55F7D300220A54AFF2301009F0F4FFCC -:100C70003EBD2DE9F041804609F0FBFCF34FF44DF9 -:100C8000060011D00246AFF2E401404609F0F8FC3C +:100C60004C55F7D300220A54AFF230100AF086F93F +:100C70003EBD2DE9F041804609F027FDF34FF44DCC +:100C8000060011D00246AFF2E401404609F024FD0F :100C900088B1002455F82410F1B13246404609F0DD -:100CA000EFFCF8B1641CF5E7787905EB800050F8AB +:100CA0001BFDF8B1641CF5E7787905EB800050F87E :100CB000041CE8A01BE0ECA000F032FB5FF0000495 -:100CC00055F8241029B1AFF2081009F0C5FF641CD3 +:100CC00055F8241029B1AFF208100AF057F9641C46 :100CD000F6E7AFF2802001E0AFF2B020BDE8F041CE :100CE00000F01EBB601C787155F82410E3A0BDE82D -:100CF000F04109F0B1BF70B5054609F0BAFCD34C1C -:100D000010F0FF0F0CD0284609F0D3FC02280ED8B3 +:100CF000F0410AF043B970B5054609F0E6FCD34C63 +:100D000010F0FF0F0CD0284609F0FFFC02280ED887 :100D100084F878030021084600F0F1FBC9A0EBE756 -:100D200094F87813BDE87040D9A009F095BF70BD64 -:100D30002DE9F047814609F09CFCDB4D060029D0E7 +:100D200094F87813BDE87040D9A00AF027B970BDD7 +:100D30002DE9F047814609F0C8FCDB4D060029D0BB :100D4000012E03D199F800002A2823D0D7A14846C4 -:100D500009F067FC00286ED0401C044609F0A9FC8D +:100D500009F093FC00286ED0401C044609F0D5FC35 :100D600082462046FFF7F2F98046002606EB86070A -:100D700005EB870455F8270009F07BFC024655F87F -:100D80002710484609F07CFCF8B1761C612EEDD3A3 +:100D700005EB870455F8270009F0A7FC024655F853 +:100D80002710484609F0A8FCF8B1761C612EEDD377 :100D9000C7A04CE0CEA000F0C3FA002404EB84000E -:100DA00005EB800755F82010AFF2502009F054FFF2 +:100DA00005EB800755F82010AFF250200AF0E6F866 :100DB00031463846FFF78AFCAFF2683000F0B0FAEF :100DC000641C612CEAD3BDE8F08706EB860605EBD0 -:100DD0008607F86809F054FD414609F08DFD25D8D5 -:100DE000386909F04DFD414609F090FD1ED839796A +:100DD0008607F86809F080FD414609F0B9FD25D87D +:100DE000386909F079FD414609F0BCFD1ED8397912 :100DF000052907D0504606290ED2DFE801F0050587 :100E000008080B0B4046F6E7A168087004E0A168EB -:100E1000088001E0A168086055F82610B2A009F02A -:100E20001BFF2046BDE8F04700214FE4B1A0BDE81C +:100E1000088001E0A168086055F82610B2A00AF029 +:100E2000ADF82046BDE8F04700214FE4B1A0BDE891 :100E3000F04700F075BA002404EB8406494655F8E3 -:100E4000260009F0EEFB78B155F8261005EB860771 -:100E5000AFF2F82009F000FF00213846FFF736FC1A -:100E6000AFF2104009F0F8FE641C612CE4D3AAE74D -:100E70002DE9F04106F02DFF4FF47A71B0FBF1F14E -:100E8000A6480378A6480278A6A009F0E5FE00F07F +:100E4000260009F01AFC78B155F8261005EB860744 +:100E5000AFF2F8200AF092F800213846FFF736FC8E +:100E6000AFF210400AF08AF8641C612CE4D3AAE7C0 +:100E70002DE9F04106F059FF4FF47A71B0FBF1F122 +:100E8000A6480378A6480278A6A00AF077F800F0F2 :100E90000DFD0646B348B4490068B0FBF1F1B3A0BC -:100EA00009F0DAFE6A4F00240125903757F8241024 -:100EB00051B105FA04F0304203D0AFF2FC2009F042 -:100EC000CBFE641CE4B2F1E7022000F0DDFCA0B12F -:100ED000AE4C5F482178AC3050F82110ACA009F03E -:100EE000BBFE2078022808D1AC48007C08B16F21F5 -:100EF00000E06E21AAA009F0AFFEAFF2A84000F01A -:100F00000FFA06F0FAFB0246A6484FF45F73018819 -:100F1000BDE8F041A4A009F09FBEB0A000F000BA67 +:100EA0000AF06CF86A4F00240125903757F8241097 +:100EB00051B105FA04F0304203D0AFF2FC200AF041 +:100EC0005DF8641CE4B2F1E7022000F0DDFCA0B1A3 +:100ED000AE4C5F482178AC3050F82110ACA00AF03D +:100EE0004DF82078022808D1AC48007C08B16F2169 +:100EF00000E06E21AAA00AF041F8AFF2A84000F08D +:100F00000FFA06F026FC0246A6484FF45F730188EC +:100F1000BDE8F041A4A00AF031B8B0A000F000BADA :100F20002DE9FF5FDFF8E49299F8000038B901215C :100F300089F80010B6A000F0F3F900F0FDF9DFF831 -:100F400008B3DFF858A25446DAF8000008F0A6FA11 -:100F500000285AD0206808F0A4FA092807D03F28B2 +:100F400008B3DFF858A25446DAF8000008F0D2FAE5 +:100F500000285AD0206808F0D0FA092807D03F2886 :100F600005D0DBF800105C4600294FD076E1002464 :100F70004D4F2546A83FDFF83081DBF800600BE0DD -:100F8000DBF8002022B1B148396809F079FB10B9CB +:100F8000DBF8002022B1B148396809F0A5FB10B99F :100F900004B93C463D460C374745F1D394B1AB4FBD :100FA0005946226808682B68125C1B5C9A4209D17A :100FB00092B92E2810D220223A54401C0021CBF89E @@ -259,70 +259,70 @@ :101010004D75737420626520616E79206F7264650E :1010200072206F662041455452313233340D0A002C :1010300043757272656E742061737369676E6D6556 -:101040006E743A2000000000B4C10008640400205F -:10105000B0B8000843757272656E74206D6978656A +:101040006E743A2000000000F0C700086C04002015 +:10105000ECBE000843757272656E74206D69786528 :10106000723A2025730D0A00417661696C61626CE9 :1010700065206D69786572733A2000004D69786566 :10108000722073657420746F2025730D0A000000B0 :1010900043757272656E742070726F66696C653A22 -:1010A0002025640D0A00000020BA00083D00000061 +:1010A0002025640D0A0000005CC000083D0000001F :1010B0004552523A20556E6B6E6F776E2076617294 :1010C0006961626C65206E616D650D0A000000004B :1010D00043757272656E742073657474696E67739C :1010E0003A200D0A000000002573207365742074F7 :1010F0006F2000004552523A2056616C75652061A0 :10110000737369676E6D656E74206F7574206F669A -:101110002072616E67650D0A00000000600100200A -:10112000CA00002053797374656D20557074696D21 +:101110002072616E67650D0A000000006801002002 +:10112000D200002053797374656D20557074696D19 :10113000653A202564207365636F6E64732C2056B6 :101140006F6C746167653A202564202A20302E3147 :101150005620282564532062617474657279290DC4 -:101160000A0000000004002040420F0043505520B8 +:101160000A0000000804002040420F0043505520B0 :1011700025644D487A2C2064657465637465642029 -:1011800073656E736F72733A200000007401002063 -:1011900041434348573A202573000000D4080020FB -:1011A0002E256300CC0000204379636C65205469D0 +:1011800073656E736F72733A200000007C0100205B +:1011900041434348573A202573000000DC080020F3 +:1011A0002E256300D40000204379636C65205469C8 :1011B0006D653A2025642C20493243204572726FB8 :1011C00072733A2025642C20636F6E666967207302 :1011D000697A653A2025640D0A0000004166726F45 :1011E000333220434C492076657273696F6E20322A -:1011F0002E32204F63742032382032303133202F8A -:101200002030393A35333A3438000000AD0100203F +:1011F0002E32204E6F762020312032303133202F96 +:101200002030393A30343A3031000000B501002046 :101210000D0A456E746572696E6720434C49204D16 :101220006F64652C20747970652027657869742750 :1012300020746F2072657475726E2C206F72202777 -:1012400068656C70270D0A0000000020340400203F +:1012400068656C70270D0A00000000203C04002037 :101250000D1B5B4B00000000042813D00C2817D096 :1012600019B10A2818D00D2816D07F2840D030296F :10127000BFF469AE2028FFF466AE7E283FF663AE69 :10128000A9B343E004B03048BDE8F05FFFF720BBEE :101290002EA000F045F827E0AFF6480000F040F837 :1012A000294E206800250C2335542B48CDE9000633 -:1012B0000E222A49029501A809F060F9070007D01B -:1012C000386809F0D6F93044B968401C884702E014 -:1012D00023A000F025F830211B4809F08BF9256088 +:1012B0000E222A49029501A809F08CF9070007D0EF +:1012C000386809F002FA3044B968401C884702E0E7 +:1012D00023A000F025F830211B4809F0B7F925605C :1012E00099F80000002819D000F026F82BE60BE052 :1012F0000029FBD0144A491E0020CBF8001050549E :1013000020A000F00DF81EE62028EFD00E4A505421 :10131000491CCBF8001000F011F814E6BDE8FF9F5F -:1013200070B50446184D03E0641C286806F07AFF87 +:1013200070B50446184D03E0641C286806F0A6FF5B :1013300021780029F8D170BD14A0F1E701461248C8 -:10134000006806F06FBF0000340400201B5B324AC7 -:101350001B5B313B314800001903000878B90008D5 +:10134000006806F09BBF00003C0400201B5B324A93 +:101350001B5B313B3148000019030008B4BF000893 :101360004552523A20556E6B6E6F776E20636F6DEB :101370006D616E642C20747279202768656C70270B -:101380000000000008200800D40800200D0A2320D7 +:101380000000000008200800DC0800200D0A2320CF :10139000000000002DE9F04105460446FD4EFE4FD9 -:1013A00009E0FC4809F05BF920B1611B801B38445F +:1013A00009E0FC4809F087F920B1611B801B384433 :1013B00080F80A11641C21780029F2D1BDE8F0817F :1013C000F64800210278372A12D14288B2F55F7FB1 :1013D0000ED10279BE2A0BD190F87923EF2A07D1DA :1013E00000F55F7210F8013B59409042FAD309B101 :1013F00000207047012070472DE9F05FFFF7E0FF04 -:1014000010B90A2006F01EFD4FF45F72E349E2486E -:1014100009F0D7F8E04C94F87803022802D90020AC +:1014000010B90A2006F04AFD4FF45F72E349E24842 +:1014100009F003F9E04C94F87803022802D900207F :1014200084F87803C0B200EB001101EB401004EB2C -:10143000800101F59671C422D94809F0C2F8D84A52 +:10143000800101F59671C422D94809F0EEF8D84A26 :10144000D84F002092F8201092F81F5040F6C41692 :1014500000FB00F3193B4B4303F6C41343436B43B8 :1014600093FBF6F327F81030401CC0B20628EFD3E8 @@ -334,61 +334,61 @@ :1014C00002F29CFBF2F23A4402FB03F292FBFEF2C0 :1014D00002EB460212B204FB02F292FBFBF2424420 :1014E0002AF8102000F10100C0B20B28D6D399F8D9 -:1014F000000001F065FFBDE8F05F04F06FBB2DE96F +:1014F000000001F08BFFBDE8F05F04F09BBB2DE91D :10150000F047A54D8146372028704FF45F740027BF :101510006C80BE202871EF2085F879033E4685F85F :101520007A7369B195F87803C42200EB001101EBDE -:10153000401005EB800000F59670994909F041F8DC +:10153000401005EB800000F59670994909F06DF8B0 :101540009548974903E000BF10F8012B57408842A7 -:10155000FAD385F87A73914F4FEA040808F0F2FE47 -:10156000342008F05DFF384608F01AFF04280FD138 -:101570000024E019295908F02FFF042805D008F0AD -:10158000E7FE761C032EE9DB02E0241D4445F0D380 -:1015900008F0DEFE032E02D0FFF712FF10B90A207A -:1015A00006F050FCFFF728FFB9F1000F06D0BDE8A8 -:1015B000F047012214210F2001F0FABABDE8F087AC +:10155000FAD385F87A73914F4FEA040808F01EFF1A +:10156000342008F089FF384608F046FF04280FD1E0 +:101570000024E019295908F05BFF042805D008F081 +:1015800013FF761C032EE9DB02E0241D4445F0D353 +:1015900008F00AFF032E02D0FFF712FF10B90A204D +:1015A00006F07CFCFFF728FFB9F1000F06D0BDE87C +:1015B000F047012214210F2001F020BBBDE8F08785 :1015C00075498A6802438A6070472DE9FC5F77A1FC :1015D000D1E90001CDE900014FF45F716E4809F0D7 -:1015E00009F8C4216E4809F005F86B4B3720002537 +:1015E00035F8C4216E4809F031F86B4B37200025DF :1015F00018700320587102209D60FFF7E1FF83F807 :1016000078534FF41670A3F8F000FA20A3F8F20014 :10161000D0332A20D8835D859D85DD859D74DD745A -:101620001D75DD821D835D831C3301265D701E7078 -:10163000202018735F4898606E2098762B20D8760B -:10164000212018775D7783F82650283340F2DC504C -:101650005D75188040F24C405880443B40F26C70FD -:10166000A3F8480083F84A5040F27E40188040F2C8 -:101670003A7058804FF47A70988040F27E50D8804B -:1016800040F2EA50188140F2B45058813220C10033 -:101690009881D981188283F84C5083F84D504FF4CB -:1016A000E13119654FF49641596583F8585040F679 -:1016B000AC513B4C23F8C41C83F84B5025702827B1 -:1016C00067704FF01E0984F80B9017216175A770A1 -:1016D00084F80C90A1755521E1702D226273E57597 -:1016E00020711921A173502323760B216171E573B9 -:1016F00065764FF0140B84F806B04FF0080C84F8B0 -:1017000010C0A2760E22E27184F811B0E3765A215D -:1017100021724FF00A0884F812804FF0640A84F8AE -:101720001CA06772A5722575A577E177412184F821 -:10173000201084F8235084F8245084F8255084F82D -:10174000210084F8225025856585E584042084F8ED -:101750002C0084F82D7084F82E70152084F82F004A -:1017600015482063154860631548A063012084F87C -:101770003C0014A0FFF70EFE84F8665084F8675012 -:1017800084F86870012084F8690084F86A5004F8CD -:10179000AC8F1DE0B4C100086404002000FC010807 -:1017A000E00700209C0A0020A80A00201E1E646496 +:101620001D75DD821D835D831C334FF001095D70E4 +:1016300083F80090202018735E4898606E2098769A +:101640002B20D876212018775D7783F82650283311 +:1016500040F2DC505D75188040F24C405880443BAD +:1016600040F26C70A3F8480083F84A5040F27E4084 +:10167000188040F23A7058804FF47A70988040F2A7 +:101680007E50D88040F2EA50188140F2B450588120 +:101690003220C1009881D981188283F84C5083F898 +:1016A0004D504FF4E13119654FF49641596583F877 +:1016B000585040F6AC513A4C23F8C41C83F84B50B8 +:1016C0002826257066701E27E77217216175A6709F +:1016D0002773A1755521E1702D226273E57526717E +:1016E0001921A1733C2121760B216171E573657687 +:1016F0004FF0140B84F806B008232374A2760E2250 +:10170000E27184F811B05021E1765A2121724FF034 +:101710000A0884F812804FF0640A84F81CA06672EC +:10172000A5722575A577E177412184F8201084F80A +:10173000235084F8245084F8255084F8210084F83C +:10174000225025856585E584042084F82C0084F8E2 +:101750002D6084F82E60152084F82F001648206331 +:10176000164860631648A063012084F83C0015A069 +:10177000FFF710FE84F8665084F8675084F86860BC +:10178000012084F8690084F86A5004F8AC8FC823FB +:1017900063701DE0F0C700086C04002000FC010825 +:1017A000E8070020A40A0020B00A00201E1E64647E :1017B00064646464031414009A99193F52B87E3F1C :1017C0003333733F4145545231323334000000000B -:1017D000C82363704FF49660608040F2D930A080D7 -:1017E0003C480021EE4640F2DC544FF47F754FF444 -:1017F000FA6C00BF00EBC10222F86C5FA2F802C0D5 -:1018000094801EF80180491C82F806800829F1DBCB -:1018100000F8B26F4FF4967146708670838080F83E -:1018200006B080F807900672A0F80AA08181C781EF +:1017D0004FF49660608040F2D930A0803D480021EF +:1017E000EE4640F2DC544FF47F754FF4FA6C00BFC4 +:1017F00000EBC10222F86C5FA2F802C094801EF8D0 +:101800000180491C82F806800829F1DB00F8B29FAC +:101810004FF4967180F8019080F80290838080F8F0 +:1018200006B0C77180F80890A0F80AA08181C6812F :101830000020294D014600BF05EB0012401C11613C :101840000C28F9DB5FF0000404EB041000EB4410FB -:1018500005EB800000F59670C4221E4908F0B1FE29 +:1018500005EB800000F59670C4221E4908F0DDFEFD :10186000641C032CF0DBBDE8FC9F10B50446FFF7B9 :10187000A7FD641E204206D1FFF7A7FE0021BDE8A8 :10188000104008463BE610BD14490968014201D0EA @@ -396,2996 +396,3109 @@ :1018A00070470E490A6882430A6070470B48006817 :1018B000704709498968014201D001207047002022 :1018C000704705498A6882438A6070470248806889 -:1018D00070470000E007002064040020040000209E -:1018E00070B5FE4809F0AEFC0446FD48008808F0DB -:1018F000D0FF0546214608F041FF08F0CFFFF94C24 -:1019000029462080F84808F06FFFF84908F06CFF7E -:10191000A0650820FFF7B8FF002803D0BDE870409D -:1019200002F0D6BC70BD002801DD024600E0424254 +:1018D00070470000E80700206C040020040000208E +:1018E00070B5FE4809F040FE0446FD48008808F047 +:1018F000FCFF0546214608F06DFF08F0FBFFF94CA0 +:1019000029462080F84808F09BFFF84908F098FF26 +:10191000E0650820FFF7B8FF002803D0BDE870405D +:1019200002F002BD70BD002801DD024600E0424227 :101930008A4201DA00207047002802DDA0EB010096 :101940007047FDDA084470472DE9F04F91B0D0E9B7 -:101950000045814686688846086809F073FC049053 -:10196000D8F8000009F0C8FE0590D8F8040009F086 -:1019700069FC0190D8F8040009F0BEFE0746D8F8CB -:10198000080009F05FFC8246D8F8080009F0B4FEB0 -:1019900083465046049908F0F1FE0790504601999D -:1019A00008F0ECFE80465846049908F0E7FE0690E1 -:1019B0005146059808F0E2FE08905946059808F04F -:1019C000DDFE03900198594680F0004008F0D6FEF5 -:1019D00082463946089808F0D1FE069908F076FE4E -:1019E00010903946039808F0C9FE079908F0C3FE25 -:1019F0000E900598019980F0004008F0BFFE059018 -:101A00003946079808F0BAFE039908F0B4FE029030 -:101A10003946069808F0B2FE089908F057FE83464A -:101A20000499019808F0AAFE04903046029908F043 -:101A3000A5FE01902846109908F0A0FE00904146AE -:101A4000204608F09BFE009908F040FE019908F03E -:101A50003DFEC9F800005946304608F08FFE834627 -:101A600028460E9908F08AFE80465146204608F026 -:101A700085FE414608F02AFE594608F027FEC9F8BF -:101A800004003046049908F079FE06462846059978 -:101A900008F074FE05463946204608F06FFE2946D8 -:101AA00008F014FE314608F011FEC9F8080011B024 -:101AB000BDE8F08F70B506468A4886B08030016870 -:101AC00081F000410391406880F000400490884814 -:101AD000B0F9000008F0D4FE864908F04FFE8649B0 -:101AE00008F04CFE7F4C05907434B4F9000008F007 -:101AF000C7FE0090B4F9020008F0C2FE0190B4F9EC -:101B0000040008F0BDFE029003A96846FFF71CFF21 -:101B10007A4D743C95F83C00012804D07048008848 -:101B200008F0B7FE17E0764840780028606B0CD1CB -:101B3000C11700EB9161A0EBA11008F0A1FE029982 -:101B400008F0C4FD08F0AAFE6063C11700EB9160C5 -:101B5000801108F095FE029908F00DFE029008F041 -:101B60009DFE15F82D1FFFF7DEFE08F089FE02909E -:101B7000009808F093FE6978FFF7D5FE08F080FE24 -:101B80000090019808F08AFE6978FFF7CCFE08F013 -:101B900077FE0190E0683044E0602069401C2061DD -:101BA000584C206808F06CFE009908F08FFD08F092 -:101BB00075FE2060606808F063FE019908F086FDFC -:101BC00008F06CFE6060A06808F05AFE029908F008 -:101BD0007DFD08F063FEA06006B070BD2DE9F05FEA -:101BE000404D04468035286809F02CFB8346286860 -:101BF00009F082FD8246686809F024FB8146686826 -:101C000009F07AFD0546D4F808802946404608F0D8 -:101C1000B5FD594608F0B2FD67680646514638469C -:101C200008F0ACFD294608F0A9FD054649462068A4 -:101C300008F0A4FD294608F049FD314608F046FDAC -:101C400004465146404608F099FD05465946384637 -:101C500008F094FD294608F08BFD214609F0C8F9EB -:101C6000294908F08BFD294908F0BEFD1D49C96AC4 -:101C700008F02CFD264908F0B7FD09F025FD00B25B -:101C8000002802DA00F5B47000B2BDE8F09F2DE93B -:101C9000F04F8DB0002606F002F8DFF848B0054698 -:101CA0005C46DBF83800281A099008F0F2FD194963 -:101CB000C96808F063FD04901048A5630BF16E0A33 -:101CC00090F82C7000240AF106054FF07E58054864 -:101CD000683030F9140008F0D3FD1DE0F366DF3EF4 -:101CE0007A010020080000200AE81C4100401C4640 -:101CF000A801002089C3E43A000020C1E0070020C9 -:101D0000680A0020BC0800200000E144DB0F4940C5 -:101D100000002041440C0020049908F02FFD06A982 -:101D200041F8240017B3384608F0B3FD0146404699 -:101D300008F05AFD81460B903AF9140008F0A0FD16 -:101D4000494608F01BFD814641460B9808F013FDFB -:101D5000FE4951F8241008F011FD494608F0B6FC80 -:101D6000FA4941F8240008F099FD01E03AF814001E -:101D700025F8140035F91400641C00FB0066032CE0 -:101D8000A5D3DFF8CCA364204643BAF8000006A927 -:101D9000404396FBF0F4ED481830FFF7D5FD0820DE -:101DA000FFF772FD06A910B1E8480C3800E0E948D9 -:101DB000FFF7CAFDA0B24938DFF89C933C2827D230 -:101DC0000024B9F8F00008F064FD4546414605904E -:101DD00008F07CFC0146284608F006FDDB4E05466F -:101DE0001836DC48143830F9140008F049FD07466D -:101DF00056F82410059808F0C1FC394608F066FC36 -:101E0000294608F0BBFC46F82400641C032CE8D3E8 -:101E10000820FFF739FD50B34546CC4EDFF8348338 -:101E200000240C3EA8F10E08B9F8F20008F031FDCC -:101E30008146294608F04AFC0146284608F0D4FCB1 -:101E40004FEA000538F9140008F01AFD0746484625 -:101E500056F8241008F092FC394608F037FC294661 -:101E600008F08CFC46F82400641C032CEAD35E4680 -:101E7000BBF9000008F004FDB44C1834A16808F068 -:101E80003BFD01D2012100E00021B4484173D4E9B7 -:101E9000010109F0ADF8AF4D083D2860A06801468A -:101EA00008F06CFC07466068014608F067FC39469C -:101EB00008F00CFC09F0E6FC0146206880F00040C8 -:101EC00009F096F8DFF8988268604146286808F0C3 -:101ED00055FC09F0F9FBA5F15007414638806868C8 -:101EE00008F04CFC09F0F0FB78800820FFF7CCFCF0 -:101EF0009C4D10B195480C3800E09648FFF76EFEF7 -:101F000028800998FFF7D6FD974D95F86A000028BC -:101F10001BD0BAF8000008F0BCFC0146A06808F02D -:101F200063FC924908F02AFC08F0B8FCC0F1640098 -:101F30006422002104F086FB95F86A104843C1171B -:101F400000EB517040F3CF0070800DB0B0E52DE98B -:101F5000F04102F0B4F90220FFF796FC20B102F044 -:101F6000B1F8FFF794FE05E07A4900201A3908809D -:101F7000488088804020FFF79CFC7649764B2C39BE -:101F800010B3A1F15602107830B9D3F8F400030C65 -:101F90001370030A537090706E4B0020B3F1260348 -:101FA000145C31F9105033F91060671E06FB0755B9 -:101FB0006D1C95FBF4F421F8104023F81040401CF0 -:101FC0000328EDD3BDE8F081587901280AD0614A91 -:101FD0000020203A32F8103021F81030401C03283D -:101FE000F8D3EFE75B4AB1F90400883AB2F904305C -:101FF00000EB4300032390FBF3F088809080E1E73F -:10200000524900200C310860486088605149883985 -:102010000861C86070472DE9F84F05F040FE4D4C4F -:10202000883C216C461A46F2A8118E4202D200204A -:10203000BDE8F88F4E4920644B4D088858B195F89B -:102040002F20A369521EB3FBF2F2401EE263088008 -:1020500000206064A06495F82F00401E08F010FC7A -:102060000746E06B08F00CFC394608F087FB074692 -:10207000A06908F00EFC394608F0B6FB09F05AFAE0 -:102080003C4908F07BFB09F09DF94FF07E5108F0C8 -:1020900072FB0746606946F6B321084408F0F0FB7E -:1020A000354908F06BFB394608F068FB08F0F6FB91 -:1020B000D5F83080074641464FF07E5008F058FB77 -:1020C0008146384608F0DCFB494608F057FB0746D6 -:1020D000E06908F0D5FB414608F050FB394608F0AE -:1020E000F5FA08F0DBFB8346E061E06808F0D1FB1D -:1020F0008046224908F042FB0746206908F0C0FBF1 -:10210000814612480C30806808F0BAFBA16D08F0D7 -:1021100035FB414608F032FB494608F065FB804636 -:10212000606C3946009008F029FB81464FF0FF3182 -:10213000404608F099FB394608F020FB494608F074 -:10214000C5FAA16C08F0C2FA824619E0B008002076 -:102150007A0100209000002064040020680A00201A -:102160004C3D0F44A8010020E00700200000C842B9 -:10217000A601002041D3423EA1D81943BD37863580 -:10218000D5F838904FF07E50494608F0F1FA0746EE -:10219000584608F075FB394608F0F0FA07464946FC -:1021A000504608F0EBFA394608F090FAA06408F0BF -:1021B00075FB20654146009808F088FA6064FFF7D7 -:1021C0001FFFD4E914104FF49678401AC8F10009A3 -:1021D0004246494604F036FA0A21FFF7A4FB0746B7 -:1021E0002879C8227843C11700EB5160C0115142D1 -:1021F00004F028FA2062A87B4CF250327843C117D1 -:1022000000EB9160616A01EBA0105142606204F042 -:1022100019FAC117606200EBD150216A01EB60200E -:102220002062304608F035FB0646E769E06C381A54 -:1022300008F026FB234908F0A1FA314608F0D4FA49 -:1022400008F02CFB42464946E76404F0FBF90A21FA -:10225000FFF769FB6F6B804639464FF07E5008F000 -:1022600087FA0646404608F00BFB314608F086FA2E -:1022700006463946606C08F081FA314608F026FAC5 -:10228000606408F00BFB4FF47A72514204F0DAF903 -:1022900008F0F6FA606408F001FB0521FFF743FB44 -:1022A000A062297E96224143C81701EB10700011ED -:1022B0006FF0950104F0C6F9216A081A2062012026 -:1022C000B6E600000024744970B5994D04462868AC -:1022D00007F0EDF80028FAD0E1B2286807F0CEF850 -:1022E000204670BD86B005F023FD0020FFF7BDFA43 -:1022F000FFF782F88F4C002594F8090118B10128E6 -:102300001ED009281CD08DF8105084F8095104A85B -:1023100004F0C4FB04F09EF90E20FFF7BDFA00F0B4 -:1023200039F9607901260E280DD008280BD08DF8D8 -:10233000065000BF4FF48070FFF7BBFA50B905E0BC -:102340008DF81000E3E78DF80660F3E70820FFF74B -:10235000B0FA00B101208DF802004FF4004B58464E -:10236000FFF7A7FA8DF803000120FFF7A2FA8DF816 -:1023700001000820FFF79DFADFF8B48180F001002A -:102380008DF800006C4F98F812008DF8040097F853 -:10239000B400C0F380008DF80500B4F8DE00ADF89D -:1023A0000800B4F8E000ADF80A004FF48040FFF7F1 -:1023B00080FA08B1B4F8DA00ADF80C00B7F8B00054 -:1023C000ADF80E0094F80901012823D0092824D083 -:1023D0008DF80750684605F05DFB5849002040F233 -:1023E000DE5200BF21F81020401CC0B21228F9D3E1 -:1023F000544953480827086088F811703846FFF799 -:1024000058FAB0B194F8120158B1012809D0022845 -:102410001CD10AE08DF80760DCE707208DF8070083 -:10242000D8E7484803F002FE10E0464804F0CDFA31 -:102430000CE094F81C0128B194F91D01002801DA80 -:1024400084F81D5194F81D0103F011FC0120FFF7E1 -:1024500030FA30B14FF48060FFF72BFA08B101F089 -:10246000BBFF39494FF0100AC1F800A0A1F10409DF -:10247000B846C9F800700025A9F10407386880F053 -:1024800010003860386880F008003860192005F0C6 -:102490002FFC012005F037FC192005F029FC002055 -:1024A00005F031FC6D1CEDB20A2DE7D3C9F80080B0 -:1024B000C9F800A001F048FCFFF712FA0220FFF76C -:1024C000F8F908B101F00CFDD4F8200102F0B5F8DC -:1024D0005846FFF7EEF928B194F82811D4F82401F2 -:1024E00006F0EAFE4FF40060FFF7E3F908B103F0ED -:1024F0004BFF05F0D4FB154908606079052803D12E -:1025000013494FF4C870088012494FF47A7008805C -:102510001149C8200880114880F80D6000F058FF6C -:10252000FCE70448B0F9D40000F015F9FEE700001C -:10253000D408002064040020E0070020780A00206E -:10254000832F0008FC000020140C0140F80000203C -:102550007601002078010020A6010020680A0020F2 -:102560000146FE4800EBC100B0F97000122804DA01 -:10257000082902DAFA4931F910007047F74A02EBEC -:10258000C00090F97200084202D04FF0FF3070474F -:10259000012070472DE9F041F24EF34F707907EBBF -:1025A000C000407800B10120F04CA0742020FFF75B -:1025B00080F908B10120A0747079ED4CED4D12281E -:1025C00008D017F8301007EBC0002170426842B302 -:1025D000002024E05FF0000006EB00110A6912F011 -:1025E000FF4F1ED0D1E9057C05EB0013C969401CE3 -:1025F000C3E902C1C3E900272178491C21700C28D6 -:10260000EADB0EE002EB001305EB0016D3E9007CD9 -:10261000D3E90283C6E90283C6E9007C401C8842F4 -:10262000F0DB4FF48040FFF744F900281AD02778F8 -:10263000012F17D9002613E005EB06144FF0FF38E1 -:102640004146A06808F010F9A0604146606808F0B3 -:102650000BF960604146E06808F006F9761CE0601E -:10266000BE42E9DBBDE8F081F0B5401C0021BD4A67 -:102670000B4600BF02EB0114491C23610C29F9DB56 -:10268000B94B03EBC0014C68002C11D0002113F8AA -:1026900030000BE004EB011302EB011593E8C010CE -:1026A000DB68491CC5E906C3C5E904678842F1DC5B -:1026B000F0BDAE4810B5807C002839D0A948AC4C9C -:1026C0004079A41C05280ED004DC01281BD0042866 -:1026D00004D112E0082825D00E2829D02020FFF7A9 -:1026E000E8F8002824D02188002005F063FA6188EA -:1026F0000120BDE8104005F05DBA2189002005F0F9 -:1027000059FA6189F4E79A499448891C90F8B30012 -:10271000498908B10020ECE7974840780028F9D1B2 -:102720000021F7E7E188002005F044FA2189DFE77E -:1027300010BD70B58F4E0024183E8D4D07E000BFD0 -:1027400036F81410204605F02AFA641CE4B2287802 -:102750008442F5D370BD864A864B00211278183B1F -:1027600004E000BF23F81100491CC9B29142F9D31B -:10277000DFE72DE9FC5F7E4C804EDFF80492207885 -:10278000032814D9B9F904004142002801DD0246AA -:1027900000E00A4602F1640200DC08466FF06301C3 -:1027A000A1EB0001B6F9040003F04CFFB0807048C3 -:1027B000DFF8C0A1DFF8A4810778AAF1180A012F79 -:1027C00038D9002434E000BF98F9B200B6F90410FB -:1027D0004042484308F054F8664901EB0415E968A3 -:1027E00007F0CCFF0190B6F9000008F049F86968DD -:1027F00007F0C4FF0090B6F9020008F041F8A9689C -:1028000007F0BCFF8346B9F9060008F039F82968DB -:1028100007F0B4FF594607F059FF009907F056FF3B -:10282000019907F053FF08F039F82AF81400641CE6 -:10283000BC42C9D34B4D4E4CDFF848B16879A41C5B -:10284000052842D004DC012831D004283CD102E024 -:102850000828FBD156E00420FFF782FE0346022140 -:102860000420FFF78BFEB6F9041000FB01F70121ED -:102870000420FFF783FEB6F9021000FB0170184434 -:1028800020810520FFF76CFE034602210520FFF79B -:1028900075FEB6F9041000FB01F701210520FFF7D2 -:1028A0006DFEB6F9021000FB017018440BE0052024 -:1028B000FFF756FE034601210520FFF75FFEB6F93C -:1028C000041000FB0130608199E098F97200BBF9B7 -:1028D00002103226484390FBF6F708F172025B467D -:1028E0000020FFF73DFE3844208092F90800B3F93C -:1028F0000010484390FBF6F20120FFF731FE104430 -:1029000060807CE01C4F7878F0B3B5F8D220B5F841 -:10291000D010B9F9060003F095FEE081AAF8000096 -:10292000B87A4FF0010100284FF003003BD0FFF7C9 -:1029300025FEB9F902104B4600FB01F602210320E7 -:10294000FFF71CFEB3F9001000FB0160E0800121DD -:102950000420FFF713FEB3F9021016E0E007002091 -:10296000780A002064040020B0C50008D4080020C4 -:10297000AC00002000090020680A00202E01002081 -:102980003C010020380000200AE000FB01F6022193 -:102990000420FFF7F3FDB3F9001000FB016021E014 -:1029A000B5F8D400B9E7FFF7E9FDB6F9021000FB6E -:1029B00001F302210320FFF7E1FDB6F9001000FB4F -:1029C0000130E08001210420FFF7D8FDB6F90210A4 -:1029D00000FB01F302210420FFF7D0FDB6F900103F -:1029E00000FB013020810320FFF7BAFDE188084495 -:1029F000E0800420FFF7B4FD2189084420812020D5 -:102A0000FEF757FFC0B30020FFF7AAFD208001208A -:102A1000FFF7A6FD62496080097A69B398F8B4208F -:102A20004146920715D591F97220BBF90230564202 -:102A30005E43322398F97A10BBF9002096FBF3F637 -:102A4000514391FBF3F1721A238831449A1A228080 -:102A500010E098F97230BBF90210278803FB01F6E9 -:102A6000322196FBF1F63E442680BBF90020534309 -:102A700093FBF1F1084460800026474607EBC6004F -:102A80006C30B0F90220B0F9001034F9160003F0F0 -:102A9000D9FD24F81600761C082EEFD397F8B40061 -:102AA000DFF80091400711D500262020FEF701FF36 -:102AB00000B1022600244F4607EB44000189A0190B -:102AC000C0B205F077F8641C042CF5D3364956469D -:102AD000BAF9007001200B7806E000BF36F910202B -:102AE000BA4200DD1746401C9842F7D300244FF449 -:102AF000804A88464DE000BFB5F8D200B84205DAFA -:102B000036F81410381A081A26F814005046FEF742 -:102B1000D0FE98B1B9F9060040F2DC51884204DDDC -:102B2000B5F8D220B5F8D81003E0B5F8D620B5F83E -:102B3000D41036F9140003F085FD15E0B5F8D22065 -:102B4000B5F8D01036F9140003F07CFD26F8140017 -:102B5000B9F90600B5F81611884207DA1020FEF719 -:102B6000A8FE38B1B5F8D40026F814000F48407814 -:102B700018B10DE0B5F8D000F6E75046FEF799FE23 -:102B800010B1B5F8DA0001E0B5F8D40026F8140069 -:102B9000641C98F800008442AED3BDE8FC9F00009E -:102BA000BE0A0020780A0020AC000020680A00203D -:102BB0002DE9F0471746894606460025DFF83C8494 -:102BC0001AE0002411E000BFD8F8001081F00801DD -:102BD000C8F80010012005F096F8484605F088F87E -:102BE000002005F090F8641CE4B2B442ECD33C2021 -:102BF00005F07EF86D1CEDB2BD42E2D3BDE8F08772 -:102C00002DE9FC5FFE4C002540F2DC51B4F90600D2 -:102C1000FC4E4FF4FA73884201DA64210CE0F94962 -:102C2000B0F5FA6F91F8251004DAA0F2DC525143A6 -:102C300091FBF3F1C1F164018946F34996F866E02E -:102C400096F867B0B1F814410022B246EC49EE4B59 -:102C500040F2E63C31F91260311B01F2F31767458F -:102C600003D8002903DCA11B01E04FF4FA71022A0A -:102C700034D0BEF1000F05D08E4502DAA1EB0E0173 -:102C800000E00021642391FBF3F3DD4F6FF018089F -:102C9000243707EB430C37F91370BCF902C003FB70 -:102CA00008F3ACEB070C01EB83030CFB03FC642380 -:102CB0009CFBF3F33B44D54F27F812309AF82330AE -:102CC0004B434FF4FA7193FBF1F1C1F1640189B206 -:102CD00001FB09F1642391FBF3F11CE0BBF1000F50 -:102CE00005D08B4502DAA1EB0B0100E0002193F93E -:102CF000EC30DFF818C35B424B43ACF804309AF871 -:102D00002430002900DC49424B434FF4FA7193FB15 -:102D1000F1F1C1F164010AEB0207642397F801C0E5 -:102D2000DFF8E8820CFB01FC9CFBF3FCA8F15408E3 -:102D300008F802C097F80BC008F103080CFB01FC6F -:102D40009CFBF3FC08F802C07F7D4F4397FBF3F137 -:102D500008F10303A642995405DAAC4931F8123060 -:102D60005B4221F81230521C032AFFF66FAFDFF8E6 -:102D700098A24FF4FA625446BAF8161103F062FCB6 -:102D8000B4F816114FF47A72401A5043C1F5FA6143 -:102D9000B0FBF1F1642291FBF2F0994B6FF0180651 -:102DA000303303EB400433F910307043B4F9024080 -:102DB00001EB8000E41A444394FBF2F0DFF84C820C -:102DC0008F4E1844103EA8F80600707AA8F17C04D3 -:102DD000E8B38F48B4F91E10B0F90000401A07F0AC -:102DE0004FFD8C4907F0CAFC8B4907F0FDFC0746F4 -:102DF00008F028FA0190384608F07EFC009047461B -:102E0000B8F9000007F03CFD8346009907F0B6FCD6 -:102E10008046B7F9020007F033FD8146019907F0BB -:102E2000ADFC414607F052FC07F038FD80464846AD -:102E3000009907F0A3FC81465846019907F09EFCD3 -:102E4000494607F095FC07F029FD388000E001E0D5 -:102E5000A7F802800220FEF72CFD002750B3E0788F -:102E6000401CC0B20621B0FBF1F2E07001FB120081 -:102E7000B8B9002003F084FE2179614A01F007030C -:102E8000AC3A491C22F813002171002032F81010CE -:102E9000401C29448DB20828F8DBE80801F008F846 -:102EA000A072A07AE18C884203D89AF80811814276 -:102EB00001D9A77001E00420A070A07803F059F9AF -:102EC00056484E4D008818B10220FEF7DDFC10B9BF -:102ED0005348008820B1286880F00800286011E07D -:102EE000B178082011B14549091D0860717811B108 -:102EF0004249083108604FF40060FEF7DAFC08B17F -:102F000003F057FA8020FEF7D4FC48B1E16C606B07 -:102F1000411A05D44CF250310844E06405F00AFA35 -:102F2000A16C606B411A03D4717BF9B10120B070C0 -:102F300002F00BF82020FEF7A7FC68B1216D606B52 -:102F4000411A09D4E17A052906D336490844206597 -:102F5000286880F0100028603348816800290ED06E -:102F600002B02A48BDE8F05F5C380847B7702968AE -:102F700081F0080129602D490844A064D8E7BDE824 -:102F8000FC9F10B5204C204490F80A0104F01CFE70 -:102F9000A0F2EE2140F2DD52914201D3B4F81401C7 -:102FA00010BD2DE9F047194EDFF854807C3EA8F1A2 -:102FB0009C087079124F401C00247071A14608F1E2 -:102FC0004005F16B20468847727908EBC40102F096 -:102FD000030221F8120025F81490002035F814306F -:102FE00031F81020401C1A44C0B225F814200428DF -:102FF000F4D335F91400801CC11719E00C0C014002 -:10300000780A0020E0070020640400203C01002032 -:10301000A8010020DB0F4940000034437601002066 -:1030200078010020F0490200440C002020A1070094 -:1030300000EB9170801025F8140037F91410C91EA8 -:10304000884202DA811C27F8141037F91410C91CC1 -:10305000884202DD801E27F81400641CE4B2082CAC -:10306000AFD3CBE5FE480288FE48417852B982785A -:1030700042B1002905D101214170FB48FB4900887C -:10308000C88370470029FCD10122FF2102208FE56F -:103090002DE9FC5F0020F54982467C310546074654 -:1030A0000190B1F902004342002801DD044600E02E -:1030B0001C468B46B1F900104A42002901DD0E463C -:1030C00000E01646B44203DD002806DC184604E0A2 -:1030D000002901DD084600E01046DFF89493002443 -:1030E0000090E04EF07808B93079E8B3022C3FDA6E -:1030F000DE484FF4FA72443030F914103BF91400F2 -:1031000001EB4000514203F09DFADA49DFF868A371 -:1031100031F91410411A0AEB4400B0F9280001EB10 -:1031200000089AF80810642001FB08F191FBF0F008 -:103130009AF81C1001EB8102494201EB810103F076 -:1031400081FA0190C94842F21072743050F824108C -:1031500001EB0800514203F075FAC449743141F89B -:1031600024009AF8121000E008E048434FEA203AA1 -:10317000F07818B1307908B9022C48D13BF91450D5 -:10318000B84F05EB85000101BB48A83F00EB0408E0 -:103190004FF47A5298F8010091FBF0F039F91410CD -:1031A000401A57F824100844514203F04BFA47F8EC -:1031B000240039F9140000F52070B0F5A06F02D892 -:1031C00057F8240002E0002047F824007D2190FBFE -:1031D000F1F098F80B10484387113079A8B1022C10 -:1031E00013DA0098009AC0F5FA710198009B4843E1 -:1031F00005FB02004FF4FA7201FB0AF107FB031111 -:1032000090FBF2F091FBF2F608E0F07820B1022C8E -:1032100002DA5646019801E028463E46934A39F9BB -:10322000141028325023125DDFF838824A4392FB93 -:10323000F3F28E4B821A6833A8F13C0833F914007C -:1032400023F81410081A08F10C0158F8243051F82A -:1032500024C041F824309C44844448F82400834826 -:103260002E30005D00FB0CF0C11700EBD16091190E -:10327000A1EB60107D496E3121F81400641C032C11 -:10328000FFF62FAF7BE62DE9F05F764E4FF0000B97 -:10329000DFF8E4A1DFF8D4915C46A83E714DE878F0 -:1032A00008B92879D0B1022C18DA70484FF4FA72B4 -:1032B000443030F91410383030F9140001EB40007C -:1032C000514203F0BFF96B4931F91410411A0AEB6E -:1032D0004400B0F9280001EB000B01E0022C52D0B1 -:1032E000E878E0B39AF8080000FB0BF000116049A1 -:1032F0000AEB040731F91410FA7A451A787856F86F -:10330000241068434FEAE018B9F80C006843C01273 -:1033100000FB02104FF4001246F82400514203F063 -:1033200091F946F8240043134E480C3850F8241005 -:1033300040F82450B9F80C00691A02094FF6FF70E2 -:10334000B0FBF2F0484347498011243901F10C02E7 -:1033500051F824C052F824506544054400E01CE0B4 -:1033600042F824C041F82400787D6843011208EB3C -:10337000030008443D496E3121F81400641C032CFD -:103380008CDBBDE8F09F9AF8240038491B307C3173 -:10339000B1F9041048434011A9E7344A9AF82300D0 -:1033A0007C321B3032F9142050432A790011002A54 -:1033B0009DD09AF8121001FB0BF100EB212096E74B -:1033C0002A49012801D02D4800E02D4808647047A3 -:1033D0002DE9F84F0027B946B8460820FEF769FAEC -:1033E000DFF8A0B068B19BF8120120B1012802D02B -:1033F000022806D102E002F03CFE01E003F004FBEB -:103400008046DFF868A0174C4FF00005DAF834105A -:10341000DAF854004FF00106081A02D5B8F1000F8F -:103420007DD044F620621144CAF85410FFF7B9FD6C -:103430004FF48040FEF73DFA28B10A485630007834 -:1034400008B900F078FC9BF81B0168B305494FF4FC -:103450007A72103101EB40000021B0F9060013E050 -:1034600078010020680A0020A8010020C000002088 -:103470006400002038000020E007002091300008A0 -:103480008732000864040020A0F57A7003F0DAF8AF -:1034900007F0F6F9FE4907F0A7F9FE4907F06EF9C3 -:1034A00007F015FAAAF822004FF40070FEF701FAAF -:1034B000B0B3DFF8E483BAF90E2098F8ACC00CEB97 -:1034C0008C0191421DDA6078D8B1BBF91431F3490F -:1034D000002000BF21F81030401C0328FADBB8F8A8 -:1034E000AE30CB8098F8AD00604400EB8000904295 -:1034F00002DA00F020FC2570BAF81010491CAAF876 -:10350000101098F8AC0000EB8001BAF90E0081426F -:1035100004DA607810B900F00EFC257001E068E272 -:1035200004E0BAF80E10491CAAF80E10BBF81631C8 -:10353000BBF81821DFF864830020BF0838F910C0F9 -:103540009C4501DD47F08007944501DA47F04007CC -:10355000401C0428F1DB9AF8071050468F4205D131 -:103560008179FA2903D2491C817100E085718AF8BA -:1035700007704FF480473846FEF79BF958B1BBF807 -:103580001411BBF8DC00B8F906200B1A934202DADA -:103590000844904209DC3846FEF78BF9E8B9B8F9DF -:1035A0000610BBF81601814217DABC48B83805602E -:1035B00045608560BA4805604560B748C08F60B116 -:1035C000B6484630007820B1207810B1FFF74AFDA8 -:1035D00003E0607808B100F0AEFB9AF8060014280A -:1035E00017D16078B0B1AC4FF88F28B99AF80700BE -:1035F0005F2801D100F09FFB9BF81A01002808D03A -:10360000F88F002805D19AF807007D2801D100F035 -:1036100092FB8FE09AF80700572809D00420FEF7A4 -:1036200048F9E8B19AF8071050465A2921D017E016 -:103630009C494FF47A7008804FF48070FEF739F996 -:1036400008B101F062FF0420FEF71EF910B196499F -:103650000A2008800820FEF717F908B9934805806A -:103660009AF807005D2817D05B2817D05E2817D07E -:1036700023E0818A19B18582AAF816601DE0818C49 -:1036800021B10021818419B1022102E00121F9E771 -:1036900003218AF8001010E0012702E0022700E071 -:1036A0000327781E8BF8780300210846FDF727FFD3 -:1036B0003A4628210220FFF77BFA774FF88F18B996 -:1036C0009AF807106F290ED09BF81A1121B118B97A -:1036D0009AF807007E2806D09AF80700972805D0A8 -:1036E000A72808D008E0FFF7BDFC05E070494FF4BB -:1036F000C870088000E0A6739AF80700BB2806D0BF -:10370000B72807D0BE2809D0BD280AD012E0788D8E -:10371000801C01E0788D801E788505E0388D801C46 -:1037200001E0388D801E388501210846FDF7E7FE4F -:103730008AF806500420FEF7BCF820B3BAF824201B -:10374000504632216AB162785AB1B8F90630BBF8F6 -:103750001621934205DD514A463212780AB9418258 -:1037600085844E4A4632527C32B1028B838A1A4398 -:1037700009D1AAF8121006E0818A21B1617811B945 -:103780008582AAF816600020C64640F2A46700BFF2 -:103790000EEB4001B1F9082040F214518A4201DADF -:1037A000012300E0002300EB40018B40A2F2155CF6 -:1037B000BCF5C77F02D84FF0010C01E04FF0000CC0 -:1037C00001F101080CFA08FC43EA0C03BA4201DDDE -:1037D000012200E00022891C8A40134343EA0903C6 -:1037E000401C1FFA83F90428D2DB2C4F00204637F7 -:1037F000294901EB4001C98F11EA090100D00121DB -:103800003954401C1428F3DB787840B9224890F8EA -:10381000AC0000EB8001BAF90E0081420ADA022006 -:10382000FEF732F830B1E07828B91D4805604560F0 -:10383000E67000E0E570B87838B1E570207928B915 -:10384000174805604560267100E025713878B84654 -:1038500000B92670E178102009B9217909B115491C -:1038600001E01449091F08600420FEF70DF870B14B -:1038700098F80300474650B3A07938BB0E48A671AC -:1038800001680E48016006480830C18818E02BE046 -:1038900000007A4400C07F44E0070020780A00203E -:1038A0003401002078010020A6010020A80100209A -:1038B00076010020140C0140580000205C0000201C -:1038C000FF48AAF81A100560FE48056000E0A571DF -:1038D0004FF40050FDF7EDFF30B1387918B1E07BBF -:1038E00010B9E67300E0E5730220FDF7CDFF18B9CB -:1038F0000820FDF7C9FFD0B198F80510404639B14E -:10390000617931B9F04966710A88F0490A8000E0AE -:103910006571817919B1617A11B9667200E06572D9 -:1039200098F8070018B1E8480188AAF81E1020206E -:10393000FDF7AAFFF0B3E07AE8B39AF80B00574618 -:10394000052844D398F80A1059B1E07990BBE67184 -:10395000DF4925723D72081F02F095FA0220787047 -:1039600039E0E57198F80B0030B3D94A143AB2F94E -:103970000000002800DC4042D649B1F8C01088425F -:103980001DDAB2F90200002800DC4042884216DA53 -:10399000207A78B9CE4826720C383D7200F11001B9 -:1039A00002680A60406841F8040FC948001D02F02F -:1039B0006AFA02E00FE00AE001E07E700BE0257297 -:1039C000387A40B98AF8086002F032FA03E0E5710B -:1039D00025728AF8015098F80C0008B1A67200E030 -:1039E000A5729BF80500082801D00E2843D1657206 -:1039F00041E0DAF85C005746042801DD401FF86515 -:103A0000052838D2DFE800F0030B151F2A00082034 -:103A1000FE65FDF739FF10B100F067FC58BBF86D8B -:103A2000401CF8650420FDF72FFF10B100F06DFB7E -:103A300008BBF86D401CF8650420FDF725FF10B1A8 -:103A4000FEF7E9FAB8B9F86D401CF8654FF48070DC -:103A5000FDF72FFF10B102F0BAF90CE0F86D401C31 -:103A6000F8651020FDF710FF08B100F0C0FC4FF41E -:103A70000050FDF71EFF04F012F9CAF83400BBF83D -:103A80000C10574611B1BB6DC31A79D40844D946FE -:103A9000B865FEF75CFAFFF7B3F804F000F9786355 -:103AA000398F411AB981B8630820FDF7EDFE20B3C4 -:103AB00087491439B1F9042002F145008A281DD83C -:103AC0006079D8B18048038880480088181A00B20D -:103AD00010F1B40F02DC00F5B47000B2B42802DBC0 -:103AE000A0F5B47000B2637B3BB17A4B5B7A434381 -:103AF0001E2093FBF0F0101A888003E072480188C2 -:103B0000724801800420FDF7BFFE58B3A07948B386 -:103B1000704A92F8690030B36D48B7F91A1014383A -:103B2000B0F90630A3EB010CBCF1000F01DCA1EBF6 -:103B3000030C92F86820944509DDDFF884C18B42BC -:103B4000CCF800507E7200DD5242991809E07A7A72 -:103B500022B1614A1368614A13607D72594A128822 -:103B60001144C18039E0DFF86881B7F91A00A8F183 -:103B70001408B8F90630191A002902DD0B4601E0D5 -:103B8000D7E0C31A92F8682093420FDDBA8B4FF446 -:103B9000FA6C114409B291FBFCF3504A0CFB13116F -:103BA00015681D441560B9837E7207E0797A29B1E2 -:103BB00049490A6849490A60BD837D7241490988BB -:103BC000084400B2A8F80600B9F8D010B9F8D2201D -:103BD000963102F037FDA8F806003E4D95F86A00D0 -:103BE00050B1E07808B9207930B139483C4A1438EE -:103BF000C18812881144C1802020FDF745FEE8B33A -:103C0000E07908B9207AC8B3207BB8B32E4CB4F958 -:103C1000000006F035FE334E314606F0AFFD07F0EA -:103C20006BFD0090B4F9000006F02AFE314606F064 -:103C3000A5FD07F007FB264C064695F8B900303C79 -:103C4000DFF8A4A0A4F11C0810B3A146B4F9020047 -:103C5000241DB4F90210401A01F008FA15F8B92F22 -:103C6000514202F0EFFC618808446080B9F900001D -:103C7000B4F90010401A01F0F9F900E04FE02A7899 -:103C8000514202F0DFFC2188084400B2208001E0AC -:103C9000B4F9000006F0F4FD8346009906F06EFDCD -:103CA0000546B4F9020006F0EBFD8146314606F008 -:103CB00065FD294606F05CFD5546514616E00000BC -:103CC0002C00002028000020A8010020AA010020CC -:103CD00050010020E0070020580000205C00002078 -:103CE0000A00002035FA8E3C0000204106F07CFDE1 -:103CF00006F0D4FDA8F8000044465846314606F0C8 -:103D00003DFD06464846009906F038FD314606F06E -:103D1000DDFC294606F068FD06F0C0FD6080386CC9 -:103D20008047FEF726FDFEF7C4FCBDE8F84FFEF71E -:103D300000BDBDE8F88F03484178002901D000217B -:103D400041707047680A00202DE9F843FE4CFF4B94 -:103D5000FF490026B4F8EE209846A1F1100004F0C7 -:103D6000EAFB08B101260EE0B4F8EE10F84804F0C2 -:103D7000F1FD40B9B4F8EE10F54803F082FD10B93A -:103D8000032004F05FF8F34D5FF0000794F8ED00B6 -:103D900006283CD2DFE800F0070719283303022089 -:103DA000FDF77FFD33E08DF800704FF44870E8496F -:103DB000ADF802001039684602F085FF08B1012015 -:103DC000287094F8ED00012821D06EB1E049B4F8D4 -:103DD000EE204346A1F1100004F0ADFB0220287054 -:103DE00094F8ED0002281DD0D948103804F0ACFC3E -:103DF00028B10320287094F8ED00032812D0D4488D -:103E0000103805F01AFB10B1042028700AE0287859 -:103E100040B994F8ED0010B184F8ED70B6E70220D7 -:103E2000FDF73FFDCA48103004F097FE38B9C84886 -:103E3000103002F0EFFF10B90420FDF732FD022030 -:103E4000FDF722FD28B1C24994F8E3001039096852 -:103E50008847BF4914F8E20F09688847A07803F043 -:103E6000F3F810B90820FDF71CFDBB486421B0F938 -:103E7000262092FBF1F001FB102406B20820FDF78A -:103E800003FDB64D90B1204606F0FAFCB44906F0A9 -:103E900075FC0446304606F0F3FC214606F016FC9D -:103EA000B04906F06BFC2860BDE8F8832F60FBE7A3 -:103EB00070B50546A44890F8060106F0EAFC0446F1 -:103EC000284606F0E6FCA84906F058FCA74906F08B -:103ED0008BFC214606F052FC06F0F9FC80B270BD66 -:103EE00070B500252C46002002F04AFE05440A2049 -:103EF00003F0FEFE641C202CF5D3C5F34F10FFF732 -:103F0000D7FF914A022192F8073100BF03FB01F469 -:103F1000844202D8491C0629F8D39548017092F8CA -:103F2000080148439349088070BD2DE9F05FDFF830 -:103F30002492914E884FB9F80220834C0025C2B3D9 -:103F40008E4900204FF4C878424501D141F82050F5 -:103F500051F8203036F910C0634441F8203026F87B -:103F6000105004EB4003401CA3F8FA500328EBDB8D -:103F7000012A19D10868C83090FBF8F024F8FA0F2C -:103F80004868C83090FBF8F060808868C83090FBC3 -:103F9000F8F1B9F80600081AA0803D850121FA3C25 -:103FA0007D850846FDF7ABFAB9F80210491EA9F85D -:103FB00002100420FDF77DFC002874D0704BDFF860 -:103FC00094816E491A8808F120080C31A8F1180A6A -:103FD000322A05D0F2B300209B46322A14D015E0D5 -:103FE00034F8FA0FA8F800006088A8F80200A0884A -:103FF000A8F80400B7F828C0AAF800C0B7F82AC08B -:10400000FA3CAAF802C0E6E741F8205051F8203007 -:1040100036F910C0634441F8203026F8105004EB04 -:104020004003401CA3F8FA500328D6DB012A1AD11A -:104030005448554B058001201880544B02201870BD -:10404000B8F8000024F8FA0FB8F802006080B8F859 -:10405000040000E00AE0A080BAF800303B85BAF81E -:104060000200FA3C7885521EABF8002048480288CE -:10407000012A18D105800A68322092FBF0F224F858 -:10408000FA2F4A6892FBF0F26280896891FBF0F1A6 -:10409000B9F80600081AA0803D850121FA3C7D850B -:1040A0000846FDF72CFA308834F8FA1F401A3080A1 -:1040B00070886188401A7080B088A188401AB080EA -:1040C000BDE8F09F224810B5103841682A4888475B -:1040D000BDE8104029E730B51E4C1F4AE06892F851 -:1040E0002F200146401C824200D10020294A13683B -:1040F000224A183242F82130274952F820200D6810 -:104100002B449A1A0A60E06030BD70B52348114C08 -:1041100000682169411A01D5002070BD20610C4D55 -:104120006069103578B128698047686880472888B9 -:104130002169084420616A6919491648904700209E -:104140006061022070BD2DE064040020E4080020BE -:10415000440C002074010020E007002034000020FF -:104160008988883C000020413333534000F07F456C -:1041700060010020E600002076000020140B0020E3 -:10418000D2000020D8000020D4000020C000002071 -:10419000D60000209C00002020000020F400002019 -:1041A0001C000020A8688047E8688047FFF793FF5D -:1041B000012060616888216908442061012070BD88 -:1041C0002DE9F05FA24DA88800286AD0DFF884822C -:1041D0000024A3464FF47A79A8F10C06A888484534 -:1041E00007D104EB840208EB820146F824B0C1F841 -:1041F00010B0994F56F8241037F91400014446F8CE -:10420000241006F03DFB014604EB840208EB82001B -:10421000824600F0EFF827F814B0904F27F814B05A -:10422000A888012837D1DAF81000012808DD401EDF -:1042300006F026FB0146DAF80C0006F0D5FA00E09D -:10424000002007F01FFB8246854890F8F800A8B1CF -:1042500006F01FFB514606F04FFB0FD27D49A5F833 -:104260000490C8F810B0C1F824B0C1F838B0C6F84E -:1042700008B0C6F804B0C6F800B00CE056F8240048 -:10428000012200F5FA7090FBF9F027F814000F21D5 -:104290000A20FEF78DFC641C032C9FDBA888401EBF -:1042A000A8806D496D4A002031F8103032F8104076 -:1042B0001B1B21F81030401C0328F5DB00E7654884 -:1042C00010B54C30416864488847BDE8104077E736 -:1042D00010B564481024046002F005FF6148001F17 -:1042E00004605B490120487010BD2DE9F0415E4833 -:1042F000574C0068A169411A02D50020BDE8F08141 -:104300005A490844A0615A4802F0B5FEDFF864C17A -:104310004F4B00269CF80E005549514A26339D1DEF -:1043200088B1A069E061002002EB4007A7F80061B6 -:1043300031F8107023F8107025F81070401C032815 -:10434000F2D38CF80E60607870B10888B2F8007112 -:10435000C01B08804888B2F80271C01B488088885A -:10436000B2F80471C01B8880E06998B3A769381A55 -:10437000414FB84218D23B480838026882F0080220 -:104380000260002031F9102033F91040A24201DA16 -:1043900023F8102035F91040A24201DD25F8102045 -:1043A000401C0328EED315E00020E66133F910101D -:1043B00035F91040214402EB400401EBD17141F387 -:1043C0004F01401CA4F800110328EFD30121084637 -:1043D000FDF795F8012091E710B5012004F001FAEE -:1043E0001020FDF759FA25490020086010BD234828 -:1043F00004F04BBA2DE9F041044600690E46401C1A -:10440000206101281FD006F03BFA25688046294626 -:10441000304606F0ADF90746414606F0E5F9294673 -:1044200006F054F9054660602946304606F0A0F9CA -:104430000146384606F0A2F9A16806F047F9256062 -:10444000E060A0605AE7666000202660F9E700009F -:1044500074010020F80B002070000020A000002054 -:1044600064040020140C0140F4000020A086010028 -:1044700082000020680A002080C3C901A800002033 -:1044800070B5FB4CFB4EC1B20546A170306804F01C -:10449000F5FFE079A1784840E071C5F30721A170EC -:1044A000306804F0EBFFE079A1784840E071C5F393 -:1044B0000741A170306804F0E1FFE079A17848403D -:1044C000E071290EA170306804F0D8FFE079A1787E -:1044D0004840E07170BD70B5E54CE64EC1B205468E -:1044E000E170306804F0CAFFE079E1784840E0719B -:1044F000C5F30721E170306804F0C0FFE079E1788E -:104500004840E07170BD10B50446DA4821460068A5 -:1045100004F0B4FFD648C1796140C17110BDD44ADE -:10452000D548117A405C491C1172704700B5FFF7FD -:10453000F6FF0346FFF7F3FF03EB002080B200BD58 -:1045400010B5FFF7F3FF0446FFF7F0FF04EB004060 -:1045500010BD70B504460D462420FFF7D4FF4D2052 -:10456000FFF7D1FF0CB1212000E03E20FFF7CBFF89 -:10457000BF4C0020E0712846FFF7C5FF607ABDE818 -:104580007040C0E701460020E3E701460120E0E774 -:10459000B748C079B7E770B504460D460846FFF73F -:1045A000F1FF03E014F8010BFFF7ADFF2800A5F1C0 -:1045B0000105EDB2F6D170BD10B5044603E000BFB1 -:1045C000FFF7A1FF641C20780028F9D110BD2DE968 -:1045D000F05FDFF89CB2DFF8989201274FF0000AF5 -:1045E0000BF10C0B00251AE0A3481438405D00EBDA -:1045F00040010BEB8108D8F8040006F03AF80646B3 -:104600000FB1B2440AE0002406E000BFD8F804006D -:10461000005DFFF778FF641CB442F7DB6D1C99F86E -:1046200000008542E0DB002F05D00AF0FF00FFF715 -:10463000A9FF0027D6E7BDE8F09F70B50246032327 -:1046400000218E4803F0D4FC8A49FF2208608A4882 -:104650001421143805F0C7FF874D0020143D0124B4 -:1046600028700220FDF710F920B1012068700220A7 -:10467000A87003240420FDF707F950B10320285542 -:10468000641C4FF40050FDF714F910B104202855B4 -:10469000641C0220FDF7F8F818B90820FDF7F4F8BB -:1046A00040B105202855641C06202855641C0720AD -:1046B0002855641C2020FDF7FCF810B1082028556F -:1046C000641C4FF48070FDF7F4F828B10A202855D7 -:1046D000641C0B202855641C69484079082801D0C7 -:1046E0000E2802D10C202855641C0D202855641C6E -:1046F0000420FDF7DEF810B111202855641C1320AA -:1047000028555B48641C047070BD2DE9F05F584E5D -:10471000DFF864B14FF00008717A594D594C5A4F87 -:10472000C1464FF0010AABF1140B782978D011DCA7 -:104730003046A1F16401007814293BD2DFE801F092 -:10474000FCFBFAF9F8F7F6F5F4F3F2F1F0EFEEED21 -:10475000ECEBEAE94C48CF29407871D014DCCA2947 -:104760005FD008DCA0296CD0A4296BD0C82927D041 -:10477000C9291FD138E0CB2965D0CC2971D0CD29EA -:1047800070D0CE2916D17BE3D4296CD00ADCD02995 -:104790006AD04FF00008D12967D0D22966D0D3293A -:1047A00008D1DFE0EF2918D0F02960D0FA2979D0BC -:1047B000FE2978D00020FFF7E8FEBDE8F05FE7E6CD -:1047C0000024324DFFF7B2FE25F81400641C082CBB -:1047D000F8D30020FFF7D6FEEFE7FFF7A7FE6085CE -:1047E000FFF7A4FE2085F4E7FFF799FEF872FFF7C4 -:1047F00096FE27490870FFF7A3FE264C2060FFF7BE -:104800009FFE6060FFF792FE23490880FFF78EFE4F -:10481000224908802248017841F002010170D8E75E -:1048200061E10023FFF77BFEE5186870FFF777FE74 -:10483000E872FFF774FE5B1C68750A2BF2D3C8E7B9 -:1048400049E04BE35CE300255F4606E0FFF76EFEC0 -:10485000795D6D1C04EB4101C88730788542F5D342 -:10486000B7E721E005E358E1FDE2C9E26BE02BE3A5 -:10487000AC010020D4080020800C0020003801404A -:1048800064040020E0070020680A0020780A002065 -:10489000CB000020440100206E01002070010020A8 -:1048A0005C010020F1E2F2E2FFF739FE04F81F0F8D -:1048B000FFF735FE6070FFF732FE2071FFF72FFE25 -:1048C0006071FFF72CFEA071FFF729FEA070FFF7C3 -:1048D00026FEE0707DE7FFF729FEFFF727FEE935AA -:1048E00025F8190CFFF72CFEFFF720FEA4F8AE0008 -:1048F000FFF71CFEFFF724FEFFF718FE00EB800019 -:104900004000E084FFF70BFE6877FFF708FEE877CA -:1049100013E0D2E150E2B3E1CCE10CE2DAE1B6E13E -:104920009CE183E174E16AE151E13EE120E111E1C2 -:104930000BE1D5E0A1E028E018E0FFF7F0FDA87753 -:10494000FFF7EDFD45E700288AD1FFF7E8FD85F880 -:104950007803022801D985F8788300210020FCF72C -:10496000CEFD36E7FFF7E2FDF94987E20720FFF7C2 -:1049700009FEE620FFF7C7FD6879FFF7C4FD0020B8 -:10498000FFF7C1FD4FF00040B7E20B20FFF7FAFD43 -:10499000F048008800B2FFF79EFD02F0AEFE00B2C4 -:1049A000FFF799FD0220FCF76FFF04460420FCF797 -:1049B0006BFF44EA40040820FCF766FF44EA8004E9 -:1049C0002020FCF761FF44EAC0041020FCF75CFFE4 -:1049D00044EA0010FFF77FFDF9783A79490041EA8F -:1049E0008201BA79002041EAC2017A79367841EA37 -:1049F00042117A7AD44641EA8211D74AD37941EA00 -:104A0000C311137A41EA0321537A41EA4321FB7926 -:104A100041EA83213B7A41EAC321BB7A41EA03316F -:104A2000537B41EA4331937B41EA8331137C41EA72 -:104A30000341137941EA0311537C41EA4341937CDA -:104A4000D27C41EA834141EAC24479785F460C4313 -:104A5000002208E0BB5C0CFA03F3234202D00CFAFC -:104A600002F10843521CB242F4D3FFF709FD95F856 -:104A7000780300BFFFF747FD9FE61220FFF782FD96 -:104A8000B648B74D4FF000040088B0F5806F0BD9E1 -:104A900035F91400C11700EB5170C010FFF71BFD72 -:104AA000641C032CF4D306E035F91400FFF713FD62 -:104AB000641C032CF8D3AB4D002400BF35F914005F -:104AC000FFF709FD641C032CF8D3A74D002400BF99 -:104AD00035F91400FFF7FFFC641C032CF8D36CE6D7 -:104AE0001021A24833E03820FFF74CFD5FF00005AD -:104AF00004EBC50636F96C0FFFF7EDFCB6F90200C2 -:104B0000FFF7E9FCB6F90400FFF7E5FCB079FFF721 -:104B1000FAFC6D1C082DEBD34FE60020FFF732FDA9 -:104B20005FF00005FFF702FD04EBC50626F86C0FE9 -:104B3000FFF7FCFC7080FFF7F9FCB080FFF7EFFC9B -:104B40006D1CB071082DEDD337E610218848FFF7B2 -:104B500022FD32E61020FFF715FD864D002400BF30 -:104B600035F91400FFF7B7FC641C082CF8D324E6D1 -:104B70001020FFF707FDF87AFFF7C5FC7E480078A4 -:104B8000FFF7C1FC7D4C2068FFF77AFC6068FFF7F7 -:104B900077FC7B48008800B2FFF79DFC79480088CD -:104BA00000B2FFF798FC78483DE00520FFF7EAFCEB -:104BB0007648008800B2FFF78EFC7548B0F9000017 -:104BC000FFF789FC7348007800F0010052E70820E5 -:104BD000FFF7D8FC704D002435F91400FFF77BFC7B -:104BE000641C022CF8D36D48B0F90000FFF773FC89 -:104BF0006B48B0F9000000BFFFF76DFCDDE5062053 -:104C0000FFF7C0FC67480068FFF73AFC66480AE017 -:104C10000520FFF7B7FC65480078FFF774FC00201B -:104C2000FFF759FC6248008800B2E5E70720FFF76C -:104C3000A9FC14F81F0FFFF766FC6078FFF763FC10 -:104C40002079FFF760FC6079FFF75DFCA079FFF742 -:104C50005AFCA078FFF757FCE0780BE71E20FFF71F -:104C600091FC002566197078FFF74DFCF07AFFF78C -:104C70004AFC707DFFF747FC6D1C0A2DF2D39CE5C2 -:104C80002F20FFF77FFC4B48FFF796FC95E5400689 -:104C9000000EFFF777FC00255F4607E0785D04EB28 -:104CA0004000B0F93E00FFF716FC6D1C30788542DD -:104CB000F4D382E5FFF78BFC7FE5FFF763FC00246C -:104CC0005D4603E0285DFFF71EFC641C30788442DB -:104CD000F8D372E53220FFF755FC0020FFF7FBFB0D -:104CE00035F9D00FFFF7F7FBB5F90200FFF7F3FB3B -:104CF000B5F90400FFF7EFFBB4F9AE00FFF7EBFBEB -:104D00000020FFF7E8FB0020FFF7BAFBB4F926000C -:104D10000A2190FBF1F000B2FFF7DDFB95F83600B9 -:104D2000FFF7F1FB95F83800FFF7EDFB95F837003A -:104D3000FFF7E9FB62E00820FFF724FC0024601C79 -:104D4000C0B2FFF7E0FB641C082CF8D335E5000087 -:104D5000AA010020CC000020BE0A00207A01002019 -:104D60007C0000206400002082000020AE000020B3 -:104D7000E8080020780A0020CB0000204401002031 -:104D80006E010020700100205E0100206A010020F9 -:104D90006C0100205C01002038000020A8010020E8 -:104DA000DE0000205800002030000020CA00002053 -:104DB000E200002048C60008FFF7B1FB04461220BD -:104DC000FFF7E0FB14B1102C02D004E0954800E09E -:104DD0009548D0E900892046FFF795FB4046FFF74C -:104DE0004FFB4846FFF74CFB90480068FFF748FB35 -:104DF0000020FFF770FB0020FFF76DFB002039E675 -:104E0000FFF78DFB8446FFF79BFB0546FFF798FBFA -:104E10000646FFF795FB0446FFF788FBFFF786FB86 -:104E2000FFF77DFBBCF1000F11D0BCF1100F7FF438 -:104E3000DAAC7D49C1E900560CB17C4804607C4A7B -:104E40000220091D1070784801F01DF8C1E4754872 -:104E5000002CC0E9005687F8078087F80CA0F5D031 -:104E600072480460B5E40028F0D10120FCF7FDFC95 -:104E7000AFE40028EAD16F494FF4C8700880A8E475 -:104E80000028E3D187F80EA0A3E4012166E50820FD -:104E9000FFF778FB68486A4A6A4D016867481268FC -:104EA000B1FBF0F1B2FBF0F000EB4002C2EBC0103E -:104EB00001EBC000E880002435F91400FFF70BFB7C -:104EC000641C042CF8D378E40420FFF75BFBB4F9EE -:104ED0002A00FFF700FBB4F928008DE60C20FFF74D -:104EE00051FB59480068FFF7CBFA5748001D00688E -:104EF000FFF7C6FA544808300068FFF7C1FA5CE4CF -:104F0000524D29780AEB8100C0B2FFF73BFB2878AD -:104F1000FFF7F9FA00244E4E4E4FDFF83C81DFF8E0 -:104F20003C910EE0305DFFF7EEFA385DFFF7EBFAEB -:104F300018F80400FFF7E7FA19F80400FFF7E3FA9E -:104F4000641C28788442EDD337E470B5444C454E58 -:104F50000025607810B3BDE87040FBF7E1BF306812 -:104F600004F09FFAA17951B101291CD002291FD068 -:104F7000032923D0042929D005293FD12CE0242856 -:104F800003D00021A17149B901E00121FAE72328EA -:104F900002D0522832D102E0FBF7C2FF2EE00120FE -:104FA00002F071FF2AE04D2804D10220A07125E013 -:104FB0003C2801D00020F9E70320F7E740281CD85F -:104FC000607125712572E0710420EFE76072E1796C -:104FD0004140E1710520E9E721796279914207D2E8 -:104FE000E2794240E271204A5054491C217105E0A7 -:104FF000E179814201D1FFF788FBA571306804F0A7 -:105000004DFA0028ABD16078002809D14FF4006038 -:10501000FCF74FFC002803D0BDE8704001F0E3B975 -:1050200070BD00004C010020540100205C000020F5 -:10503000C1000020760100200004002040420F0043 -:105040000404002062010020E8F7FF1F7201002025 -:10505000D20A0020E20A0020F20A0020020B0020FF -:10506000AC010020D4080020800C002044F25061E4 -:10507000884201DDA0EB4100FE49884202DA48F691 -:10508000A041084470472DE9F0470646506899460C -:1050900014460D46301A05F0F3FB296805F0A4FB11 -:1050A0002061A768394605F063FB8046F24890F816 -:1050B000B80005F0EEFBF14905F060FB01464FF04A -:1050C0007E5005F091FB2D68294605F0FFFA014658 -:1050D000284605F089FB414605F050FB394605F0AE -:1050E000F5FA2061C4E901600146D9F8080005F02D -:1050F00045FBBDE8F04705F0D1BB2DE9F0411D4669 -:1051000014460E4605F0BCFB696805F037FB3168B4 -:1051100005F034FB216805F0D9FA2060ED680746F8 -:10512000284605F0BBFB064685F0004005F0B6FBBF -:105130000546384605F0B2FB3246294601F082FAB0 -:1051400005F09EFB2060BDE8F04105F0A7BB70B5FF -:10515000CB4CD4E90D01401AFFF788FF0028D4E9B1 -:105160000D01A0EB010002DDFFF780FF02E0FFF779 -:105170007DFF404241F29411884228DAD4E90D01C2 -:10518000401A05F07DFBBF4905F0F8FA0646E06BD2 -:1051900005F07FFB0546304606F0AEFA294605F0DD -:1051A000EDFA05F07BFB00B240F6B83220825142A6 -:1051B00001F048FA616B084448F6A04160648842F7 -:1051C00000DD401A002800DA0844606470BD606B9E -:1051D000FBE72DE9FE4F0546FFF7B9FFA84842F26D -:1051E0002831406C081A05F04BFBA64905F0C6FAB9 -:1051F000044606F027F80190204606F07DFA00905C -:105200000024284605F03CFBDFF874A2DFF8789212 -:10521000DFF878B20AF1300A029099481A3030F972 -:10522000140005F02DFB05465DF82410029805F0EA -:10523000A5FA294605F09CFA05F030FB00B24FF4C0 -:105240007A7255462AF81400514201F0FBF98E4952 -:1052500000B225F81400603900F03CFE04EB84062F -:10526000894B8749074609EB8602904635F91400B9 -:10527000603B2831FFF741FF834B81490744424699 -:1052800035F91400603B2831FFF7FDFE384400B2C9 -:1052900040F6B8325D462BF81400514201F0D2F9C5 -:1052A00025F81400784859F826102838641C40F86E -:1052B0002610022CB1DBBDE8FE8F2DE9F05F704EA9 -:1052C0000024DFF8C4915036DFF8C0B1A6F1360AE9 -:1052D000A9F128096C4956F82400803900F0FAFD3C -:1052E0003AF81410664F401A3037674900B227F871 -:1052F0001400703900F0EEFD054637F9140056F839 -:10530000241004EB840708445F4B5D4909EB8702D6 -:105310009046703B2831FFF7F0FE28445A4B58491D -:105320002BF814005D46424656F82400703B2831A5 -:10533000FFF7A9FE4FF4FA62514201F083F93AF9FE -:1053400014103131622900D8002035F8141040F6CD -:10535000B832084400B225F81400514201F072F945 -:1053600025F81400484859F82710641C40F8271005 -:10537000022CAFDBBDE8F09F70B5054608681968E0 -:105380001446401A05F07CFA3D49C96A05F0F6F961 -:1053900005F084FA01463A48503041602968226895 -:1053A000891A016070BD2DE9F0410F46DDE90685DF -:1053B000116800681E46081A05F062FA0446306853 -:1053C0003968401A05F05CFA2D49C96A05F0D6F92A -:1053D0000646014605F0D2F907462146084605F083 -:1053E000CDF9394605F072F906F04CFA284905F076 -:1053F000C5F905F06CFAC8F8000084F000403146A9 -:1054000005F0F6FD234905F0B9F9234905F05EF9E9 -:1054100005F044FA2860002803DA48F6A041084461 -:105420002860BDE8F0812DE9F0471C48144CD0E914 -:105430000056617804F1480991B34FF07E50A16A9B -:1054400005F0D2F98246D9F80400301A05F018FAAE -:10545000E16A05F093F9514605F090F905F01EFA5E -:1054600007B2D9F8000004F11A08281A05F008FA62 -:10547000514616E0B0B9FFFFE0070020DB0FC9403E -:10548000B4020020D3023739600D00202001002033 -:105490002C7D8E3FA00CB34500A00C46440100209B -:1054A0001AE005F06BF905F0F9F901B204F12400F6 -:1054B000B0F902203A4402EBD27242F34F02A8F84C -:1054C0000220B0F90030194401EBD17141F34F01D2 -:1054D000A8F800104280018001206070C9E90056E0 -:1054E000BDE8F08710B5044605F0CAF9002C01DCD0 -:1054F00080F00040F74905F077F9F74905F03EF9EB -:1055000005F0A0FEF549C86210BD10B5F44CE07A74 -:10551000002811D0F348007805280DD3F249F34A4A -:105520000868106049685160FFF7DCFFF048EB49FC -:10553000008888820120207310BD2DE9F043E749DF -:10554000EC48E74B8E7A012502790024062E29D0FB -:1055500004DC022E09D0032E04D116E0122E33D023 -:10556000302E3DD00020BDE8F083DF4A466856600B -:105570008668166000694FF47A7290FBF2F0DE4A9A -:105580001080C87AD8724D7351E04079C00701D0BD -:10559000032A03D00020C87210B148E00120FAE7C6 -:1055A000DC7244E0C27AD20702D0827A032A03D0A6 -:1055B0000022CA7212B102E00122FAE7DC72C94A83 -:1055C00090F82F00107032E0CC4B828A1A808069EC -:1055D00042F2107290FBF2F0C94A10808D7326E0FF -:1055E000C84B102A1A7001D910221A700022C64E18 -:1055F000C64FDFF81CC3DFF81C931D7815E000BF11 -:1056000002EB420300EB830393F8088006F8028064 -:1056100093F8098007F8028093F80B800CF8028059 -:1056200093F80C8009F80280521CAA42E8DB487B00 -:105630008A7B104097D04C738C73012093E72DE93F -:10564000F041A64900240A4691F809E092F807C003 -:10565000157A0CEB0003D78ADEB22246BEF1090FA1 -:1056600051D2DFE80EF008050F151C233343490023 -:10567000622803D04A72B52802D044E0022033E009 -:10568000012031E003224A720873C87108723AE0BF -:1056900004224A72CE7172190A72887233E00522AE -:1056A0004A72CE7172190A72C8822CE006234B72BC -:1056B000731907EB0020CE7180B20B72C882B0F56F -:1056C000007F01D9CA824A720A831CE0CE71721926 -:1056D0000A720A8BC82A01D2864B9854521C90B287 -:1056E0000883B8420FD1072048720CE008234B72A0 -:1056F000844508D04A7206E04A72854203D1FFF71A -:105700001CFF00B1012420468BE670B50346002043 -:105710000246054611E02E2C04D1521C00290FD060 -:1057200054181D559C5C00EB80004000A4F130062D -:10573000092E01D830382044521C9C5C002CEAD140 -:1057400070BD2DE9F04100268046354637460446B7 -:1057500004F00AFF016800E0641C2078085C20283F -:10576000FAD0404609E01EB106EB86025206160E3C -:1057700010F8012B303E3244D6B2221A022AF2DC53 -:1057800009E01DB105EB85025206150E10F8012B3C -:10579000303D2A44D5B28442F3D820782E280ED149 -:1057A000641C002007EB8702570022788B5C202BBB -:1057B00002D1303F1744641C401C0428F2DB5648D9 -:1057C0000621454307EBC70000EB071005EB8000FF -:1057D000B0FBF1F051494E4300EBC61021E62DE934 -:1057E000F04700273D4C0546242815D0414E204661 -:1057F000F03EC0782C2D13D02A2D11D021460D2D2E -:10580000497964D00A2D62D00F2802D23554401C49 -:10581000E07000295CD0BAE0A770E7702771B6E0AD -:105820003754A0784FF0010928B1A179012921D07E -:1058300002294ED0A2E0A7713078472807D17078AE -:10584000502804D1B078472802D0522809D095E0DA -:10585000F078472804D13079412801D184F80690A6 -:105860008CE0F0784D2804D13079432801D1022012 -:10587000A07183E0DFF8708002280CD003280FD0DD -:10588000042816D0052819D0062849D0072850D05A -:10589000092855D072E01748F038FFF752FF05E0AD -:1058A000307853286AD1D8F800004042C8F8000088 -:1058B00064E01048F038FFF744FF05E030785728DF -:1058C0005CD1D8F804004042C8F8040056E063E018 -:1058D0005AE03BE08096184B35FA8E3CB40200202B -:1058E000680A0020CB000020440100204C01002069 -:1058F000A8010020B00D00206E01002070010020E2 -:105900005E01002072010020D20A0020E20A00207D -:10591000F20A0020020B002040420F002D3101004E -:105920003078302801D9012000E00020FE49C872FB -:1059300024E00021FD48FFF7E8FEFD4908701DE066 -:105940000021FA48FFF7E1FEFA4916E0072802D0E5 -:1059500008280DD012E00121F448FFF7D6FE41F2ED -:10596000184148434FF47A71B0FBF1F0F24904E07A -:105970000121EE48FFF7C9FEF0490880A078401CDD -:10598000A070E7702A2D04D0207968402071002093 -:10599000A6E584F80590FAE70029F8D0307800F001 -:1059A000C7FA0501707800F0C3FA28442179C0B223 -:1059B00088426771EBD1A0790128E8D190E52DE903 -:1059C000FF5FDF49C0B291F81C1119B1012904D061 -:1059D00002297CD1FFF703FF01E0FFF730FE00282A -:1059E00075D0D24C1034A068E06002F072F9A0606B -:1059F0002020FBF751FFD3484FF0000B017801291D -:105A000010D001210170C848C17A00295FD0C8496F -:105A1000097805295BD38246407830B19AF80C109A -:105A200031B108E080F800B0EDE78AF80CB002E090 -:105A300008B1FFF76AFDC44805218E460278C44CC0 -:105A4000521CB2FBF1F301FB1322C049027000208B -:105A500091F90090BC4954F820306831BA4D41F8B2 -:105A60002030BC49783593FBF1F145F82010BA4D50 -:105A700000EB80074D4303EBC51342F2107593FB17 -:105A8000F5F5AEB2B04D403525F81060A74DC835DC -:105A900005EB8707AC4D57F822C0603555F82080DC -:105AA00047F82230A8EB0C0C634445F8203093FBF8 -:105AB000FEF3A94D6D42694303EBC111A24B703354 -:105AC000B9F1010F43F8201007D1B61E00E080E0C5 -:105AD000B6F5797F01D844F82010401C0228B9DBC4 -:105AE00002F0F7F8984D296A401A04F0D2FE9B495B -:105AF00004F07AFEA86202F0ECF82862A86A4FF07F -:105B00007E51884200DB0846A86203A902A8944B94 -:105B1000CDE900011A1F211D8D48FFF744FC0298B2 -:105B20006426B0FBF6F08F498F4A574608800398E9 -:105B300090FBF6F010809AF80C0018B9A1F800B0AC -:105B4000A2F800B0FFF76FFC387A10B9F879002896 -:105B50003FD07D49343101F1080000F11C07CDE947 -:105B600000013B1D3A46211D7948FFF71CFC231D0F -:105B7000774A391D3846FFF7FFFB744C94F9000053 -:105B8000012828D0022824D1784F0121B7F9BE007E -:105B900000F0ABF9FFF71DFB97F8BA00744A18B193 -:105BA000686C90FBF6F01080B7F8B600E96B88429D -:105BB0000BD2D5E90D01401AFFF758FA002800DC96 -:105BC000404242F21071884203DD01202070A88A11 -:105BD0001080BDE8FF9FFFF770FBFAE72DE9F04763 -:105BE000624C607904F055FEDFF88891494604F074 -:105BF000FBFD4E4D20352860E07B04F04AFE49460F -:105C000004F0F2FD5C4EEE606860A07904F041FEA5 -:105C10005A4F394604F0E8FD10352860207C04F026 -:105C200038FE494604F0E0FD6860A07E04F031FED5 -:105C3000DFF82881414604F0D7FDC5E90206E07986 -:105C400004F027FE394604F0CFFD10352860607C53 -:105C500004F01FFE494604F0C7FD6860E07E04F0D2 -:105C600018FE414604F0C0FDC5E9020638E42DE9FE -:105C7000F0412E4C064610340027032527704FF4C0 -:105C80008070FBF716FE002819D0667002F021F82C -:105C9000C4E901702A4890F81C0100B90125FFF7FA -:105CA0009DFF374906EB46002B4651F82020354929 -:105CB000354802F09DF9354948600120207023E500 -:105CC0002DE9F041194C032710341D4A60782F4DFF -:105CD00000EB400192F81C31294E686813B1012B8A -:105CE0001ED105E056F8211003F0DEFB27700BE50E -:105CF0002378012B4CD056F8211003F0D5FBDFF8A8 -:105D00008080002608F13C08686818F8061003F047 -:105D1000B5FB042001F0ECFF761C8C2EF4D3277029 -:105D200000206060F0E40000680A0020C00C002041 -:105D3000CB0000206E010020700100205E010020D9 -:105D4000640400205C010020B4020020C100002097 -:105D50004401002080969800D3CEFEFF00007A44D4 -:105D6000500100206A0100206C010020E0070020A3 -:105D7000AA0100200000C8420000FA4400002041AF -:105D800078C60008BF59000800440040D40800202D -:105D90000027904607EB470056F82010686803F08C -:105DA00083FB98F91D0100EB400006EB8000416881 -:105DB000686803F066FBC82001F09AFF7F1C052F7E -:105DC000E8DB98F81D01607002202070A8E710B58C -:105DD0005E4C207805282AD2DFE800F02903031C56 -:105DE0000600BDE810406BE760680521401C60605C -:105DF0006078401CC0B2B0FBF1F201FB1200607091 -:105E000001F067FF5249A060002008705149C87234 -:105E100001200BE001F05DFFA168401A40F6C411BB -:105E2000884204D92020FBF73CFD0420207010BDDF -:105E30002DE9F05FDFF814A10024474FDFF81C8143 -:105E4000DFF81C910AF1400A25460AF1280B00BF31 -:105E500027F8145028F8145004EB840629F814503D -:105E60000AEB860000F06DF80BEB860000F069F895 -:105E70003648903000EB860000F063F8641C022C7A -:105E8000E6DBBDE8F09F7CB5364C0268226009680D -:105E900061600068FFF726FBA4F1240101F108000E -:105EA000314ECDE90001231D2246311D3046FFF75A -:105EB0007AFAA4F15805331D686B68643246211DD7 -:105EC0002046FFF759FA686BA8632848B0F8BC0071 -:105ED00068827CBD10B50C4604F0D2FC216804F049 -:105EE0004DFCBDE8104004F0D9BC70B51D4C583CC9 -:105EF000E26B21B1B0EB520F0BD3500809E0904296 -:105F000000D31046194900B2B1F8BC10814200DB41 -:105F10000846B4F9125000B2A84208DD1449A06A3C -:105F200004F02CFC04F0BAFC284400B2608270BD7E -:105F30003038C0B2092801D9C01FC0B200F00F002C -:105F4000704700210160416081607047D00C0020E3 -:105F5000CB000020680A002004010020240100205A -:105F6000200100200C03002044010020E007002055 -:105F70000000C842F0B5404A404C1178E9B192F8AF -:105F800005C01779032104F11C035E1816F8015CA3 -:105F9000FD4005F00F05072D09D213F801E016F8B2 -:105FA000016C06EA0C060EEB062644F82560891CF7 -:105FB000C9B21029E9D300211170314907280ED246 -:105FC000937863B151782E4A104490F80A0149B190 -:105FD00054F820004FF4777101EB500006E0B1F85F -:105FE0001401F0BD34F8200000F5777080B2F0BDE8 -:105FF00070B5214C01260546A67001F050FEA1683F -:10600000421AC4E9020241F288300021824200D9DA -:10601000E1701A4AE0781C3215540F2802D0401C57 -:10602000E07070BD17482670018070BD70B50446E1 -:106030001348114990F81221032007252AB1012A9B -:1060400008D108714D71012003E002220A714871E4 -:106050000020487001234FF4E1320B490B4801F056 -:10606000C7FF01460A48C1600CB10A492160457466 -:1060700070BD01480078704734030020780E00207E -:1060800064040020CE000020F15F000800440040BE -:10609000D4080020755F000870B57C4C06460125C9 -:1060A000207880B901F015FEA1683231884207D30B -:1060B0002570012001F027FE01F00BFEA06070BDED -:1060C00020780028FBD001F004FEA168314488420A -:1060D000F5D30020207001F016FE01F0FAFD6C49A6 -:1060E000A060087808B1401E0870657070BDF8B5F2 -:1060F000664D8DF800008DF801108DF802208DF8A6 -:106100000330A8791DF8001044292DD04C2929D03E -:106110004D2925D04E292AD032240026032806D224 -:1061200074B12046FFF7B8FFA879032808D301F01F -:10613000D0FDA968001B884202D95548AE7106708F -:106140006878012801D0002C09D1A879032801D250 -:10615000401CA8716E702E70002001F0D4FDF8BDB7 -:106160006424DAE7C824D8E74FF4FA64D5E70024BA -:10617000D3E72DE9F047DFF81CA10546434C9AF818 -:106180000D004FF00109002610B184F8029000E0E4 -:10619000A6704FF40070FBF78CFB3F4F18B33F49DC -:1061A0003F484FF0020C91F8AC30B0F9000003EB1F -:1061B000830282420FDA97F80180B8F1000F0AD00B -:1061C00084F8049091F8AD10194401EB81018142EB -:1061D00001DA84F804C0824203DA797809B984F8D4 -:1061E00004C000B926712020FBF74EFB40B19AF89D -:1061F0000A1011B99AF80B0008B1F87AA8B1E67044 -:106200002079022814D0012817D0E078012817D06F -:10621000A078012817D0042D19D0022D1ED0012DF1 -:106220001ED0607901281ED022E084F80390E7E7B1 -:106230004E22442311464C200DE04D234C2208E011 -:106240004D234E2201E04D235322532102E04423EB -:106250004D224D215320BDE8F04748E7442305E097 -:1062600044234E22F5E7787810B14E234D22ECE717 -:106270000748007818B1BDE8F04732200CE72670D7 -:10628000BDE8F047002001F03EBD000044030020BF -:10629000C0000020BE0A0020680A0020E00700209D -:1062A000CE00002010B5D84C5E28A26807D05D282B -:1062B0000CD001461046BDE8104003F0DFB85D2168 -:1062C000104603F0DBF83E21A068F4E75D2110469C -:1062D00003F0D4F83D21A068EDE72DE9F04113204B -:1062E00000F04AF9C94C2068002800DC4042C84D43 -:1062F00090FBF5F000B200F051F91B2000F03CF9E2 -:106300002068002800DC40420A2690FBF6F042F2AA -:10631000107790FBF7F107FB110000B200F03EF997 -:10632000232000F029F92068002801DA532000E03A -:106330004E2000F033F9122000F01EF960680028AA -:1063400000DC404290FBF5F000B200F027F91A2083 -:1063500000F012F96068002800DC404290FBF6F083 -:1063600090FBF7F107FB110000B200F017F92220B3 -:1063700000F002F96068002801DA572000E04520AB -:10638000BDE8F04100F00AB910B54FF40040FBF74A -:1063900090FAA04A9C4920B192F82901012806D020 -:1063A00002E0002082F829010868886010BD9A4840 -:1063B000FBE770B5974890F8291111B9974A5278C0 -:1063C0000AB1012400E00024954D2A78944209D0B6 -:1063D00039B914B14FF4165001E0D0F82001FEF79E -:1063E0002CF92C7070BD2DE9F0478A4890F82901EE -:1063F00018B98A48407800287ED08348806803F026 -:106400004DF8002878D101F064FC854D6968401A88 -:106410007D2871D301F05DFC68606878814F401C75 -:10642000DFF80482DFF804926870002404F124008D -:10643000C0B200F0A1F8388804F02BFA064638F90B -:10644000140004F01DFA314604F0CEF9494604F078 -:1064500095F904F023FA00B200F0A0F8641C032CB4 -:10646000E4DB00F096F868784FF06404800724D1EC -:10647000102000F081F86E4E306890FBF4F000B20E -:1064800000F08CF8212000F077F8306890FBF4F1F0 -:1064900004FB110000B200F081F8142000F06CF849 -:1064A0006448B0F9000000F079F81C2000F064F8AE -:1064B000002000F073F800F06CF86878400735D1E0 -:1064C000022000F059F85C484FF00A08B0F90010BB -:1064D00091FBF8F000B200F061F80220FBF7E9F957 -:1064E000E0B100F065F855486E2100784843152169 -:1064F000B0FBF1F63A2000E03CE000F03DF8B6FBDE -:10650000F4F738B200F04AF83B2000F035F804FB0D -:106510001760401DB0FBF8F000F040F82020FBF7BA -:10652000B3F908B1FFF7D9FE00F033F868782828EE -:1065300020D10020687001F0CCFB4FF47A71B0FBE1 -:10654000F1F43C25B4FBF5F6B6FBF5F005FB10675E -:10655000172000F011F8380200B200F01FF81820E0 -:1065600000F00AF805FB164000F018F8BDE8F04707 -:1065700000F00FB8BDE8F08770B5234C05465E21EA -:10658000A06802F07BFF2946A068BDE8704002F0D9 -:1065900075BF1D485E21806802F070BF10B50446CB -:1065A000C0B2FFF77FFEC4F30720BDE8104079E6D4 -:1065B00070B52248224E40F6340200783178184DEA -:1065C000B0FBF1F050432A22B0FBF2F06A88B2FB34 -:1065D000F1F301FB13214FF6FF7202EA011141EAC8 -:1065E0000024C0F3032004430620FFF7C5FF20B2B8 -:1065F000FFF7D4FF68883178401C80B2B0FBF1F21D -:1066000001FB1200688070BDD40800204401002006 -:10661000A086010064040020D0140020680A002035 -:10662000500300207A0100207C00002000007A4402 -:1066300024000020A8010020E0000020CA00002063 -:1066400060010020884201DA084670479042FCDD74 -:10665000104670472DE9F047BD49BD48E831B0F913 -:10666000E600B1F90050B1F9024010B90DB9002CA3 -:106670007ED0B84A0021117004F002F9B64F3946B5 -:1066800004F07CF8DFF8D492494604F0ADF8804677 -:10669000284604F0F5F8394604F070F8494604F04D -:1066A000A3F80646204604F0EBF8394604F066F8F5 -:1066B000494604F099F80746304604F0C3FD044605 -:1066C000404604F0BFFD214604F058F8A44C206079 -:1066D000384604F0B7FD0546404605F00DF829465A -:1066E00004F04CF80546384605F006F88246304678 -:1066F00005F002F88146404604F0A4FD494604F046 -:106700003DF8514604F03AF8294604F031F860604B -:10671000384604F0F1FF0546404604F0EDFF2946F7 -:1067200004F02CF80546384604F08CFD82463046CD -:1067300004F0E2FF8146404604F084FD494604F03F -:106740001DF8514604F01AF8294603F0BFFFA06077 -:10675000304604F077FD0546404604F0CDFF29465B -:1067600004F00CF8E060384604F06CFD054600E0EB -:1067700057E0404604F066FD294603F0FFFF05465A -:10678000384604F0B9FF8246304604F0B5FF814632 -:10679000404604F0B1FF494603F0F0FF514603F0D4 -:1067A000EDFF294603F092FF2061384604F0A4FF74 -:1067B0000546404604F046FD294603F0DFFF054646 -:1067C000384604F03FFD8246304604F095FF81468E -:1067D000404604F091FF494603F0D0FF514603F0D4 -:1067E000CDFF294603F0C4FF6061304604F084FF0A -:1067F00080F00040A061384604F07EFF0546304638 -:1068000004F020FD294603F0B9FFE061384604F0AA -:1068100019FD0546304604F015FD294603F0AEFF8C -:106820002062BDE8F0872DE9F0470546B0F9008009 -:10683000B0F90260B0F9040004F022F8484C824636 -:10684000A16803F09BFF0746304604F019F8814623 -:10685000616803F093FF0646404604F011F8804655 -:10686000216803F08BFF314603F030FF394603F017 -:106870002DFF04F013F828805046616903F07EFF75 -:1068800007464846216903F079FF06464046E1681D -:1068900003F074FF314603F019FF394603F016FF89 -:1068A00003F0FCFF68805046216A03F067FF07464B -:1068B0004846E16903F062FF06464046A16903F0DD -:1068C0005DFF314603F002FF394603F0FFFE03F09F -:1068D000E5FFA880A5E7092A11D2DFE802F010053C -:1068E00009161C21262A2E0002880A80428803E00D -:1068F00042880A8002880CE04A8080888880154897 -:106900000078002822D108468DE7028852420A808A -:1069100042885242F0E7428852420A800288EBE7FE -:10692000028852420A8042880CE042880A8002882B -:1069300008E002880A80428803E0428852420A80C6 -:10694000028852424A8080884042D7E77047000060 -:106950006404002058030020DB0F4940000034434A -:10696000A40E002044490844444990F80A0151F813 -:1069700020004FF4777101EB500080B2704710B5E2 -:10698000044601F08CF93E4902464868131A00207B -:10699000B3F57A6F00D948704A604A780AB90F2C6B -:1069A0000AD1087032B1354B20331344182A03F84A -:1069B000014C02D0521C4A7010BD304A2032D27DA8 -:1069C0000AB901220A70487010BD10B504462A4861 -:1069D00000212A4BB0F814014200A2F5F76200BF73 -:1069E00043F82120491C0829FADB0123254A2649BE -:1069F000264801F0FDFA01462548C1600CB1254941 -:106A000021600821417410BD1D4B10B5187840B1AC -:106A10001A484FF000022030817DC908C90702D012 -:106A20001A70002010BD1C49401C0A8030F8011C5F -:106A3000C1F30A0411490C600488C4F3CA044C6011 -:106A40000468C4F38A348C60B0F80340C4F34A0489 -:106A5000CC608488C4F30A140C614468C4F3CA345B -:106A60004C61B0F80740C4F38A048C610089400986 -:106A7000C8611A70012010BD64040020C80E0020F7 -:106A80005C030020A08601007F69000800440040EC -:106A9000D408002065690008CE0000202DE9F041EF -:106AA0000646007890B008B1012500E00025DFF827 -:106AB000D880404602F0BCFE3448009000243448A0 -:106AC000CDE90104012725B10220CDE9030480208E -:106AD00002E0CDE90374002005904FF48070069029 -:106AE00080000790202008900002CDE90904694643 -:106AF000404602F00AFF0121404602F030FF8DF8C7 -:106B000030500B948DF831704FF46020CDE90D04B6 -:106B10000DB1022000E001201C4C8DF83C004C3CE3 -:106B20000BA9204602F0F0FD032301220421204698 -:106B300002F03FFE2DB1317803230222204602F0FD -:106B400038FE0121204602F008FE0121204602F015 -:106B5000FAFD204602F00BFE204602F00DFE002852 -:106B6000FAD1204602F00FFE204602F011FE002866 -:106B7000FAD10121204602F012FE10B0BDE8F081EA -:106B8000034931F810007047080002404C240140CE -:106B9000640300202DE9FF47DFF86C81814698F8F7 -:106BA0000000D0B300273E463D463C46641CE4B29C -:106BB00002AB08223221532000F063FD9DF808004B -:106BC0009DF80910202C00EB012000B207449DF82D -:106BD0000A009DF80B1000EB012000B206449DF85E -:106BE0000C009DF80D1000EB012000B205449DF84B -:106BF0000F0000F07F0001D20028D7D197FBF4F0FE -:106C0000ADF8000096FBF4F0ADF8020095FBF4F04F -:106C1000ADF8040088F802401EE0FFE702AB062250 -:106C20003221532000F02DFD9DF808009DF8091039 -:106C300000EB0120ADF800009DF80A009DF80B1054 -:106C400000EB0120ADF802009DF80C009DF80D103E -:106C500000EB0120ADF8040098F801204946684691 -:106C6000FFF739FEBDE8FF8770B5274D04464FF0AA -:106C7000080228784FF02D0100284FF053000ED065 -:106C800000F0F9FC0A223121532000F0F4FC0C2220 -:106C90002C21532000F0EFFC9022382108E000F076 -:106CA000EAFC0A223121532000F0E5FC0A222C21C3 -:106CB000532000F0E0FC154940F20910002C088038 -:106CC00000D06C7070BD38B5054600208DF800000E -:106CD0000F480C460F49006888420AD06B460122D3 -:106CE0000021532000F0CDFC18B19DF80000E528EC -:106CF00001D0002038BD044928780870064820607B -:106D000006486060012038BD680300207A01002039 -:106D100004040020001BB700696C0008956B000894 -:106D200010B54FF48044204602F076FE012805D1CC -:106D3000204602F07FFEB9490120087010BD70B5F1 -:106D40000D46B649B64A064688885389B2F91440BA -:106D5000C01A13895843B2F91230C013DB0204443D -:106D600093FBF4F31844D06100EB8000082202EB9F -:106D700040000411886800F0D0F806B13060002DA2 -:106D800000D02C6070BD38B5A44C207810B9608854 -:106D9000401C60806B460322F621772000F071FCD6 -:106DA0009DF800009DF80110000440EA01209DF8C4 -:106DB000021008439A49B1F92010C1F10801C840F6 -:106DC000A06038BD9648342190F8200001EB801077 -:106DD0009249C2B200200870F421772000F04BBC29 -:106DE00038B58E4C207810B96088401C60806B46A6 -:106DF0000222F621772000F044FCBDF8000040BAE2 -:106E0000A08038BD854900202E220870F42177200B -:106E100000F031BC2DE9F04304468248824985B038 -:106E20000068884203D1002005B0BDE8F083DFF898 -:106E3000EC9199F8010008B10120F5E74FF40055F5 -:106E4000ADF80C5002208DF80F001020774E8DF811 -:106E50000E0003A9304601F039FF6F00ADF80C7049 -:106E600004208DF80E0003A9304601F02FFF356194 -:106E70000E21022003F052FA00208DF808000820AD -:106E80008DF809004FF00108019747468DF80A80F8 -:106E900001A802F08BFD28208DF810000F208DF83E -:106EA00011008DF812008DF8137004A802F0F9FBA0 -:106EB000142000F01DFF6B460122D021772000F046 -:106EC000E0FB574F9DF800000321F87539845528E1 -:106ED00001D07561A7E76B460122D121772000F030 -:106EE000D0FB9DF8000000F00F013976000978769C -:106EF00000F05CF889F8018041F27070208046F65D -:106F0000781060804A4860604A48A0604A48E06063 -:106F10004A4820614A4860618EE770B54049CA69B5 -:106F2000B1F90E40A2F57A6202FB02F31D136C4325 -:106F3000E512B1F90240B1F90460544305EBE424D1 -:106F4000B1F9005004EB850591F82040A540564367 -:106F50007213B1F90C601B135E4302EB2642921CC4 -:106F60009210C98802F50042AD1C5143C90B4CF286 -:106F70005032A0EBA500E2405043B0F1004F03D2E5 -:106F80004000B0FBF1F002E0B0FBF1F04000011274 -:106F9000494340F6DE3251432A4A0914424301EB89 -:106FA000224101F6CF6100EB211070BD00B587B022 -:106FB0006B461622AA21772000F063FBBDF8000083 -:106FC00041BA17480180BDF8021049BA4180BDF8A6 -:106FD000041049BA8180BDF8061049BAC180BDF8D5 -:106FE000081049BA0181BDF80A1049BA4181BDF8BB -:106FF0000C1049BA8181BDF80E1049BAC181BDF8A3 -:10700000101049BA0182BDF8121049BA4182BDF888 -:10701000141049BA818207B000BD00006C03002043 -:10702000040F002004040020001BB70000100140E2 -:10703000056E0008E16D0008C56D0008876D000849 -:107040003F6D000843E3FFFF38B5044600208DF88C -:1070500000006B4601220A211E2000F012FB18B12D -:107060009DF80000482801D0002038BD0CB18D48A3 -:107070000470012038BD7FB5054602AB062203210E -:107080001E2000F0FEFABDF8080040BA00B203F07E -:10709000F7FB844C241D216803F070FB03F0FEFB1A -:1070A000ADF80000BDF80A0040BA00B203F0E8FBFA -:1070B000A16803F063FB03F0F1FBADF80400BDF839 -:1070C0000C0040BA00B203F0DBFB616803F056FB32 -:1070D00003F0E4FBADF80200201F29460278684661 -:1070E000FFF7F9FB7FBD2DE9F0476F4800246F499A -:1070F000006825468EB02E464FF0010888420CD11C -:107100004FF48050ADF8280002208DF82B000420A9 -:107110008DF82A000AA9664808E06649884207D126 -:107120004FF48040ADF828000AA9634801F0CEFD75 -:10713000322000F0DDFD112200211E2000F09BFA1C -:10714000602201211E2000F096FA642000F0D0FD9C -:107150006846FFF790FFDFF858A1DFF8609100273D -:107160000AF10C0A012202211E2000F084FA3220CA -:1071700000F0BEFD6846FFF77EFFBDF90210BDF9C5 -:107180000400BDF900200D4414440644814201DA94 -:107190000B4600E00346934201DD104602E08142C7 -:1071A00000DA0846484502DC4FF0000808E0DAF84B -:1071B000001081F01001CAF800107F1C0A2FD1DBEB -:1071C000122200211E2000F056FA0027012202217F -:1071D0001E2000F050FA322000F08AFD6846FFF7CA -:1071E0004AFFBDF90020BDF90210BDF90400A41A40 -:1071F0006D1A361A814201DA0B4600E003469342CB -:1072000001DD104602E0814200DA0846484502DC12 -:107210004FF0000808E0DAF8001081F01001CAF819 -:1072200000107F1C0A2FD1DB204603F029FB244FDE -:107230000146384603F0D8FA1A4C20F00040241DCD -:107240002060284603F01CFB0146384603F0CCFAC8 -:1072500020F000406060304603F012FB0146194800 -:1072600003F0C2FA20F00040A060702200211E202E -:1072700000F001FA202201211E2000F0FCF900227A -:1072800002211E2000F0F7F9642000F031FDB8F172 -:10729000000F04D14FF07E5020606060A0600EB0FF -:1072A000BDE8F087780300200404002000127A0073 -:1072B000000C0140001BB7000010014000F0FFFF70 -:1072C00000406F4601C05E4630B587B005464FF4BA -:1072D0004060ADF8140002208DF817001C208DF8D6 -:1072E000160005A9FB4801F0F1FCFB4CE56000F03D -:1072F00007FAE06802F0A4FB684602F00CFC0022EA -:107300004FF44071E06802F03CFC0025ADF80450F9 -:107310004BF6FF70ADF806004FF48040ADF80C005E -:10732000EE4800900121E06802F003FC6946E06845 -:1073300002F099FB4FF4A06002F0AEF922208DF824 -:1073400010008DF811508DF8125001208DF81300A7 -:1073500004A802F0A6F921208DF810008DF8115034 -:1073600004A802F09EF907B030BD38B5DA4CE068E9 -:10737000818A009111F4706F01D001212170009970 -:1073800011F4E06F25D0018B00224FF4806102F0F0 -:10739000F8FB009880051CD4E0680188890518D4A2 -:1073A0000188C9050CD50188C905FCD4012102F06A -:1073B000D4FBE06801888905FCD4FFF785FF08E06D -:1073C000012102F0CAFB00224FF44071E06802F094 -:1073D000D8FBE068818A21F47061818200202071ED -:1073E00038BDC2E72DE9F041BB4CE068818A4FF01F -:1073F0000105C9B2CA074FF0000627D0018821F461 -:1074000000610180012102F0B2FBE670607A20B1D8 -:10741000607860B9A079FF2809D061790022E0681E -:1074200002F0BCFBA079FF2848D0FF20C9E06570BE -:10743000E079022804D1E068018841F4006101800C -:1074400061790122E06802F0A9FB37E08A074FF476 -:10745000806745D5BFF3508FE079012810D1607A5D -:1074600070B1607860B10021E06802F080FBBFF38A -:10747000508FE068018B012102F06FFBA57018E0CE -:10748000E068008BBFF3508FE079022808D1607A62 -:1074900030B1607820B10021E06802F068FB06E0BE -:1074A000E079032805D1607A18B1607808B100222C -:1074B00000E001223946E06802F063FB94F9031012 -:1074C000E079401C814209D16670A07828B1002281 -:1074D0004FF44071E06802F054FB2671BDE8F08182 -:1074E0004A0753D5A570627A7B494978CAB3C9B3B4 -:1074F000E17902291FD9002102F039FBE06802F08E -:107500004AFB94F9031062695054491CE17001214F -:10751000E06802F022FBA570E06802F03CFB94F901 -:10752000031062695054491CE17001223946E06839 -:1075300002F027FB25E0012102F00FFBE06802F0DA -:107540002AFB94F9031062695054491CE170E06809 -:1075500002F021FB94F9031062695054891CE17018 -:107560000FE000E000E009B9217A31B1012102F019 -:10757000F4FAE078401CE07003E0012102F0E3FA45 -:107580006570E0680188C905FCD497E74A061AD5FA -:1075900002F001FB94F9031062695054491C48B28F -:1075A000E070E179C01C814204D100223946E068D4 -:1075B00002F0E7FAE17994F903008142E5D100F1A4 -:1075C0000100E0707AE70906DFD594F903104B1C3F -:1075D0005AB20BD02369595CE27002F0DAFAE07912 -:1075E00094F9031088423FF45AAF67E7E270A1793B -:1075F00002F0CFFA607A00287FF451AFE0790028DA -:10760000F1D05BE7EEE6B0E6ECE670B5324C4FEA5F -:10761000400047F230556071A171012020720021B5 -:10762000617223616361E27120712170E068818879 -:1076300089050ED40188C90505D401888905FCD4C3 -:10764000012102F080FA01224FF44071E06802F05B -:1076500098FA207910B16D1EFBD104E01DB120789D -:1076600080F0010070BD6089401C6081E068FFF718 -:107670002BFE002070BD07B502AB0122FFF7C5FF4E -:107680000EBD70B5144C4FEA400047F230556071A2 -:10769000A171002020720121617263612361E27196 -:1076A00021712070E068818889050ED40188C905A0 -:1076B00005D401888905FCD4012102F044FA012295 -:1076C0004FF44071E06802F05CFA207940B16D1E21 -:1076D000FBD10AE0000C014088030020801A06005C -:1076E0001DB1207880F0010070BD6089401C608170 -:1076F000E068FFF7E9FD002070BD2A484089704727 -:107700002DE9F84F4FF44067ADF800704FF0020AD2 -:107710008DF803A01420DFF890B08DF802006946C0 -:10772000584601F0D3FA204D10352F60DFF87890DD -:1077300000262C1505F1040809F1080902E00A20C9 -:1077400000F0CAFAD9F800004005F8D5C8F80040A2 -:107750000A2000F0C1FA2C600A2000F0BDFA761C65 -:10776000F6B2082EEED34FF400694646C8F80090F2 -:107770000A2000F0B1FA34600A2000F0ADFA2C6063 -:107780000A2000F0A9FAC5F80090ADF800708DF855 -:1077900003A01C208DF802006946584601F096FAB5 -:1077A000BDE8F88F88030020000C014038B504467E -:1077B0006B4602221B216820FFF763FFBDF8000023 -:1077C00043F2903140BA08444FF48C71B0FBF1F0B1 -:1077D0002330208038BD1FB5044602AB06221D2190 -:1077E0006820FFF74EFFBDF80800214640BA02B2FC -:1077F000D01702EB90708010ADF80000BDF80A00C1 -:1078000040BA02B2D01702EB90708010ADF80200BF -:10781000BDF80C0040BA02B2D01702EB9070801095 -:10782000ADF804002F4842786846FFF754F81FBDB2 -:1078300070B50446192000F05BFA0022152168207B -:10784000FFF719FF10B9032000F0FCFA254D1621AF -:10785000287840F018026820FFF70DFF002217215A -:107860006820FFF708FF01223D216820FFF703FF92 -:1078700001223E216820FFF7FEFE002C00D06C7034 -:1078800070BD70B504460D46192000F031FA002293 -:1078900015216820FFF7EFFE00281CD01248206059 -:1078A000124860601248A0601248E0600D48622DE6 -:1078B00012D004DC0A2D13D0142D05D10EE0BC2DFE -:1078C00006D0B5F5807F01D0032102E0002100E061 -:1078D00001210170012070BD0221FAE70421F8E7BF -:1078E0000521F6E7A003002031780008D7770008CB -:1078F000AD77000818449231FEB5064614460D4691 -:10790000684602F025FC0120ADF804000021ADF826 -:107910000050ADF80610ADF80810ADF80240694609 -:10792000304602F065FBFEBD70B51646D04A02EB4C -:107930000015D04A02EB00140122206801F0EFFA92 -:10794000D4E90101182200F087F9217B3246206832 -:1079500000F03FF9A07B18B10121206802F00AFC79 -:107960000121206802F0FCFB207B30B1042807D005 -:1079700008280AD00C2806D10AE02068343001E03B -:10798000206838302860284670BD20683C30F9E710 -:1079900020684030F6E72DE9F0410546B4480F462F -:1079A00000EB0516B348B27100EB05142822D4E9A8 -:1079B000010100F051F9217B00222068FFF79CFFB4 -:1079C00001224FF6FF71204601F0C6FA3A462946D9 -:1079D000204601F087FA3046BDE8F08170B5A64830 -:1079E0000024028942810181891A8BB240F68C21E0 -:1079F0008B4201D9C47070BD9F49A3F2EF2540F2BC -:107A0000DB569E4AC978B5421BD2082919D2984D37 -:107A1000E035042925F8113007D2C588AB4204D9D6 -:107A2000012305798B402B43037103790F2B08D178 -:107A30000471B2F90030142B02DD143B138000E016 -:107A40001480491CC170148070BD70B5884A894B80 -:107A500002EB001203EB0013D47918681B7B8CB186 -:107A600051811489824D091B91819479E03525F863 -:107A700014100024D47122461946FFF73DFF7F48B9 -:107A8000048070BD11810121D171BDE870400222D6 -:107A9000194631E72DE9F0470446774DE18900208A -:107AA000E980A17901B10220617801B1401C7449DB -:107AB000DFF8D081002651F820704FF47A79BA5D52 -:107AC00002F00F0002F0F001FF2A65D0A2781AB18F -:107AD00002285ED003285CD0E2783AB1042858D05E -:107AE000052856D0062854D0072852D0E2790AB18A -:107AF00082424ED011F0300F02D0227802B900211C -:107B0000227932B1A27922B9082801D0092800D1FE -:107B1000802162792AB1A2791AB9021F032A00D8FA -:107B20008021CA0605D500225749FFF734FF0820F7 -:107B300008E08A0608D5AA785449FFF72CFFA878F0 -:107B400000F10100A87024E04A0612D52289B8FB92 -:107B5000F2F1A28989B202B94A46FFF7E5FE014671 -:107B6000434A2878F03242F8201000F101002870D2 -:107B70000FE009060DD56289B8FBF2F189B24A46D9 -:107B8000FFF7D2FE0146424A687842F82010401CB6 -:107B90006870761C0E2E92DB0020BDE8F087364A16 -:107BA0001278904205D23A4A303A52F820000068E2 -:107BB00001807047304A5278904204D2344A52F8D9 -:107BC00020000068018070473149403931F81000C9 -:107BD00070477FB5064615460C46684602F0AEFA79 -:107BE0007020ADF800000120ADF802000020ADF8D3 -:107BF00004000220ADF80800C001ADF80650ADF851 -:107C00000C0074B1042C15D0082C1CD00C2C07D1FE -:107C10006946304602F038F90821304602F0D3FABE -:107C20007FBD6946304602F084F80821304602F0F4 -:107C3000B4FA7FBD6946304602F0B0F808213046FC -:107C400002F0B1FA7FBD6946304602F0E3F8082140 -:107C5000304602F0B2FA7FBD08B5ADF800108DF8DD -:107C6000022002218DF80310694601F02FF808BDAB -:107C7000280F0020B4C70008A2030020CE00002077 -:107C800078C7000840420F00DD7900084B7A0008F1 -:107C90004810002080484168491C4160704710B579 -:107CA0007D484FF0E02341689A694468A142FAD1C7 -:107CB0000368006803EB4304C4EBC313C2EBC302C5 -:107CC000B2FBF0F001EB4102C2EBC11100EBC100CD -:107CD00010BD71484068704730B50546FFF7DFFFBB -:107CE0004FEA0004FFF7DBFF001BA842FAD330BDC8 -:107CF00030B504464FF47A7502E02846FFF7ECFFF2 -:107D0000641EFAD230BD6449896808474FF4805137 -:107D100008B1624801E06148001F016070474FF4FC -:107D2000805110B15D48001F00E05C480160704761 -:107D30002DE9F04F8DB018225949684602F041FCF8 -:107D4000032701F002FC0121564801F08DFF0121BB -:107D500044F61D2001F07FFF0121084601F072FF6B -:107D600001F09DFF4FF6FF70ADF818004B484FF043 -:107D7000000A8DF81AA006A9143800F0A7FF06A97A -:107D8000494800F0A3FF06A9484800F09FFF484873 -:107D9000416841F000714160464DDFF81C813E4E64 -:107DA0002968414501D1454800E04548B0600020C0 -:107DB000FFF7A9FF3C490820103108601020086037 -:107DC000A946002483466D46D9F80010414506D1E6 -:107DD00005EBC4008179142901D180F806B005EBC8 -:107DE000C401091D55F8340000F070FF641CBC424A -:107DF000EAD307A801F0E0FE32490798B0FBF1F0A2 -:107E0000306031484FF47A710068B0FBF1F0B0F1A6 -:107E1000807F0CD220F07F414FF0E020491E41616D -:107E20002A4AF0211170C0F818A0072101612848E2 -:107E3000FFF74AFA00F0B5FF6420FFF759FF0DB0D5 -:107E4000BDE8F08F184A1021143211600821121F6A -:107E500011600446151F40F2DB104443286880F08F -:107E600010002860286880F008002860A01EFFF736 -:107E70003FFF0120FFF747FF1920FFF739FF0020E0 -:107E8000FFF741FFEAE710B11349124808600F49B4 -:107E90001248173908607047B003002014080140E9 -:107EA00088C7000807004000000C01400010014096 -:107EB0000000014004040020001BB7001F7D0008E3 -:107EC0000D7D000840420F000004002023ED00E07B -:107ED00000580040EFBEADDEF04F00200400FA0570 -:107EE0007CB5FA4C0D46FA492160A060A4F53070CB -:107EF000606100F58070A0614FF48070E0602061E7 -:107F0000F4482063F348012114386063880301F0CA -:107F1000A2FE02208DF803000002ADF80000182038 -:107F20008DF80200EC4EA80703D56946304600F0F4 -:107F3000CDFE4FF48060ADF8000048208DF80200BF -:107F4000E80703D06946304600F0C0FE0E208DF8E9 -:107F5000040001208DF805008DF806008DF807005B -:107F600001A801F09EFB20467CBD2DE9FC41D74CC9 -:107F70000D464C34D6492160A0608020E06040204E -:107F80002061A4F5867060618030A061D348012132 -:107F9000A064480401F068FE02268DF80360042006 -:107FA000ADF8000018208DF80200CB4FA80703D5CC -:107FB0006946384600F08AFE0820ADF800004820E7 -:107FC0008DF80200E80703D06946384600F07EFECF -:107FD00026208DF8040001208DF805008DF806603C -:107FE0008DF8070001A801F05CFB2046BDE8FC818C -:107FF0002DE9F04389460646B9490024B7488FB0B9 -:108000001D4617468E4204D119461046FFF768FFF9 -:1080100005E0864204D119461046FFF7A6FF044644 -:108020004FF00008C4F82080C4F81C80C4F82880F1 -:10803000C4F82C90C4F82480A6642571A760ADF81C -:108040003080ADF834800B97ADF83280ADF83880D1 -:10805000ADF83680E80702D00420ADF83600A80756 -:1080600005D5BDF8360040F00800ADF836000BA984 -:10807000304602F0CFF80121304602F023F968467D -:1080800001F060FC301D00904FF48050CDE90908EC -:108090008020CDF81080CDE905084746CDF81C803A -:1080A000E80723D0206BD8B1E068CDE9027020202A -:1080B000089060690190206B01F0BAFB6946206B63 -:1080C00001F023FC0121206B01F049FC0122402139 -:1080D000304602F019F9206B01F056FC206405E0EF -:1080E000012240F22551304602F0F6F8A80724D5C7 -:1080F000606BE0B120690390102008970290606BDC -:1081000001F096FB6946606B01F0FFFB0122022142 -:10811000606B01F02FFC0021606B01F033FC606BA1 -:10812000476001228021304602F0EEF805E001228E -:1081300040F22771304602F0CFF80FB02046BDE87C -:10814000F0837FB504460020ADF80400ADF80800C8 -:108150000091ADF80600ADF80C00ADF80A002079EA -:108160000D46C00702D00420ADF80A002079800730 -:1081700005D5BDF80A0040F00800ADF80A006946D0 -:10818000A06C02F047F8A5607FBD826A8169114446 -:10819000426BD160D0E9092100238A4205D9511AE6 -:1081A000426B5160416A816204E00269511A426B7C -:1081B0005160836280F84430406B012101F0CFBBF5 -:1081C000016B11B14968006C01E01C3003C88142A9 -:1081D00001D00120704700207047416B11B190F829 -:1081E00044007047243003C8814201D10120704708 -:1081F0000020704710B50146036BC268406943B167 -:108200000B6CD21A805C5B1E0B6401D1CA680A64D5 -:1082100010BD0B6AC05C5B1CB3FBF2F402FB1432B2 -:108220000A6210BD436A8269D154416A0269491CDD -:10823000B1FBF2F302FB13114162416B19B1096802 -:10824000C90706D1A1E7806C012240F2277102F034 -:1082500043B8704710B51D4C4FF4005001F097FB28 -:108260000021606B01F07BFBD4E90901884203D057 -:108270002046BDE8104088E7012084F8440010BD86 -:108280001249886C028812060ED5D1E909329A4249 -:108290000BD08B699A5C8280886A0A69401CB0FBAB -:1082A000F2F302FB130088627047002240F227714C -:1082B00002F012B870B5054C4C34A06C0588A906C4 -:1082C0001CD58088E16A69B1884717E0281300202F -:1082D000A0C70008580002400008014000440040C8 -:1082E00000380140E26961698854E069E16800F1A1 -:1082F0000100B0FBF1F201FB1200E06128060FD58E -:10830000D4E9091088420CD0A169085CA16C88806E -:10831000A06A2169401CB0FBF1F201FB1200A062CF -:1083200070BDA06CBDE87040002240F2277101F0E2 -:10833000D3BF0000FEB52C4C0125207878B1012870 -:1083400023D0022820D164208DF8000027488DF822 -:10835000015000264078E0B38DF802503CE07A20CE -:108360008DF8000022486B460222B0F90000FF2180 -:10837000C0F1B40000EBD070C0F347008DF80100ED -:108380006D20FFF742F92570FEBD1A4E79208DF859 -:108390000000B6F900000A2590FBF5F05A30B4222F -:1083A0000021FEF74FF98DF80100B6F90200B42262 -:1083B00090FBF5F05A300021FEF744F98DF80200E9 -:1083C0006B460322FF216D20FFF71FF9022020706A -:1083D000FEBDFFE78DF802606B460322FF216D2092 -:1083E000FFF713F92670F3E7BC030020680A0020AA -:1083F000A8010020380000201FB5044602AB062269 -:1084000043216820FFF73DF9BDF80800214640BA36 -:1084100002B2D01702EB90708010ADF80000BDF8EA -:108420000A0040BA02B2D01702EB90708010ADF88B -:108430000200BDF80C0040BA02B2D01702EB9070F7 -:108440008010ADF804007C4842786846FEF743FA95 -:108450001FBD38B504464FF40050ADF800000220AF -:108460008DF8030004208DF80200744874490068F8 -:10847000884202D16946734804E07349884203D1B7 -:108480006946724800F022FC80226B216820FFF7C9 -:10849000F2F80520FFF72CFC002219216820FFF7D5 -:1084A000EAF803226B216820FFF7E5F80222372162 -:1084B0006820FFF7E0F8604D1A2168202A78FFF75E -:1084C000DAF818221B216820FFF7D5F810221C21AA -:1084D0006820FFF7D0F8002C00D06C7038BD1FB5B5 -:1084E000044602AB06223B216820FFF7CAF8BDF81C -:1084F0000800214640BAADF80000BDF80A0040BAB5 -:10850000ADF80200BDF80C0040BAADF804004A48CE -:1085100082786846FEF7DFF91FBD47494C4ACB78A1 -:1085200013B14FF4FF6301E04FF480531380002830 -:1085300000D0887070472DE9FE4F814698469246DC -:108540000D462320FFF7D4FB6B46012275216820DE -:10855000FFF797F8002804D09DF80000682802D0A3 -:108560000020BDE8FE8F062201AB11466820FFF710 -:1085700088F89DF809009DF80710C007400F01F02A -:10858000010140EA41009DF805102B4C01F001016A -:1085900008434FF001064FF0000704D0012833D004 -:1085A00002280DD02CE06B4601220C216820FFF739 -:1085B00068F89DF8000010F00F0021D0042823D0A7 -:1085C000E7702449C9F8001023492448C9F8041069 -:1085D0002860234868602348E860B8F1000F02D0A3 -:1085E000E17888F800105046BAF1620F19D00DDC1E -:1085F00005281ED00A281AD0BAF1140F0BD114E0A6 -:108600000520FFF71FFCDCE7E670DAE7BC2806D0A0 -:10861000BAF5807F01D0032004E0277003E02670C4 -:1086200001E00220207001209BE70420FAE70520EA -:10863000F8E70620F6E70000BD0300200404002050 -:1086400000127A00000C0140001BB700001001402E -:108650007A0100201B850008DF840008538400088D -:10866000F9830008194492311FB5044602AB062273 -:1086700001211C20FFF705F8BDF80800214640BA8B -:1086800040F38D02D01702EB90708010ADF800001F -:10869000BDF80A0040BA40F38D02D01702EB90708B -:1086A0008010ADF80200BDF80C0040BA40F38D0216 -:1086B000D01702EB90708010ADF8040033480278B8 -:1086C0006846FEF708F91FBD38B504462020ADF80E -:1086D000000002208DF8030004208DF80200694696 -:1086E0002B4800F0F3FA00222A211C20FEF7C3FFDA -:1086F00002220E211C20FEF7BEFF03220F211C20A8 -:10870000FEF7B9FF12222B211C20FEF7B4FF022234 -:108710002C211C20FEF7AFFF01222D211C20FEF78B -:10872000AAFF00222E211C20FEF7A5FF05222A21E8 -:108730001C20FEF7A0FF17494FF48070002C088022 -:1087400001D01248047038BD38B5044600208DF8B9 -:10875000000011481149006888420CD06B46012284 -:108760000D211C20FEF78DFF28B19DF800002A285E -:1087700003D01A2801D0002038BD094921600949D9 -:10878000616002494870012038BD0000C10300202B -:10879000000801407A01002004040020001BB700FB -:1087A000C986000869860008434810B50068434C34 -:1087B000A188084203D0FFF772FAA0600AE0FFF731 -:1087C0006EFAA168884205D9401A3B2190FBF1F06E -:1087D00061690860E068BDE8104001F02BB9E3E78B -:1087E000E2E7FEB50125354C022110B1012810D178 -:1087F00009E04FF4807060804000A080E0600920B4 -:108800002070172004E06580A180E16025700720BA -:1088100060706088ADF800001026274F8DF8026068 -:108820008DF80310083F6946384600F04FFAA088DB -:10883000ADF8000004208DF802006946384600F0CB -:1088400045FA2178012001F069FDE06801F0F2F8B5 -:10885000E068019000208DF808008DF809608DF81F -:108860000A5001A801F0A2F894F9010000F01F01DC -:108870008D4040094FF0E02101EB8000C0F800512D -:10888000FFF727FA3C382061FEBD70B50546FFF7BB -:1088900020FA0A4C21693C3188420CD3C4E9040512 -:1088A00005496088083108600B20FFF715FA024976 -:1088B00060880C31086070BD080C0140C4030020C2 -:1088C0001FB5044602AB0622A8216820FEF7D9FE98 -:1088D000BDF80800214640BA02B2D01702EB9070F2 -:1088E0008010ADF80000BDF80A0040BA02B2D017FF -:1088F00002EB90708010ADF80200BDF80C0040BA99 -:1089000002B2D01702EB90708010ADF80400264838 -:1089100042786846FDF7DFFF1FBD70B5044664204E -:10892000FFF7E6F9F02223216820FEF7A4FE10B934 -:108930000320FFF787FA0520FFF7DAF91A4D202107 -:10894000287840F00F026820FEF795FE002C00D03A -:108950006C7070BD38B504460D461920FFF7C8F994 -:108960006B4601220F216820FEF78BFE9DF8000068 -:10897000D32801D0002038BD0C4820600C4860602E -:108980000C48E0600848362D05D04E2D07D05D2DEF -:1089900007D0002100E040210170012038BD802176 -:1089A000FAE7C021F8E70000DC0300201B8900087B -:1089B000C1880008DDE9A7312DE9F04FB74C8346A7 -:1089C0008E46608926890102B5484FF0000A40684A -:1089D000421AA6FB027CA0884FEAE2754FEA1041DA -:1089E0004FEA00430AFB02C006FB05064FEAD71018 -:1089F00040EA466013EB000941EBE611E688638824 -:108A0000A6FB02C84FEA53404FEAC3370AFB028372 -:108A100006FB05364FEA1C2343EA0663FB1840EBCE -:108A20002620A689A6FB027C0AFB02C206FB0524BF -:108A30004FEAD75242EA44224FF4FA654FEAE4542F -:108A4000521944F10004A246551B74F1000448DA9F -:108A5000944D5519A5FB05674AF1FF3404FB0577D2 -:108A600005FB047C0525A6FB05480CFB05850027B6 -:108A700006FB07556F104FEA340CB9EB0C0961EB9C -:108A80000701A40844EA85741B1B60EBA500864D12 -:108A9000551B7AF1FF3424DA40F2DC555619A6FB57 -:108AA00006474AF1000505FB067706FB0575072614 -:108AB000A4FB06C805FB0686002704FB0767B9EB85 -:108AC0000C0961EB07010B27A4FB07C805FB078511 -:108AD000002604FB065464104FEA3C055B1B60EB68 -:108AE00004006F4CA5680024A5FB036704FB037317 -:108AF00005FB0030740D44EAC0244015B4EB0903B3 -:108B000060EB0100410441EAD330BBF1000F01D01A -:108B1000CBF80000BEF1000F01D0CEF80020BDE878 -:108B2000F08F10B500F072F85D49886010BD5C48A8 -:108B3000012200784030C1B27720FEF79CBD10B50D -:108B400000F064F85649486010BD5548012200788D -:108B50005030C1B27720FEF78EBD2DE9FE430546A9 -:108B600052485349006888420FD04FF40054ADF882 -:108B7000004002208DF8030010204E4E8DF80200B8 -:108B80006946304600F0A2F874610A20FFF7B0F899 -:108B900001AB0122A0217720FEF773FD002823D02E -:108BA00001221E217720FEF766FD4FF42F60FFF7AC -:108BB00093F80024DFF8E4802646A02707EB440062 -:108BC000C1B202AB022277200296FEF75AFDBDF831 -:108BD000080040BA28F81400641C082CEEDB2F486B -:108BE00000F026F810B10020BDE8FE8342F21070BC -:108BF00028806880304868603048A8603048E86065 -:108C000030482861304868610120EDE708B56B46BF -:108C1000032200217720FEF734FD9DF800009DF827 -:108C20000110000440EA01209DF80210084308BD2D -:108C3000F0B5C289002102F47F4502F00F04012340 -:108C4000C5810A4630F8126006B10023521C082A7A -:108C5000F8DB4FF0FF36F3B90022D30722F001030F -:108C600002D0C35C594002E0C35A81EA13210823B1 -:108C70000F0401D581F4C05149005B1E002BF7DCC5 -:108C8000521C102AE9DB2543C581C1F3033084421D -:108C900001D10020F0BD3046F0BD0000C01300201F -:108CA000E003002030F8FFFF24FAFFFF0404002057 -:108CB000001BB700001001404B8B00083F8B0008E1 -:108CC0002F8B0008238B0008B9890008F0B500231A -:108CD0004FF0010C0A880CFA03F52A4228D04FEA1B -:108CE000D30200EB82064FEA437491F802E04FEAA8 -:108CF000D46734680EF00F025FEACE6E03D591F8A8 -:108D000003E04EEA02024FF00F0E0EFA07FE24EACD -:108D10000E04BA40224332608A78282A02D0482AB8 -:108D200003D005E0C268AA4301E0C2682A43C260DA -:108D30005B1C102BCED3F0BD4FF4805108B14E48D0 -:108D400001E04D48001F016070472DE9F0410446E5 -:108D50004A4817460D460088484E0C3E1CE015B1A7 -:108D600015F8010B00E0FF2080460221304601F09B -:108D7000EDFB0028F9D04146304601F0E3FB01212C -:108D8000304601F0E3FB0028F9D0304601F0DCFB6F -:108D9000C0B20CB104F8010B7F1EE0D20120BDE887 -:108DA000F081F0B501218C0389B0204600F05CFF12 -:108DB0000121204600F06AFF18208DF816004FF4BC -:108DC0002040ADF814002C4E03208DF81700143EFF -:108DD00005A93046FFF77AFFADF8144004208DF85E -:108DE000160005A93046FFF771FFA010ADF814007A -:108DF00010258DF8165005A93046FFF767FF1F4E66 -:108E00000C3E304601F054FB4FF48270ADF8020086 -:108E100068010024ADF80A000720ADF81000ADF895 -:108E200004400220ADF80E40ADF806000127ADF871 -:108E30000040ADF80870ADF80C506946304601F0BE -:108E40005BFB0121304601F073FB0DA0006806902A -:108E50000120FFF771FF042206A907A8FFF775FF9D -:108E60000020FFF769FF9DF81D00EF2802D0204683 -:108E700009B0F0BD3846FBE7140C01400C38004047 -:108E80009F0000002DE9F04180461D4616460C4625 -:108E9000084600F0E7F80746404600F0D8F807EB30 -:108EA0008000C0B2102805D2734901EB0010856024 -:108EB00004710673BDE8F08151B104290BD0082973 -:108EC0000CD00C290DD101225FF0100101F05DB929 -:108ED00001220221FAE701220421F7E701220821F9 -:108EE000F4E7704770B50D460446017B13460068F1 -:108EF0002A46FFF7C7FF217B2068BDE87040DBE70B -:108F000008B58DF8000000208DF8010001208DF8D3 -:108F100002008DF80300684600F0C3FB08BDFEB5F3 -:108F2000064614460D46684601F0FFF853486D1E8C -:108F300044435348ADF8045069460068B0FBF4F070 -:108F4000401EADF800000020ADF80600ADF80200AC -:108F5000304600F0B5FEFEBD10B504460068FFF7D0 -:108F6000DEFF0121206801F0FBF8607BBDE81040C6 -:108F7000C6E770B50546084600F074F80446284672 -:108F800000F065F804EB80003B49C0B201EB001033 -:108F900070BD70B50546022101F028F9012825D0E1 -:108FA0000421284601F022F901282CD00821284666 -:108FB00001F01CF9012833D01021284601F016F9E0 -:108FC00001283AD11021284601F01CF90C2128462D -:108FD000FFF7CFFF0446284601F005F9A2680146D5 -:108FE000002A2AD0207BBDE8704010470221284685 -:108FF00001F008F900212846FFF7BBFF0446284688 -:1090000001F0EBF8EAE70421284601F0FBF804211F -:109010002846FFF7AEFF0446284601F0E0F8DDE7FA -:109020000821284601F0EEF808212846FFF7A1FFA5 -:109030000446284601F0D5F8D0E770BD1148A8E7EE -:109040004FF08040A5E71048A3E71048A1E701468C -:1090500000200F4A01E0401CC0B252F820308B4281 -:10906000F9D17047014600200A4A01E0401CC0B215 -:10907000135C8B42FAD17047D013002040420F009E -:1090800000040020002C01400004004000080040C3 -:10909000EC03002094C80008016B4A689268896854 -:1090A0000A4290F8441204D00020002900D1012087 -:1090B000704701200029FBD100207047D0F83431DF -:1090C00001299A685B6801D021B107E090F8440259 -:1090D00030B103E090F84402012801D05A61704792 -:1090E0001A6170470189406889B2482200F052B97C -:1090F00070B5044601EB4100AC491646B1FBF0F0F7 -:1091000081B21D4603222046FFF726FF2A4631463C -:109110002046BDE87040FFF7E5BE0189406889B28E -:10912000102200F037B900B50346032083F83C0253 -:109130001846FFF7B1FF30B1B3F8400293F8391287 -:109140000843A3F8400293F83902400083F839023B -:1091500093F83E02401E10F0FF0083F83E0205D156 -:10916000012083F83802022083F83C0200BDC26867 -:10917000016A521E914201D3002100E0491C0162A4 -:10918000704710B50124034680F83C42FFF784FF86 -:1091900001280FD1002083F8380283F83A4293F86F -:1091A0004002A3F840021A6A59698854BDE8104089 -:1091B0001846DCE710BD00B50346FFF76DFF01213F -:1091C00001280BD003F23A2300201870D880042025 -:1091D00098700820187103F8011C00BD83F83C1238 -:1091E00000BD90F83C12491E11F0FF0180F83C12BE -:1091F00008D190F83A1201B1DDE790F8381201B1C8 -:10920000BFE790E77047D0E90910814201D1012002 -:1092100070470020704730B5044690F83B020025A7 -:10922000F8B194F83D02401E10F0FF0084F83D02B2 -:1092300016D1B4F8420200F001014008A4F842023D -:109240002046FFF73BFF032084F83D0294F83F02DD -:10925000401E10F0FF0084F83F0201D184F83B5219 -:1092600030BD2046FFF7CFFF0028F9D1A16AA269DF -:10927000481CA062515C2269904200D3A5624FF461 -:10928000007004F23B2440EA4100A4F807000A20E1 -:1092900020710120A070207030BD00EBC00101EBF7 -:1092A000801010B5424901EBC0042046FFF7B3FF20 -:1092B0002046BDE8104094E770B53D4C06463D4859 -:1092C000206003202071A66084F844123A4820638D -:1092D0001030C4F83401002504F1340125626161C5 -:1092E0004FF48070E060206104F59C71C4E90615BC -:1092F000A562656284F83B52012084F83A0284F842 -:10930000385284F83C02206BFFF7ECFED4F83401AD -:10931000FFF703FF01212046FFF7D0FE3220FEF7C2 -:10932000E7FCAFF289032A463146206BBDE8704066 -:10933000DEE6D0E90721914202D14FF000007047EC -:1093400002D9A1EB020003E0C0680844A0EB0200D0 -:10935000C0B2704700B50346FFF7EBFF00280BD003 -:109360005969D869095CDA68521E904201D2401CE2 -:1093700000E00020D861084600BD436A8269D154EC -:10938000416A0269491CB1FBF2F302FB131141620D -:109390007047704708B5ADF800108DF80220022123 -:1093A0008DF803106946FFF791FC08BDC0C62D007B -:1093B000D014002098C80008F4C700081FB5044660 -:1093C00002AB062202211820FEF75BF99DF8080087 -:1093D0009DF80910800800EB0120ADF800009DF811 -:1093E0000A009DF80B10800800EB0120ADF8020088 -:1093F0009DF80C009DF80D10800800EB0120ADF8E1 -:1094000004001A48214602786846FDF764FA1FBD39 -:1094100010B5044608220F211820FEF72CF90E2261 -:1094200010211820FEF727F911494FF48050002C25 -:10943000088001D00D48047010BD38B504460020E6 -:109440008DF8000001466B4601221820FEF719F93D -:1094500018B19DF80000FB2801D0002038BD054858 -:10946000206005486060012038BD0000FC0300203A -:109470007A01002011940008BD9300080268126868 -:10948000104770B50C46054603E02A682846126866 -:10949000904714F8011B0029F7D170BD0168496895 -:1094A00008470168896808470268D2681047016860 -:1094B000096908476E48016841F00101016041688F -:1094C0006C4A1140416001686B4A114001600168BB -:1094D00021F480210160416821F4FE0141604FF4D4 -:1094E0001F0181606549C00308607047604A10B57C -:1094F0005068634B10F00C01624803D0042903D07C -:10950000082903D0036016E0416813E051685368EE -:1095100001F470114FF0020413F4803F04EB914109 -:1095200006D053689B03436800D55B084B43E9E7CB -:10953000554B594301605168524AC1F30311083237 -:10954000515C0268CA40026010BD3EB40021009127 -:109550004FF4E01301914648CDE901314B4A0468CC -:1095600044F480340460846944F0100484614FF44E -:10957000A064056805F400350195009D6D1C0095FB -:10958000019D15B9009DA542F3D10568AD0301D534 -:10959000022114E0056845F00105056000910168AD -:1095A00001F0020101910099491C0091019911B942 -:1095B0000099A142F3D10168890739D501210291AF -:1095C00033490C6844F010040C600C6824F0030468 -:1095D0000C600C6844F002040C6041684160416812 -:1095E0004160416841F480614160116821F070413F -:1095F0001160244C22496160416821F47C11416072 -:10960000116841F0004111602049091FCA6822F425 -:109610000042CA608968090403D51E494FF48013CB -:10962000616002990193012908D002290AD100E062 -:10963000FEE7416843F48032114302E0416841F49F -:1096400060114160016841F0807101600168890129 -:10965000FCD5416821F003014160416841F00201FD -:1096600041604168C1F381010229FAD13EBC3DE766 -:10967000001002400000FFF8FFFFF6FE08ED00E0DA -:1096800000127A000004002000093D00041001408F -:1096900000200240001BB700184908431849086021 -:1096A0007047F0B50F21C478027801234FF0E0260F -:1096B000DCB1134C2468457804F4E064C4F5E0643C -:1096C000240AC4F10407E1408478BD400C402C43D7 -:1096D00021010C4C1155007800F01F018B4040090E -:1096E00006EB8000C0F80031F0BD02F01F0083409F -:1096F000500906EB8000C0F88031F0BD0000FA058B -:109700000CED00E000E400E010B54268464B0C7937 -:109710001A400B6842EA0422134343608368434AB9 -:109720001340D1E9024222434C7943EA44031A43ED -:109730008260C26A097C22F47002491EC9B242EA00 -:109740000151C16210BD0029816802D041F00101C0 -:1097500001E021F00101816070470029816802D099 -:1097600041F4807101E021F480718160704781686B -:1097700041F00801816070470146002089680907AF -:1097800000D501207047816841F004018160704775 -:10979000014600208968490700D50120704700294B -:1097A000816802D041F4A00101E021F4A0018160B0 -:1097B000704770B5072409290AD9C568A1F10A06BE -:1097C00006EB4606B440A543B3401D43C56007E021 -:1097D000056901EB4106B440A543B3401D43056153 -:1097E0001F23072A09D2446B521E02EB82029340C8 -:1097F0009C4391400C43446370BD0D2A09D2046B15 -:10980000D21F02EB820293409C4391400C430463BD -:1098100070BDC46A0D3A02EB820293409C439140B2 -:109820000C43C46270BD0000FFFEF0FFFDF7F1FFC6 -:1098300001684FF6FE721140016000210160416035 -:109840008160C1605749574A0839904203D148683E -:1098500040F00F0006E0534A1432904204D14868A9 -:1098600040F0F000486070474E4A2832904203D1E1 -:10987000486840F47060F5E74A4A3C32904203D1B0 -:10988000486840F47040EDE7464A5032904203D1B8 -:10989000486840F47020E5E7424A6432904203D1C0 -:1098A000486840F47000DDE73E4A7832904203D1C8 -:1098B000486840F07060D5E73B4A111F904203D1E1 -:1098C000086840F00F0006E0374A1432904204D195 -:1098D000086840F0F00008607047334A2832904230 -:1098E00003D1086840F47060F5E72F4A3C3290429B -:1098F00003D1086840F47040EDE72B4A50329042A3 -:10990000EAD1086840F47020E5E730B5036847F60F -:10991000F07293430C6A8A682243D1E904452C43D0 -:1099200022438C692243CC6922434C6A22438C6ACD -:1099300022431A430260CA6842600A68826049682A -:10994000C16030BD0021016041608160C160016182 -:1099500041618161C1610162416281627047002998 -:10996000016802D041F0010102E04FF6FE721140A1 -:1099700001607047002A026801D00A4300E08A4370 -:109980000260704741607047406880B27047C10014 -:1099900003D50549091F0860704702490839486026 -:1099A00070470000080002400804024030B5234917 -:1099B0008379026853B30B6893430B600A1D1368E5 -:1099C0000468A343136002790A44136804682343BC -:1099D00013601A4A083213680468A3431360131D06 -:1099E0001C680568AC431C604479102C05D02144E8 -:1099F0000A68006802430A6030BD116804682143A8 -:109A00001160196800680143196030BD007908448D -:109A100001689143016030BD084A01460020126888 -:109A2000064B0A4014331B680B4202D0002A00D0B8 -:109A3000012070470149143108607047000401405B -:109A40005A4910B588424FF0010101D14C0501E09F -:109A50004FF48004204600F019F92046BDE810407C -:109A6000002100F013B970B50446808886B00D4619 -:109A700020F03F06684600F09FF84D490298B0FB81 -:109A8000F1F189B20E43A680228822F001022280E1 -:109A9000484B2A689A421CD85200B0FBF2F080B2C0 -:109AA000042800D20420491C2184A083208840F08F -:109AB0000100208021884FF6F5300140A8886A898E -:109AC000104308432080A88929890843208106B0D3 -:109AD00070BDEB88A3F53F46FF3E05D102EB420285 -:109AE000B0FBF2F080B208E002EBC20303EB02121B -:109AF000B0FBF2F080B240F48040020501D140F0AA -:109B000001004FF4967251434FF47A72B1FBF2F1B7 -:109B100040F40040C7E741F28831016000218180B4 -:109B20004BF6FF72C280018141814FF480418181F7 -:109B300070470029018802D041F0010101E021F0C5 -:109B40000101018070470029018802D041F4807131 -:109B500001E021F48071018070470029018802D062 -:109B600041F4007101E021F4007101807047002987 -:109B7000018802D041F4806101E021F4806101801C -:109B80007047002A828801D00A4300E08A4382801D -:109B9000704701827047008AC0B2704712B141F02D -:109BA000010101E001F0FE01018270470054004014 -:109BB00040420F00A086010030B53C494A683C4B4A -:109BC00012F00C0405D03B4A042C126803D0082C78 -:109BD00024D0036000E002604A680F2303EA1212F7 -:109BE000354B9C5C0268E24042604C68072505EA00 -:109BF00014241C5D22FA04F484604C6805EAD42421 -:109C00001B5DDA40C2604968032303EA91312A4BA5 -:109C10001B1F595CB2FBF1F1016130BD4B684C6810 -:109C200003F470134FF0020514F4803F05EB9343E7 -:109C300005D04C68A40300D552085A43CBE71F4A0D -:109C40005343C6E7194A0029516901D0014300E096 -:109C5000814351617047154A0029916901D0014340 -:109C600000E0814391617047104A0029D16901D019 -:109C7000014300E08143D16170470C4A0029D1685B -:109C800001D0014300E08143D1607047074A0029B9 -:109C9000116901D0014300E081431161704703481D -:109CA000416A41F08071416270470000001002403B -:109CB00000127A00040400201C04002000093D006A -:109CC00030B50288FD4BFE4C98420DD0A0420BD01F -:109CD000B0F1804F08D0FB4DA84205D0FA4DA84204 -:109CE00002D0FA4DA84203D122F070054A882A43D7 -:109CF000F74DA84206D0F74DA84203D022F4407594 -:109D0000CA882A4302808A8882850A880285984206 -:109D10000AD0A04208D0F04A904205D0EF4A9042C3 -:109D200002D0EF4A904201D1097A01860121818255 -:109D300030BD30B5028C22F001020284028C83888F -:109D4000048B22F0020224F073050C882C430D8949 -:109D500015434A882A43D94DA8420BD0D84DA84272 -:109D600008D0DD4DA84205D0DC4DA84202D0DC4D24 -:109D7000A8420DD122F008054A8923F440732A43F2 -:109D800022F004058A882A438D891D43CB892B4301 -:109D900083800483C9888186028430BD70B5028CBB -:109DA00022F010020284028C8488038B0D8823F435 -:109DB000E6464FF6FF7303EA052535430E8922F088 -:109DC000200203EA061616434A8803EA02123243C7 -:109DD000BA4EB04202D0BA4EB04215D122F080063F -:109DE0004A8924F4406403EA0212324322F0400616 -:109DF0008A8803EA021232438E8903EA86062643E2 -:109E0000CC8903EA8404344384800583C9880187AC -:109E1000028470BD70B5028C22F480720284028CC0 -:109E20008488838B0D8823F073031D4322F4007311 -:109E30000E894FF6FF7202EA06261E434B8802EA9D -:109E4000032333439D4EB04202D09D4EB04215D104 -:109E500023F400664B8924F4405402EA032333437D -:109E600023F480668B8802EA032333438E8902EA57 -:109E700006162643CC8902EA041434438480858381 -:109E8000C9888187038470BD70B5028C22F480522A -:109E90000284048C8288838B0D8823F4E6464FF677 -:109EA000FF7303EA0525354324F400560C8903EAC1 -:109EB000043434434E8803EA063626437F4CA042DE -:109EC00002D07F4CA04205D122F480448A8903EA63 -:109ED0008212224382808583C988A0F840100684BC -:109EE00070BD828B22F440628283828B4FF6FF73B7 -:109EF00003EA01210A4382837047828B22F00C021D -:109F00008283828B0A4382837047028B22F44062F1 -:109F10000283028B4FF6FF7303EA01210A43028397 -:109F20007047F0B5048C24F010040484078B048C73 -:109F30004FF6FF7527F4734705EA03333B4305EA01 -:109F400002221A435D4B05EA011698420ED05C4B83 -:109F500098420BD0B0F1804F08D05A4B984205D0B0 -:109F6000594B984202D0594B984205D124F0200118 -:109F7000314341F0100104E024F0A0030B4343F00F -:109F8000100102830184F0BD028B22F00C020283D7 -:109F9000028B0A430283704770B5048C24F00104DD -:109FA0000484058B048C4FF6FF7606EA03131343F3 -:109FB00025F0F305414A2B4390420ED0404A90428F -:109FC0000BD0B0F1804F08D03E4A904205D03E4AB7 -:109FD000904202D03D4A904202D124F0020201E0B8 -:109FE00024F00A020A4342F001010383018470BD98 -:109FF0002DE9F05F0D4604460888304FDFF8C0C0F9 -:10A00000DFF8C0804988AA882B894FF0804960B367 -:10A01000042832D04FF6FF7E082836D0208C9B468D -:10A0200020F480502084A38B268C704600EA022204 -:10A0300023F473431A4300EA0B3010430EEA013E47 -:10A04000BC420BD0644509D04C4507D0444505D0EF -:10A050001D4A944202D01D4B9C425AD126F4005115 -:10A0600041EA0E0141F4805158E02046FFF794FF89 -:10A07000E9882046BDE8F05F86E72046FFF751FFFC -:10A08000E9882046BDE8F05F3FE7208C20F480702F -:10A090002084B4F81CA0208C0EEA031313432AF08A -:10A0A000F30A0EEA012B43EA0A03BC4220D06445BE -:10A0B0001ED04C451CD044451AD013E0002C014062 -:10A0C000003401400004004000080040000C004043 -:10A0D00000100040001400400040014000440140D6 -:10A0E00000480140494A944202D0494A944204D16E -:10A0F00020F4007040EA0B0002E020F420600843E6 -:10A1000040F48070A3832084E9882046BDE8F05F96 -:10A11000F3E626F402420A4342F48051A08320462B -:10A120002184E988BDE8F05FDBE64FF6FF718180AE -:10A1300000210180C18041800172704700210180AF -:10A1400041808180C180018141818181C1817047CD -:10A1500000210180418001228280C18001817047FD -:10A160000029018802D041F0010101E021F0010144 -:10A1700001807047002930F8441F02D041F40041AB -:10A1800001E0C1F30E0101807047002A828901D0ED -:10A190000A4300E08A4382817047028B22F0080262 -:10A1A0000A4302837047028B4FF6FF7322F400626A -:10A1B00003EA0121114301837047828B22F00802D8 -:10A1C0000A4382837047828B4FF6FF7322F400624A -:10A1D00003EA0121114381837047808E7047008F0D -:10A1E0007047808F7047B0F84000704702460020EB -:10A1F000138A92890B4202EA010202D0002A00D09F -:10A2000001207047C94301827047000000080040E8 -:10A21000000C004030B50446008A85B00D464CF66F -:10A22000FF710840E98801432182A1894EF6F310AD -:10A230000140A8882A8910436A890A431043A081F3 -:10A24000A08A4FF6FF410840A9890143A1826846D0 -:10A25000FFF7B2FC3048844201D1039800E0029835 -:10A26000A1890904002900EBC00101EB0010296855 -:10A2700002DA4FEA410101E04FEA8101B0FBF1F05F -:10A280006422B0FBF2F14FEA01114FEA11136FF0B3 -:10A2900018056B4300EB8300A3891D044FF03203C4 -:10A2A00006D503EBC000B0FBF2F000F0070005E0BC -:10A2B00003EB0010B0FBF2F000F00F000843208128 -:10A2C00005B030BD0029818902D041F4005101E080 -:10A2D00021F400518181704710B5C1F3421301F0A0 -:10A2E0001F040121A140012B07D0022B07D01430FD -:10A2F000002A026805D00A4304E00C30F8E7103069 -:10A30000F6E78A43026010BD002A828A01D00A4320 -:10A3100000E08A43828270470038014010B58A0706 -:10A3200021F003040649130F21440F228C689A4040 -:10A3300094438C608A68984002438A6010BD000094 -:10A34000000001403948384941603949416070474F -:10A350003648016941F080010161704733490420AA -:10A36000CA68D20701D001207047CA68520701D5D8 -:10A3700002207047C968C906FBD50320704700B5A5 -:10A380000346FFF7EBFF02E0FFF7E8FF5B1E012843 -:10A3900003D0002B00D1052000BD002BF4D1FAE73B -:10A3A00070B505464FF430263046FFF7E8FF042825 -:10A3B00011D11E4C206940F00200206165612069C6 -:10A3C00040F0400020613046FFF7D9FF216941F697 -:10A3D000FD721140216170BDF8B5064600204FF4B2 -:10A3E000005C00900D466046FFF7C9FF042816D1B7 -:10A3F0000E4C206940F00100206135806046FFF777 -:10A40000BEFF41F6FE77042806D1B61C280C009644 -:10A4100030806046FFF7B3FF216939402161F8BD04 -:10A420000249C860704700002301674500200240D0 -:10A43000AB89EFCD14481549026800608A4203D009 -:10A440001348804713480047134E4FF0090030600F -:10A450001248016821F07061016041020160104CF6 -:10A46000182020600F49104808601048D0F800D02C -:10A4700040680047FEE7FEE7FEE7FEE7FEE7FEE78F -:10A48000FEE7FEE7FEE7FEE7F04F0020EFBEADDEA1 -:10A49000B5940008ED0000081810024004000140C7 -:10A4A000140C0140000C01404434434400F0FF1FF1 -:10A4B0002A4910B588420AD1841401212046FFF7A9 -:10A4C000DCFB2046BDE810400021FFF7D6BB244945 -:10A4D000884202D10121041404E0224988420AD1B1 -:10A4E0000121C4132046FFF7D1FB2046BDE81040F0 -:10A4F0000021FFF7CBBB10BD30B502884C8802F4B9 -:10A5000041530A88CD8822438C882C4322430C89EE -:10A5100022434C8922438C892243CC8922431A430B -:10A520000280828B22F400628283098A018230BD1C -:10A530000029018802D041F0400101E021F04001F2 -:10A5400001807047818170478089704702460020F2 -:10A5500012890A4200D001207047000000300140FB -:10A5600000380040003C004000487047A0C9000887 -:10A57000A0F16101192900D8203870472DE9F05F5A -:10A58000994615460F4683464FF0FF36DDF828A062 -:10A5900011E0A819441009FB047080460146584692 -:10A5A00052469047002802D004DA254603E0404690 -:10A5B000BDE8F09F2646A5EB06000128E9DC002057 -:10A5C000F6E740EA01039B0703D009E008C9121F20 -:10A5D00008C0042AFAD203E011F8013B00F8013B5D -:10A5E000521EF9D27047D2B201E000F8012B491E89 -:10A5F000FBD270470022F6E710B513460A46044620 -:10A600001946FFF7F0FF204610BD421E12F8013F29 -:10A61000002BFBD111F8013B02F8013B002BF9D1D3 -:10A62000704730B505462A460B4612F8010B13F861 -:10A63000014B08B1A042F8D01CB1002802D06D1C1B -:10A64000F1E7284630BD10B5044604E00B7800F869 -:10A65000013B03B1491C521EF8D2204610BDCAB2BC -:10A66000401E10F8011F8A4202D00029F9D10020B3 -:10A670007047421C10F8011B0029FBD1801A70475B -:10A680002DE9F0410546002090460E46044600E0C4 -:10A69000641C44450BD2285D00F058F90746305D34 -:10A6A00000F054F9381A02D1295D0029F0D1BDE833 -:10A6B000F08170B5064600F0F3FA046805460A22F8 -:10A6C0000021304600F048F92C6070BDF0B480EAFB -:10A6D0000102D40F4200B2EB410F02D202460846FB -:10A6E00011464A0042D0C30DDDB2C1F3C752AD1AC4 -:10A6F000202D35DAC1F3160141F4000204B15242B3 -:10A70000C5F1200602FA06F12A411044B3EBD05FEE -:10A7100023D0C4B1012DA0EBC35009DCF0BC4FF035 -:10A72000004202EAC35200F50000DBB200F055B966 -:10A73000400000F1807000EBC350A0F1807040EA4F -:10A74000D170490009E0490841EAC071A0EBC3504B -:10A7500000F50000400800EBC350F0BC00F034B935 -:10A760006142012202EB4101001BF6E7F0BC704799 -:10A7700081F00041AAE780F00040A7E780EA0102EB -:10A7800010B502F00043400026D04A0023D04FEA23 -:10A79000106101EB1261C0F35600C2F3560240F49F -:10A7A000000042F40002A0FB0220A1F17F014FEA69 -:10A7B0000040140401D000F1010050EA124001D41D -:10A7C0004000491EC2B20C0604EBD010401C4008E9 -:10A7D000802A02D003E0002010BD20F001000029F3 -:10A7E00000DA0020184310BD30B480EA010202F004 -:10A7F000004530F0004221F0004015D0A0B1C0F378 -:10A80000C753C2F3C754C2F31601C0F31600E41ACB -:10A8100041F4000140F400027D34914201D3641CF4 -:10A8200000E04900002C02DA30BC002070474FF4F1 -:10A8300000000023914201D3891A034340084FEAE4 -:10A840004101F7D151B1914202D14FF0004105E0F1 -:10A8500002D24FF0010101E06FF0010103EBC4509F -:10A86000284430BC00F0B0B8420005D0C0F3C75255 -:10A870005242914201DC0020704700EBC15070470A -:10A88000C10F80EAE0700844CA079623002100F057 -:10A89000A4B896230022114600F09FB800F00042B1 -:10A8A00020F00040C10DC0F3160040F400007F29E5 -:10A8B00001DA00207047962903DCC1F19601C840F7 -:10A8C00001E096398840002AF4D04042704720F0D9 -:10A8D0000040C10DC0F3160040F400007F2901DAEA -:10A8E00000207047962903DCC1F19601C8407047EB -:10A8F0009639884070470000002801DBC0F1004015 -:10A90000002901DBC1F1004181427047002801DBD1 -:10A91000C0F10040002901DBC1F1004188427047CD -:10A9200030B50B46014600202022012409E021FA1F -:10A9300002F59D4205D303FA02F5491B04FA02F51C -:10A940002844151EA2F10102F1DC30BDA0F1410145 -:10A95000192900D8203070472DE9F04791460F465D -:10A9600080460446002614F8015B2DB1FFF7FCFD7C -:10A970000068405DC007F6D12B2D02D02D2D18D0D8 -:10A98000641E4A463946204600F0DAF827B1396895 -:10A99000A14201D1C7F8008071054FF002040BD528 -:10A9A0004042002803DD00F07BF90460A007BDE809 -:10A9B000F08746F48066E4E70028F8DA00F070F9E2 -:10A9C00004606FF00040F2E70029A8BF7047401C08 -:10A9D000490008BF20F00100704710B4B0FA80FCB5 -:10A9E00000FA0CF050EA010404BF10BC704749B1F2 -:10A9F000CCF1200421FA04F411FA0CF118BF012162 -:10AA000021430843A3EB0C01CB1D0106000A002BD8 -:10AA1000BEBF002010BC704700EBC350104400299B -:10AA2000A4BF10BC7047401C490008BF20F00100C3 -:10AA300010BC7047F0B4002802DCF0BC0020704766 -:10AA4000C0F3C751C0F3160040F40000CA0701D19B -:10AA50004000491E3F2202EB6105002211464FF4DF -:10AA6000000626FA01F31344D418844201D8001BCF -:10AA70001A464000491C1729F3DD5100814202D2D9 -:10AA80004FF0FF3100E0002102EBC550F0BCFFF7B2 -:10AA90009BBF10B541000CD0C0F3C751962908DC0C -:10AAA0007E2909DC06DB410204D000F0004040F0C2 -:10AAB0007E5010BD002010BDC1F19604C4F12001EC -:10AAC00000FA01F1E040FFF77FFFA04010BD10B594 -:10AAD00000F0004420F00040C20DC0F3160040F426 -:10AAE00000007F2A07DA7D2A00DA7D22763A00FA12 -:10AAF00002F1002008E0962A09DCA2F1760100FAB2 -:10AB000001F1C2F19602D040FFF75EFF01E0963AF4 -:10AB10009040002C00D0404210BD0000064C074D74 -:10AB200006E0E06840F0010394E80700984710341D -:10AB3000AC42F6D3F5F7DEFAB0D20008D0D2000866 -:10AB40002DE9F05F82460078002715468B460AF112 -:10AB50000104B946302801D09DB113E014F8010B6F -:10AB60000127782803D0582801D045B10AE00DB15B -:10AB7000102D07D10027102514F8010B02E008253D -:10AB800000E00A250026B0460EE005FB080005FBA4 -:10AB900006F1012701EB10461FFA80F8B6F5803F59 -:10ABA00000D3B94614F8010B294600F018F8002824 -:10ABB000EBDABBF1000F05D00FB1641E00E0544684 -:10ABC000CBF80040B9F1000F06D000F069F802217F -:10ABD0000160C81EBDE8F09F48EA0640FAE73A283F -:10ABE00000D2303820F02002412A01D3A2F13700F0 -:10ABF000884201D34FF0FF30704770B501EB02047B -:10AC000010F8015B15F0070301D110F8013B2A1180 -:10AC100006D110F8012B03E010F8016B01F8016B6D -:10AC20005B1EF9D12B0705D40023521E0FD401F867 -:10AC3000013BFAE710F8013B02F10202A1EB03032A -:10AC400003E013F8015B01F8015B521EF9D5A14244 -:10AC5000D6D3002070BD00000FB4054B10B503A97A -:10AC6000044A029800F0E8F810BC5DF814FB0000FC -:10AC7000C92200082C0400204100080218BF04204B -:10AC80000A0E18BF40F001004FF07F4232EA010186 -:10AC900008BF40F00200012808BF052070470000EF -:10ACA00000487047300400206FF05E010807FFF78E -:10ACB000DBBD00002DE9F04D0E4614464FF07F41FC -:10ACC000B1EB440F9EBF4FF0FF313160BDE8F08D16 -:10ACD0004FF0004040EA0421C4F3C75078384311D4 -:10ACE00000F01F00DFF814C1C0F12002FC445CF842 -:10ACF00023500CEB83038540D3F804C02CFA02F7F1 -:10AD00002F439D680CFA00FC25FA02F8DB6805FA6F -:10AD100000F023FA02F240EA02054CEA080CA7FB15 -:10AD20000132ACFB01C0A5FB015101EB0C058D42CA -:10AD300034BF4FF0010C4FF0000CC1186144BCF15E -:10AD4000000F02D0814202D903E0814201D20120EA -:10AD500000E00020104400F120024FEA9218800623 -:10AD6000CA0C40EA42304F03C6F80080FFF788FD66 -:10AD700082463846FFF78DFD6FF01201FFF774FD34 -:10AD800007462846FFF785FD6FF02501FFF76CFDAC -:10AD9000834639465046FFF799FC5946FFF796FC23 -:10ADA00000F500656FF30B0551462846FFF7E0FC00 -:10ADB0003946FFF7DDFC5946FFF7DDFC1049FFF788 -:10ADC000DDFC07460F492846FFF7D8FC3946FFF758 -:10ADD0007DFC07460C492846FFF7D0FC3946FFF7B3 -:10ADE00075FC14F0004F08BFBDE8F08DC8F180512C -:10ADF00080F000403160BDE8F08D0000B41C000020 -:10AE0000DB0FC92F22AAFD290000C92F02E008C8C4 -:10AE1000121F08C1002AFAD170477047002001E0D4 -:10AE200001C1121F002AFBD17047000001490860D0 -:10AE300070470000300400202DE9FF4F8BB09A4688 -:10AE40000F4605460026C9E0252837D100246D1C91 -:10AE50006649A04601222B78203B02FA03F0084203 -:10AE600002D004436D1CF6E728782E2817D115F878 -:10AE7000010F44F004042A280ED06FF02F02287826 -:10AE8000A0F1300109290AD808EB880102EB410141 -:10AE900000EB01086D1CF2E757F8048B6D1C287855 -:10AEA00069283FD006DC002871D063280CD06428C4 -:10AEB00004D137E0732811D075284ED052460D9931 -:10AEC000904706F1010688E017F8040B8DF80000A2 -:10AED00000208DF80100E946012003E057F8049BAB -:10AEE0004FF0FF3061074FF0000401D40AE0641C0A -:10AEF00044450DDA8442FADB19F804100029F6D132 -:10AF000006E0641C8442FCDB19F804100029F8D127 -:10AF1000264404E019F8010B52460D999047641E2F -:10AF2000F8D25AE001CF4FF00A0B002804DAC0F142 -:10AF300000004FF02D0102E0210504D52B218DF8F2 -:10AF40002410012103E0E10705D02021F7E70DF1EE -:10AF5000200908910CE00021F9E701CF4FF00A0B1E -:10AF6000F9E75946FFF7DCFC01F1300209F8012D41 -:10AF70000028F6D1ADEB090000F1200B600701D4E9 -:10AF80004FF00108D84503DDA8EB0B0001E029E0F4 -:10AF900000208046002406E009A85246005D0D9975 -:10AFA0009047761C641C08988442F5DB04E030204E -:10AFB00052460D999047761CB8F10001A8F101089E -:10AFC000F5DC05E019F8010B52460D999047761C07 -:10AFD000BBF10001ABF1010BF4DC6D1C28780028FB -:10AFE0007FF432AF0FB03046BDE8F08F0928010082 -:10AFF0002DE9F0474FF0684202EB40030C4605464E -:10B00000B3F1654F3CBF02EB4102B2F1654F3FD354 -:10B010004FF07F42B2EB400F28BFB2EB410F03D29B -:10B02000BDE8F047FFF752BB40EA01035B0008BFF1 -:10B0300044F0FF410AD0B2EB400F08BFB2EB410F22 -:10B0400006D125F0804024F0804105460C461FE0E3 -:10B05000B2EB400F12BF5FEA410245F0FF4004F03F -:10B06000004115D04FEA410292EA400310D4002A71 -:10B07000B4BF4FF03E564FF09F463146FFF77EFB80 -:10B08000054631462046FFF779FB0446284621460F -:10B09000C0F3C753C1F3C7529A1A1B2A06DD10F03A -:10B0A000004F14BF54485548BDE8F08712F11A0FFD -:10B0B00017DA11F0004F06D010F0004F0CBF5048C7 -:10B0C0005048BDE8F08721462846FFF78DFB04462F -:10B0D000FFF7D2FD042808BFFFF7E6FD2046BDE8D4 -:10B0E000F0874200B2EB410F25D910F0004F19BF95 -:10B0F000454F464E464F474E224685F00044154682 -:10B100000A4680F0004110460A1A5200B2F1807FD0 -:10B110003ED248404049DFF804A110F0004F18D05B -:10B120004FF03F483846FFF723FB0746514630466D -:10B13000FFF71EFB17E011F0004F04BF0026374653 -:10B14000E2D010F0004F19BF354F364E364F374E14 -:10B15000DAE74FF07C583846FFF7B8FA0746514611 -:10B160003046FFF7B3FA064641462846FFF706FB8E -:10B170002146FFF7ABFA824621464046FFF7FEFA2A -:10B180002946FFF7F8FA5146FFF72EFB044604E084 -:10B1900021462846FFF728FB04460146FFF7EEFA52 -:10B1A00080462349FFF7EAFA2249FFF78FFA414622 -:10B1B000FFF7E4FA2049FFF789FA4146FFF7DEFA84 -:10B1C0001E49FFF783FA4146FFF7D8FA1C49FFF7FB -:10B1D0007DFA054641462046FFF7D0FA2946FFF79B -:10B1E000CDFA3146FFF772FA2146FFF76FFA39467A -:10B1F000BDE8F047FFF76ABADB0FC9BFDB0FC93FF5 -:10B20000DB0F4940DB0F49C00000C9BF22AAFDB9CE -:10B210000000C93F22AAFD390060ED3EC30ACE37C7 -:10B22000000049C022AA7DBA0000494022AA7D3A06 -:10B230002DAD65BD8FB8D53D0FB511BE61C84C3E73 -:10B24000A8AAAABE2DE9F84304460246504869461A -:10B25000B0EB420F09D94FF0E640B0EB420F94BF7C -:10B2600000204FF0FF30009034E04A4B22F00040C5 -:10B2700083422BD948492046FFF780FAFFF709FCA3 -:10B280008046FFF70BFB00F0030000904349404667 -:10B29000FFF774FA054642494046FFF76FFA064643 -:10B2A00040494046FFF76AFA07463F494046FFF7E4 -:10B2B00065FA2146FFF75FFA3946FFF759FA31463A -:10B2C000FFF756FA2946FFF753FA02E01046FFF758 -:10B2D000F1FC04462546009C002C18DA6800B0F109 -:10B2E0007F4F3CBF4FF07E50BDE8F88309D14FF04F -:10B2F0000100FFF79BFDBDE8F84300210846FFF77A -:10B3000073BA2846BDE8F8430121FFF7ADBA2946D4 -:10B3100014F0010F08461CD0FFF730FA0646234907 -:10B32000FFF72CFA2249FFF726FA3146FFF726FAF3 -:10B330002049FFF7CBF93146FFF720FA2946FFF7FE -:10B340001DFA2946FFF7C2F914F0020F1CD0BDE820 -:10B35000F883FFF713FA05461749FFF70FFA174965 -:10B36000FFF7B4F92946FFF709FA1549FFF7AEF9D7 -:10B370002946FFF703FA4FF07E51FFF7A7F914F0C3 -:10B38000020F08BFBDE8F88380F00040BDE8F883F5 -:10B39000B61F927E490E494683F9223F1A61342C2A -:10B3A0000020A23300A0FD390000C93F336D4C39A5 -:10B3B000DA82083CA0AA2ABEB93AB2BACA9F2A3D8C -:10B3C000DDFFFFBE2DE9F04104464FF019404E4924 -:10B3D000002500EB4400884230D94FF0FF4131EAAC -:10B3E000040018D04FF0CE41B1EB440F84BF4FF0B2 -:10B3F0007E50BDE8F0814549B1EB440F28BF0125DF -:10B400001CD20220FFF712FD14F0004F0FD0BDE850 -:10B41000F041FFF749BC204614F5000F04BF00209F -:10B42000BDE8F0810121BDE8F041FFF71DBABDE89C -:10B43000F04161214FF0E040FFF716BA3449204651 -:10B44000FFF79CF9FFF725FB8046FFF727FA064632 -:10B4500030494046FFF792F907462F494046FFF72B -:10B460008DF92146FFF787F93946FFF781F9044640 -:10B470002A49FFF783F92A49FFF728F92146FFF700 -:10B480007DF96FF04141FFF721F92146FFF776F989 -:10B490002449FFF71BF92146FFF770F901462248BE -:10B4A00006F00304784450F82400FFF767F91F49B9 -:10B4B000794451F82410FFF709F91D49794451F8EE -:10B4C0002410FFF703F9B110D5B1FFF7CDF904004F -:10B4D0000BD0B4F1FF4F0FD0FFF7CEFB042808BF0D -:10B4E000FFF7E2FB2046BDE8F0810220FFF79EFC5B -:10B4F000BDE8F041FFF7D8BB0220FFF797FC96E7C5 -:10B50000BDE8F041FFF7B0B90000501E0000A08573 -:10B510003BAAB840F4FD05370070313E12BB2A3D0E -:10B5200012BB2A3EFFFF7F3F2414000008140000D6 -:10B53000EC1300002DE9F0410026A0F50001B1F167 -:10B54000FE4F22D34FF07F42B2EB400F04D2BDE852 -:10B55000F0410121FFF788B9B0F1FF4F08BFBDE806 -:10B56000F081B0F1004F08D90120FFF75FFCBDE882 -:10B57000F04100210846FFF737B930F000415ED0B6 -:10B580006FF016061721FFF76FF900F500226FF034 -:10B590007E0101EBE251C2F3025477184FF07E5264 -:10B5A000A0EBC15602EB045557EA040050D02946DF -:10B5B0003046FFF78BF8804629463046FFF7D8F82B -:10B5C0004146FFF711F905460146FFF7D7F88046D7 -:10B5D0003349FFF7D3F83349FFF778F80646414679 -:10B5E0002846FFF7CBF83146FFF7C8F8064638463D -:10B5F000FFF746F907462C49FFF7C0F82B49794475 -:10B6000051F82410FFF762F83146FFF75FF806465D -:10B6100001212846FFF728F93146FFF757F805467C -:10B6200038462349FFF7AAF82249794451F82410F3 -:10B63000FFF74CF82946BDE8F041FFF747B8022074 -:10B64000FFF7F4FBBDE8F04100211B48FFF7CCB841 -:10B650004FF07E513046FFF78BF805461749FFF74C -:10B660008DF81749FFF732F82946FFF787F8154993 -:10B67000FFF72CF82946FFF781F86FF08241FFF7BA -:10B6800025F8044629460846FFF778F82146FFF7D3 -:10B6900075F801462846BDE8F041FFF717B80000ED -:10B6A00066F1CC3EAAAA2A3FF4FD0538FA12000042 -:10B6B0000070313FAE120000000080BF21ED423E1D -:10B6C0000A1180BEC1ABAA3E70B50546FFF7FFF96F -:10B6D00004464000801C0DD12846FFF7DAF90546E4 -:10B6E0002046FFF7CDF82946FFF706F91CBF0120D9 -:10B6F000FFF79CFB204670BD2DE9F8430446024647 -:10B7000053486946B0EB420F09D94FF0E640B0EB21 -:10B71000420F94BF00204FF0FF30009034E04D4BBB -:10B7200022F0004083422BD94B492046FFF726F8F0 -:10B73000FFF7AFF98046FFF7B1F800F00300009083 -:10B7400046494046FFF71AF8054645494046FFF787 -:10B7500015F8064643494046FFF710F807464249A8 -:10B760004046FFF70BF82146FFF705F83946FEF78C -:10B77000FFFF3146FEF7FCFF2946FEF7F9FF02E026 -:10B780001046FFF797FA04462546009C002C1DDA68 -:10B790006800B0F17F4F09D22846FFF76DFA042800 -:10B7A00008BFFFF781FA2846BDE8F88308D10120D9 -:10B7B000FFF73CFBBDE8F84300210846FFF714B84B -:10B7C0002846BDE8F8430121FFF74EB8294614F09A -:10B7D000010F08461ED0FEF7D1FF05462349FEF7AC -:10B7E000CDFF2349FEF772FF2946FEF7C7FF214927 -:10B7F000FEF76CFF2946FEF7C1FF4FF07E51FEF7C2 -:10B8000065FF14F0020F08BFBDE8F88380F0004028 -:10B81000BDE8F883FEF7B2FF06461749FEF7AEFF14 -:10B820001649FEF7A8FF3146FEF7A8FF1449FEF7B8 -:10B830004DFF3146FEF7A2FF2946FEF79FFF29463E -:10B84000FEF744FF14F0020FE0D1BDE8F8830000DA -:10B85000B61F927E490E494683F9223F1A61342C65 -:10B860000020A23300A0FD390000C93FB93AB2BAA6 -:10B87000CA9F2A3DDDFFFFBE336D4C39DA82083C9A -:10B88000A0AA2ABE70B50546FFF7D4F8044620F0FA -:10B890000040C0F1FF40C00F08D025F00040C0F1CB -:10B8A000FF40C00F04BF0120FFF7C0FA204670BD63 -:10B8B00053CA0008A3CA0008E9CA000850CA000811 -:10B8C00057CA0008F9C90008F4C9000844CA0008AA -:10B8D000E9C90008E3CA0008FCC90008B4CA0008A6 -:10B8E000F8CA000813CA000881CA000820CA000864 -:10B8F000E2C900087ACA0008000000008FCA0008E8 -:10B90000D3CA00085ECA0008EFCA0008A9CA000826 -:10B91000D8CA00082CCA00083BCA0008CFCA0008D1 -:10B920000ACA0008BECA000802CB0008C4CA000840 -:10B9300093CA000807CA00086FCA00080000000088 -:10B940009ECA000803CA000899CA00081CCA000859 -:10B95000BECA0008CFCA00080000000031D10008AC -:10B96000ECC90008D3C90008F1D00008DBC9000801 -:10B9700053CC0008000000000CD100089FD0000844 -:10B980003303000807D1000899CF00088703000897 -:10B99000ECCF00084DD00008A906000869CF0008C8 -:10B9A00080CE00085B0700081AD0000831D10008DB -:10B9B000D10800087CCC0008EBCD0008F108000895 -:10B9C00064CF000831D10008BD09000860CF00082D -:10B9D0006ECF0008E9090008A7CF00086AD0000868 -:10B9E000730C000804CC0008C4C90008F70C000858 -:10B9F000F1CC00083DD00008AB08000816D00008C4 -:10BA00007DD00008310D00080FD0000803D00008D9 -:10BA1000710E0008BDCE000831D100081B0F0008D0 -:10BA20004ACC000802000000700400200000000062 -:10BA30002823000016CB0008020000007805002033 -:10BA4000B0040000A406000032CC00080200000090 -:10BA50003405002000000000D00700003ECC0008A4 -:10BA6000020000003605002000000000D0070000A2 -:10BA7000B4CB0008020000003805002000000000E0 -:10BA8000D00700009BCD0008020000007A050020CE -:10BA900000000000D0070000A4CD00080200000054 -:10BAA0007C05002000000000D0070000E2D0000864 -:10BAB000020000003A05002000000000D00700004E -:10BAC0006CCD0008020000003C05002000000000D2 -:10BAD000D00700001CCB0008020000003E0500203B -:10BAE00000000000D00700000CCC0008020000009D -:10BAF0004005002000000000D0070000ABCC00088B -:10BB0000020000004205002032000000F2010000A7 -:10BB10009CCC000802000000440500203200000018 -:10BB2000F201000073CE0008000000007E05002036 -:10BB30000000000001000000CCCC00080400000060 -:10BB400084050020B004000000C20100C8CC000839 -:10BB5000040000008805002080250000004B000044 -:10BB600045CB0008000000008C050020000000000C -:10BB70000100000058CC00080000000080050020F3 -:10BB80000000000003000000DCCC00080100000001 -:10BB900081050020FFFFFFFF0400000061CC0008CA -:10BBA00000000000760500200000000002000000F8 -:10BBB000BCCD0008000000008D0500200000000042 -:10BBC00001000000FACB0008000000006A05002018 -:10BBD0000A000000C8000000D2CB000800000000EE -:10BBE0006B0500200A00000032000000BFCB0008F7 -:10BBF000000000006C0500200A0000003200000078 -:10BC0000FFCD0008000000006D05002000000000CE -:10BC10000900000024CF00080000000046050020B5 -:10BC200000000000080000000CCB0008000000002D -:10BC30004705002000000000080000001CCD00089F -:10BC4000000000004805002000000000080000007F -:10BC500046CE0008030000004A0500204CFFFFFF0D -:10BC6000680100003BCD0008030000004C050020E7 -:10BC70004CFFFFFF68010000C6D000080300000071 -:10BC80004E0500204CFFFFFF68010000D5CE0008E4 -:10BC90000100000050050020FFFFFFFF0100000031 -:10BCA0006FCC0008000000005105002000000000DB -:10BCB0000500000061CB0008000000005C050020CA -:10BCC000000000008000000013CD0008020000000A -:10BCD000520500200000000000010000BCCF000859 -:10BCE000020000005405002064000000E80300008A -:10BCF000CDCF0008020000005605002064000000BF -:10BD0000E80300008ACF000800000000E0070020E0 -:10BD10000000000001000000ABCB000800000000A4 -:10BD2000460800200000000020000000A8CB00080A -:10BD30000000000047080020000000006400000030 -:10BD4000D1CD0008000000004808002001000000DC -:10BD5000FA000000E5CB00080000000049080020C0 -:10BD60000000000001000000F9CE00080000000003 -:10BD70004A080020000000006400000084CC000895 -:10BD800000000000FF07002000000000FA00000093 -:10BD900013CF000800000000000800200000000091 -:10BDA0006400000059CB00080000000001080020DA -:10BDB00000000000640000001BCF0008000000002D -:10BDC0000208002000000000FA0000008CCC0008EF -:10BDD00000000000030800200000000064000000D4 -:10BDE000E9CC00080000000004080020000000006A -:10BDF0006400000010D10008000000008C08002042 -:10BE000000000000C80000001FD100080000000072 -:10BE10008D08002000000000C800000020CC0008B1 -:10BE2000020000008E080020E8030000D007000098 -:10BE300071CB0008020000009008002064000000A0 -:10BE4000D007000011CE0008010000007F0500208F -:10BE50000000000004000000EBCE0008010000001C -:10BE600092080020FFFFFFFF010000002FCF000815 -:10BE70000100000093080020000000000100000005 -:10BE8000DFCF000800000000940800200000000040 -:10BE9000FF000000ADCF0008000000000C080020EB -:10BEA00000000000FA0000008BCB0008000000003A -:10BEB0000E08002000000000640000009ACB00087B -:10BEC000000000000D0800200000000064000000D9 -:10BED000ADCD0008000000001C080020000000009C -:10BEE0000100000055CD0008030000000A080020F2 -:10BEF000D4FEFFFF2C0100005ECE0008030000000E -:10BF000008080020D4FEFFFF2C010000F6CC00083A -:10BF1000000000000F0800200000000030000000BA -:10BF200004CD0008050000001008002000000000FB -:10BF30000100000022CE00080500000014080020C7 -:10BF4000000000000100000025D0000805000000EE -:10BF5000180800200000000001000000C5CE000805 -:10BF60000300000006080020B0B9FFFF50460000A3 -:10BF70004CCF000800000000E50700200000000092 -:10BF8000C800000087CD000800000000EF07002077 -:10BF900000000000C800000031CB000800000000D5 -:10BFA000F907002000000000C800000041CF000891 -:10BFB00000000000E607002000000000C8000000AC -:10BFC0007CCD000800000000F00700200000000009 -:10BFD000C800000026CB000800000000FA0700207F -:10BFE00000000000C800000056CF0008000000005C -:10BFF000E707002000000000C800000091CD000805 -:10C0000000000000F107002000000000C800000050 -:10C010003BCB000800000000FB07002000000000F0 -:10C02000C8000000F5CF00080200000096080020BC -:10C0300000000000D007000026CD0008000000002E -:10C040009A0800200000000001000000AFCE0008A8 -:10C05000020000009C0800200A000000D007000039 -:10C06000F9D00008020000009E0800200A0000002D -:10C07000D0070000BACC000800000000990800209A -:10C08000000000006400000064CD00080000000013 -:10C09000E207002000000000C80000004DCD0008AD -:10C0A00000000000EC07002000000000C8000000B5 -:10C0B00045CD000800000000F60700200000000049 -:10C0C000C80000006CCE000800000000E10700205E -:10C0D00000000000C800000057CE0008000000006B -:10C0E000EB07002000000000C800000050CE000850 -:10C0F00000000000F507002000000000C80000005C -:10C10000DCD0000800000000E30700200000000071 -:10C11000C8000000D6D0000800000000ED07002095 -:10C1200000000000C8000000D0D00008000000009F -:10C13000F707002000000000C800000037D000080A -:10C1400000000000E407002000000000C80000001C -:10C1500031D0000800000000EE07002000000000C1 -:10C16000C80000001FD0000800000000F8070020F1 -:10C1700000000000C80000003ECE000800000000E3 -:10C18000E807002000000000C800000036CE0008CC -:10C1900000000000F207002000000000C8000000BE -:10C1A0002ECE000800000000FC0700200000000068 -:10C1B000C8000000414552543132333400000000C1 -:10C1C0000000803F00000000A8AAAA3F0000000075 -:10C1D0000000803F000080BFB0AA2ABF000000001E -:10C1E0000000803F0000803FB0AA2ABF000000008E -:10C1F0000000803F000000000000803F000080BF82 -:10C200000000803F000080BF000000000000803F71 -:10C210000000803F0000803F000000000000803FE1 -:10C220000000803F00000000000080BF000080BFD1 -:10C230000000803F000080BF0000803F000080BF02 -:10C240000000803F000080BF000080BF0000803FF2 -:10C250000000803F0000803F0000803F0000803FE2 -:10C260000000803F0000803F000080BF000080BFD2 -:10C270000000803F0000803F000000000000000040 -:10C280000000803F000080BF0000000000000000B0 -:10C290000000803F00000000A8AAAA3F0000803FE5 -:10C2A0000000803F000080BFB0AA2ABF000080BF0E -:10C2B0000000803F0000803FB0AA2ABF000080BF7E -:10C2C0000000803F00000000A8AAAA3F000080BF35 -:10C2D0000000803F000080BFB0AA2ABF0000803F5E -:10C2E0000000803F0000803FB0AA2ABF0000803FCE -:10C2F0000000803F000080BFD0B35D3F0000803F62 -:10C300000000803F000080BFD0B35DBF000080BF51 -:10C310000000803F0000803FD0B35D3F0000803FC1 -:10C320000000803F0000803FD0B35DBF000080BFB1 -:10C330000000803F00000000D0B35DBF0000803FE0 -:10C340000000803F00000000D0B35D3F000080BFD0 -:10C350000000803F000000000000803F000080BF20 -:10C360000000803F000080BF000080BF0000000090 -:10C370000000803F000000000000803F0000803F80 -:10C380000000803F0000803F000080BF00000000F0 -:10C390000000803FD0B35DBF0000803F0000803FC1 -:10C3A0000000803FD0B35DBF000080BF0000803F31 -:10C3B0000000803FD0B35D3F0000803F000080BFA1 -:10C3C0000000803FD0B35D3F000080BF000080BF11 -:10C3D0000000803FD0B35DBF00000000000080BFC0 -:10C3E0000000803FD0B35D3F000000000000803FB0 -:10C3F0000000803F000080BF0000803F000080BF41 -:10C400000000803F000080BF000080BF0000803F30 -:10C410000000803F0000803F0000803F0000803F20 -:10C420000000803F0000803F000080BF000080BF10 -:10C430000000803F000080BF0000803F0000803F80 -:10C440000000803F000080BF000080BF000080BF70 -:10C450000000803F0000803F0000803F000080BF60 -:10C460000000803F0000803F000080BF0000803F50 -:10C470000000803FF704353FF70435BF0000803FE0 -:10C480000000803FF70435BFF70435BF0000803F50 -:10C490000000803FF70435BFF704353F0000803FC0 -:10C4A0000000803FF704353FF704353F0000803F30 -:10C4B0000000803F00000000000080BF000080BF3F -:10C4C0000000803F000080BF00000000000080BF2F -:10C4D0000000803F000000000000803F000080BF9F -:10C4E0000000803F0000803F00000000000080BF8F -:10C4F0000000803F0000803F000000BF0000803F40 -:10C500000000803F000000BF000080BF0000803FAF -:10C510000000803F000080BF0000003F0000803F1F -:10C520000000803F0000003F0000803F0000803F8F -:10C530000000803F0000003F000080BF000080BF7F -:10C540000000803F000080BF000000BF000080BFEF -:10C550000000803F000000BF0000803F000080BF5F -:10C560000000803F0000803F0000003F000080BFCF -:10C570000000803F000000000000803F0000803F7E -:10C580000000803F000080BF000080BF000000006E -:10C590000000803F000000000000803F000080BFDE -:10C5A0000000803F0000803F000080BF000000804E -:10C5B000000000000000000003010000C0C10008EE -:10C5C00004000000F0C100080400000030C20008B0 -:10C5D0000201000070C2000800010000000000001D -:10C5E0000600000090C2000806000000F0C200082B -:10C5F00001010000000000000400000050C300081A -:10C600000600000090C3000808000000F0C3000806 -:10C610000800000070C4000808000000F0C4000812 -:10C620000101000000000000000100000000000007 -:10C6300000010000000000000400000070C50008B8 -:10C640000000000000000000524F4C4C3B50495489 -:10C6500043483B5941573B414C543B506F733B500F -:10C660006F73523B4E6176523B4C4556454C3B4DA9 -:10C6700041473B56454C3B0000C2010078D20008C0 -:10C680009BD2000800E1000056D2000842D2000808 -:10C69000009600000CD200082ED20008004B0000CB -:10C6A000EAD10008D6D100088025000031D1000869 -:10C6B00031D10008B56206010300F00500FF19B58D -:10C6C0006206010300F00300FD15B56206010300D8 -:10C6D000F00100FB11B56206010300F00000FA0F43 -:10C6E000B56206010300F00200FC13B56206010307 -:10C6F00000F00400FE17B562060103000102010EFE -:10C7000047B562060103000103010F49B562060146 -:10C710000300010601124FB5620601030001120178 -:10C720001E67B562061608000307030051080000E3 -:10C730008A41B56206080600C80001000100DE6AF1 -:10C740001048494A4B4C4D44454647FF202122237F -:10C750002425262748494A4B4C4DFF1048498A8BCF -:10C760008C8D84858687FF20212223242526274837 -:10C77000498A8B8C8DFF00004CC7000840C7000819 -:10C7800067C700085BC70008000C014008001002E2 -:10C79000000C0140100010020008014000101402BB -:10C7A00025820008C1810008F58100084381000846 -:10C7B000DB8100080000004000080140010000008B -:10C7C000001C0000000000400008014002000000C2 -:10C7D000041C0000000000400008014004000000AC -:10C7E000081C000000000040000801400800000094 -:10C7F0000C1C000000040040000801404000000044 -:10C80000001D0000000400400008014080000000FE -:10C81000041D000000040040000C01400100000065 -:10C82000081D000000040040000C01400200000050 -:10C830000C1D0000002C0140000801400001000018 -:10C84000001B0100002C014000080140000800000E -:10C850000C1B010000080040000C014040000000DB -:10C86000001E000000080040000C01408000000095 -:10C87000041E000000080040000C01400001000000 -:10C88000081E000000080040000C014000020000EB -:10C890000C1E00000004080C7B9300083393000872 -:10C8A0005593000893930008079200080000803F0A -:10C8B0000030983F0000B53F0040D73F0000000027 -:10C8C000320A7E397F661E395B991F390000803F2E -:10C8D000F037983FF304B53FFD44D73F0000000018 -:10C8E0000030F13D0070643E0000A33E0090CF3E5A -:10C8F0000090F83E00400F3F00E0203F00000000A5 -:10C9000015B78337CDE37B380EE1C53860F6913833 -:10C91000AF5F0F38E1BC3E3823F447390040404058 -:10C920004040404040404141414141404040404002 -:10C9300040404040404040404040404040050202AE -:10C94000020202020202020202020202022020206D -:10C9500020202020202020020202020202029090C9 -:10C9600090909090101010101010101010101010C7 -:10C97000101010101010101002020202020288881B -:10C980008888888808080808080808080808080827 -:10C99000080808080808080802020202400000000F -:10C9A0001DC90008000000006E83F9A22915444E3D -:10C9B000D15727FCC0DD34F5999562DB4190433CAB -:10C9C000AB6351FE696E64657820283020746F2057 -:10C9D0003229004D50553630353000424D41323805 -:10C9E0003000565441494C34005934004144584CAD -:10C9F0003334350048455836005936004F43544FBC -:10CA0000583800414343003344004641494C5341A8 -:10CA1000464500414952504C414E45004D4147006A -:10CA200048454C495F39305F444547004759524FAC -:10CA30005F534D4F4F5448494E47004C45445F5259 -:10CA4000494E4700464C59494E475F57494E4700AB -:10CA50004249005452490047494D42414C00494E19 -:10CA6000464C494748545F4143435F43414C005360 -:10CA70004F465453455249414C00435553544F4D32 -:10CA80000048454C495F3132305F4343504D0050C0 -:10CA9000504D00564152494F004241524F004759B4 -:10CAA000524F005155414450004D4F544F525F5327 -:10CAB000544F50004F43544F464C41545000534F35 -:10CAC0004E415200504F5745524D45544552004734 -:10CAD0005053005642415400534552564F5F5449FB -:10CAE0004C5400484558365800515541445800535D -:10CAF000455249414C5258004F43544F464C4154C3 -:10CB0000580054454C454D4554525900616C696775 -:10CB10006E5F616363006D69647263006E65757456 -:10CB200072616C3364006770735F706F73725F64FF -:10CB3000006770735F706F735F64006770735F6E20 -:10CB400061765F6400736F667473657269616C5FB0 -:10CB5000696E766572746564007468725F6D69648D -:10CB6000006D6F726F6E5F7468726573686F6C646E -:10CB7000006661696C736166655F646574656374A2 -:10CB80005F7468726573686F6C6400616363787961 -:10CB90005F6465616462616E64006163637A5F64AF -:10CBA00065616462616E6400796177646561646285 -:10CBB000616E64006D696E636F6D6D616E640076A9 -:10CBC0006261746D696E63656C6C766F6C746167BD -:10CBD0006500766261746D617863656C6C766F6C0C -:10CBE0007461676500616C745F686F6C645F666137 -:10CBF00073745F6368616E67650076626174736306 -:10CC0000616C650070726F66696C65006465616473 -:10CC100062616E6433645F7468726F74746C650013 -:10CC20006661696C736166655F7468726F74746C59 -:10CC300065006D696E7468726F74746C65006D6107 -:10CC4000787468726F74746C65006C6F6F7074695F -:10CC50006D65004E6F6E65006770735F7479706507 -:10CC60000073657269616C72785F747970650061D8 -:10CC700063635F68617264776172650066656174A1 -:10CC80007572650072635F7261746500726F6C6CBF -:10CC90005F70697463685F72617465007365727652 -:10CCA0006F5F70776D5F72617465006D6F746F7226 -:10CCB0005F70776D5F72617465006E61765F736C33 -:10CCC00065775F7261746500736F6674736572690E -:10CCD000616C5F6261756472617465006770735F37 -:10CCE00062617564726174650079617772617465FF -:10CCF0000073617665006261726F5F7461625F7379 -:10CD0000697A65006261726F5F6E6F6973655F6CEF -:10CD10007066006779726F5F6C706600616C69673E -:10CD20006E5F6D6167006E61765F636F6E74726FC8 -:10CD30006C735F68656164696E6700616C69676EDA -:10CD40005F626F6172645F706974636800695F70CD -:10CD500069746368006163635F7472696D5F7069B1 -:10CD600074636800705F706974636800646561640F -:10CD700062616E6433645F68696768006770735FDF -:10CD8000706F73725F69006770735F706F735F6954 -:10CD9000006770735F6E61765F69006D696E6368CE -:10CDA00065636B006D6178636865636B00616363E5 -:10CDB0005F756E61726D656463616C0074656C654E -:10CDC0006D657472795F736F667473657269616C97 -:10CDD00000616C745F686F6C645F7468726F747408 -:10CDE0006C655F6E65757472616C006C697374203C -:10CDF0006F72202D76616C206F722076616C0070EE -:10CE00006F7765725F6164635F6368616E6E656CA6 -:10CE100000727373695F6175785F6368616E6E65D8 -:10CE20006C006261726F5F63665F76656C00645F61 -:10CE30006C6576656C00695F6C6576656C00705F2B -:10CE40006C6576656C00616C69676E5F626F6172BC -:10CE5000645F726F6C6C00695F726F6C6C00616311 -:10CE6000635F7472696D5F726F6C6C00705F726F7C -:10CE70006C6C0072657461726465645F61726D00F0 -:10CE80007072696E7420636F6E6669677572616235 -:10CE90006C652073657474696E677320696E2061B8 -:10CEA000207061737461626C6520666F726D006ED4 -:10CEB00061765F73706565645F6D696E007665723B -:10CEC00073696F6E006D61675F6465636C696E6145 -:10CED00074696F6E007961775F636F6E74726F6CE7 -:10CEE0005F646972656374696F6E007961775F640E -:10CEF0006972656374696F6E007468726F74746CC4 -:10CF0000655F616E676C655F636F7272656374699C -:10CF10006F6E0072635F6578706F007468725F6532 -:10CF200078706F00616C69676E5F6779726F00740B -:10CF300072695F756E61726D65645F736572766F3D -:10CF4000006770735F706F73725F70006770735FFC -:10CF5000706F735F70006770735F6E61765F7000F3 -:10CF60006D61700068656C700064756D70006D6156 -:10CF70007070696E67206F66207263206368616EEF -:10CF80006E656C206F72646572007069645F636FB8 -:10CF90006E74726F6C6C65720064657369676E2085 -:10CFA000637573746F6D206D69786572006163637A -:10CFB0005F6C70665F666163746F72006779726F31 -:10CFC0005F636D70665F666163746F72006779722C -:10CFD0006F5F636D70666D5F666163746F7200672B -:10CFE000696D62616C5F666C616773006465666140 -:10CFF000756C7473006770735F77705F72616469DA -:10D0000075730073686F772073797374656D20731F -:10D010007461747573007365740065786974006475 -:10D020005F616C74006261726F5F63665F616C74F4 -:10D0300000695F616C7400705F616C74007361768D -:10D040006520616E64207265626F6F740072657333 -:10D05000657420746F2064656661756C74732061FB -:10D060006E64207265626F6F74006D6978657220FE -:10D070006E616D65206F72206C697374006E616DF6 -:10D08000653D76616C7565206F7220626C616E6BB8 -:10D09000206F72202A20666F72206C69737400669C -:10D0A0006561747572655F6E616D65206175786626 -:10D0B0006C6167206F7220626C616E6B20666F72AC -:10D0C000206C69737400616C69676E5F626F617276 -:10D0D000645F79617700695F79617700705F79617A -:10D0E00077006465616462616E6433645F6C6F775E -:10D0F000004D4D4138343578006E61765F73706550 -:10D1000065645F6D617800636D69780061757800B2 -:10D110006661696C736166655F64656C6179006600 -:10D1200061696C736166655F6F66665F64656C619B -:10D13000790043414D535441423B0043414C4942E5 -:10D140003B0047505320484F4C443B004845414426 -:10D15000465245453B00414E474C453B00475053E6 -:10D1600020484F4D453B004D41473B0043414D5406 -:10D170005249473B004845414441444A3B004152E3 -:10D180004D3B00484F52495A4F4E3B005641524981 -:10D190004F3B004241524F3B004245455045523BB8 -:10D1A00000474F5645524E4F523B004C4C49474862 -:10D1B00054533B0050415353544852553B004C4547 -:10D1C000444C4F573B004F53442053573B004C4572 -:10D1D000444D41583B0024504D544B3235312C3195 -:10D1E000393230302A32320D0A0024505542582C40 -:10D1F00034312C312C303030332C303030312C3134 -:10D20000393230302C302A32330D0A002450554246 -:10D21000582C34312C312C303030332C30303031EC -:10D220002C33383430302C302A32360D0A0024505A -:10D230004D544B3235312C33383430302A32370D9F -:10D240000A0024504D544B3235312C3537363030AE -:10D250002A32430D0A0024505542582C34312C31C7 -:10D260002C303030332C303030312C3537363030B4 -:10D270002C302A32440D0A0024505542582C3431A7 -:10D280002C312C303030332C303030312C313135A2 -:10D290003230302C302A31450D0A0024504D544B89 -:10D2A0003235312C3131353230302A31460D0A00D9 -:10D2B000D0D200080000002034040000FAAB0008BF -:10D2C000C0D30008340400202C2500001CAE000848 -:10D2D0000192031A7A44CBDC0502A10237011391B3 -:10D2E00030025C08021A030936B3914B7ED1BC2987 -:10D2F000491A560C290832021A830C2908297C1A6B -:10D30000930C290832041A8C0C290832051A670C70 -:10D31000290832061A4C0C290832071A750C2908FC -:10D3200029591A320C290832091A6C0C2908320AB8 -:10D330001A5D0C2908320B1A420C2908320C1AB457 -:10D340000C2908320D1A990C2908320E1ACE0C2914 -:10D3500008320F1ABE0C290832101AAB0C290832F9 -:10D36000111A3B0C290832121AA10C290832131A7F -:10D37000C60C2908721402A7FF021001E20452032E -:10D380008B803F0401165A03494AD931E91D120125 -:10D390000A1C0285C208342C01401A408C1A40191C -:10D3A0003A405B14A24A048B127A33380B0203040E -:10D3B000060708090204063B2910691481000000D1 +:101950000045814686688846086809F005FE0490BF +:10196000D8F800000AF0E6F90590D8F8040009F06C +:10197000FBFD0190D8F804000AF0DCF90746D8F81E +:10198000080009F0F1FD8246D8F808000AF0D2F903 +:1019900083465046049908F01DFF07905046019970 +:1019A00008F018FF80465846049908F013FF069087 +:1019B0005146059808F00EFF08905946059808F022 +:1019C00009FF03900198594680F0004008F002FF9B +:1019D00082463946089808F0FDFE069908F0A2FEF6 +:1019E00010903946039808F0F5FE079908F0EFFECD +:1019F0000E900598019980F0004008F0EBFE0590EC +:101A00003946079808F0E6FE039908F0E0FE0290D8 +:101A10003946069808F0DEFE089908F083FE8346F2 +:101A20000499019808F0D6FE04903046029908F017 +:101A3000D1FE01902846109908F0CCFE0090414656 +:101A4000204608F0C7FE009908F06CFE019908F0E6 +:101A500069FEC9F800005946304608F0BBFE8346CF +:101A600028460E9908F0B6FE80465146204608F0FA +:101A7000B1FE414608F056FE594608F053FEC9F83B +:101A800004003046049908F0A5FE0646284605994C +:101A900008F0A0FE05463946204608F09BFE294680 +:101AA00008F040FE314608F03DFEC9F8080011B0CC +:101AB000BDE8F08F2DE9F04380468A4887B0843036 +:101AC000016881F000410391406880F0004004907B +:101AD0008748B0F9000008F0FFFE864908F07AFE5A +:101AE000804C05907834B4F9000008F0F5FE0090C1 +:101AF000B4F9020008F0F0FE0190B4F9040008F017 +:101B0000EBFE029003A96846FFF71EFF7A4D783C72 +:101B100095F83C00012804D07148008808F0E5FEE3 +:101B200017E0764840780028206B0CD1C11700EBF5 +:101B30009161A0EBA11008F0CFFE029908F0F2FD30 +:101B400008F0D8FE2063C11700EB9160801108F007 +:101B5000C3FE029908F03BFE0290616B894608F0D3 +:101B600033FE0746404608F0C0FE0646644908F0CA +:101B7000D9FD0146304608F063FE394608F02AFEDA +:101B8000494608F0CFFD606309F0AEFD15F82D1F42 +:101B9000FFF7C9FE08F0A0FE0290009809F0A4FD2E +:101BA0006978FFF7C0FE08F097FE0090019809F0F1 +:101BB0009BFD6978FFF7B7FE08F08EFE0190E168A3 +:101BC00001EB0800E0602069401C2061009809F0EA +:101BD0008BFD4C4C216808442060019809F084FD7D +:101BE000616808446060029809F07EFDA1680844BD +:101BF000A06007B0BDE8F0832DE9F05F394D0446E1 +:101C00008435286809F0B0FC834628680AF092F809 +:101C10008246686809F0A8FC814668680AF08AF87C +:101C20000546D4F808802946404608F0D3FD5946B9 +:101C300008F0D0FD676806465146384608F0CAFDF0 +:101C4000294608F0C7FD05464946206808F0C2FD50 +:101C5000294608F067FD314608F064FD0446514608 +:101C6000404608F0B7FD05465946384608F0B2FD33 +:101C7000294608F0A9FD214609F04CFB224908F04D +:101C8000A9FD224908F0DCFD1649896A08F04AFDE1 +:101C90001F4908F0D5FD09F027FD00B2002802DA3F +:101CA00000F5B47000B2BDE8F09F2DE9F04F8DB0A3 +:101CB000002606F020F8DFF82CB005465C46DBF87D +:101CC0003800281A099008F010FE1249C96808F077 +:101CD00081FD0490A56300241EE00000F366DF3E52 +:101CE00082010020080000200AE81C4100401C4638 +:101CF000B001002035FA8EBCE8070020700A0020F1 +:101D00003661023CC40800200000E144DB0F49407A +:101D1000000020414C0C00200BF1720A0AF106056C +:101D20004FF07E58FE4890F82C70FE4830F91400B1 +:101D300008F0D2FD049908F04DFD06A941F82400F1 +:101D400017B3384608F0D1FD0146404608F078FD4B +:101D500081460B903AF9140008F0BEFD494608F0A0 +:101D600039FD814641460B9808F031FDEE4951F8A6 +:101D7000241008F02FFD494608F0D4FCEA4941F848 +:101D8000240008F0B7FD01E03AF8140025F814002B +:101D900035F91400641C00FB0066032CC5D3DFF882 +:101DA0008CA364204643BAF8000006A9404396FB82 +:101DB000F0F4DD481830FFF7C7FD0820FFF764FD99 +:101DC00006A910B1D8480C3801E0D6482030FFF7FA +:101DD000BBFDA0B24938DFF858933C2827D2002435 +:101DE000B9F8F00008F081FD45464146059008F03D +:101DF00099FC0146284608F023FDCB4E05461836CF +:101E0000C8480C3030F9140008F066FD074656F853 +:101E10002410059808F0DEFC394608F083FC2946BA +:101E200008F0D8FC46F82400641C032CE8D30820F2 +:101E3000FFF72AFD48B34546BB4EDFF8E882002491 +:101E40000C3E08F11208B9F8F20008F04EFD814688 +:101E5000294608F067FC0146284608F0F1FC0546D3 +:101E600038F9140008F038FD0746484656F82410A3 +:101E700008F0B0FC394608F055FC294608F0AAFCE9 +:101E800046F82400641C032CEAD35E46BBF900002C +:101E900008F022FDA44C1834A16808F059FD01D2C5 +:101EA000012100E00021A3484173D4E9010109F0B8 +:101EB00031FA9C4D18352860A068014608F08AFC6C +:101EC00007466068014608F085FC394608F02AFCA0 +:101ED00009F0F6FF0146206880F0004009F01AFA88 +:101EE000DFF8548268604146286808F073FC09F006 +:101EF000FBFBA5F1580741463880686808F06AFC8A +:101F000009F0F2FB78800820FFF7BEFC8B4D10B182 +:101F100085480C3801E083482030FFF76DFE2880AB +:101F20000998FFF7C7FD7E4D95F86A0000281BD081 +:101F3000BAF8000008F0D9FC0146A06808F080FC5F +:101F40007F4908F047FC08F0D5FCC0F1640064222A +:101F5000002104F0A3FB95F86A104843C11700EB79 +:101F6000517040F3CF0070800DB0A1E52DE9F04134 +:101F700002F0D1F90220FFF787FC20B102F0CEF881 +:101F8000FFF793FE05E067480021801D0180418036 +:101F900081804020FFF78DFC624B654CA3F10C0162 +:101FA00018B3A1F15A02107830B9D4F8F400040C37 +:101FB0001470040A547090705A4C0020B4F1060456 +:101FC000155C33F9106034F91070A5F1010C07FBB2 +:101FD0000C66761C96FBF5F521F8105024F810508D +:101FE000401C0328ECD3BDE8F0816079012809D0BA +:101FF0005FF0000033F8102021F81020401C032867 +:10200000F8D3F0E7474AB3F904006C3AB2F9044058 +:1020100000EB4400032490FBF4F088809080188843 +:10202000088058884880DEE73F4900200C3108606E +:10203000486088603B496C390861C86070472DE989 +:10204000F84F05F058FE374C46F2A8126C3CE16B95 +:10205000A0EB0108904502D20020BDE8F88F394F6F +:10206000E0632F4D3888DFF8E090DFF8E0A0DFF87C +:10207000E0B04FF07E5640B3206D6269C11700EBAF +:102080005171A0EBE10095F82F10491EB2FBF1F160 +:102090000844C117206500EB5170C01008F01CFC0B +:1020A000494608F0CDFB514609F036FB314608F0B1 +:1020B0008EFB594608F08EFB08F01CFCE064002003 +:1020C000206460643888401E388095F82F0061696C +:1020D000401EB1FBF0F008F008FC494608F0B0FBE8 +:1020E000514609F019FB4FF07E5108F070FB59463C +:1020F00008F070FB09F0F8FAE16C2F6B461A3946CC +:102100004FF07E5008F060FB8146304608F0E4FB5B +:10211000494608F05FFB0646A06908F0DDFB19E0C0 +:10212000E807002074000020B80800208201002089 +:102130006C040020700A00204C3D0F44B0010020C8 +:102140000000C842AE01002080E6C547B1DC423E37 +:10215000D048874A394608F03DFB314608F0E2FA9C +:1021600009F0C2FA8346A061E06808F0BEFB0746AA +:10217000654908F02FFB0646206908F0ADFB814653 +:102180006248806808F0A8FBE16D08F023FB39463F +:1021900008F020FB494608F053FB0746206C314607 +:1021A000009008F017FB81464FF0FF31384608F0E9 +:1021B00087FB314608F00EFB494608F0B3FA616C24 +:1021C00008F0B0FAD5F83890824649464FF07E5074 +:1021D00008F0FAFA0646584608F07EFB314608F049 +:1021E000F9FA06464946504608F0F4FA314608F036 +:1021F00099FA606408F07EFB60653946009808F043 +:1022000091FA2064FFF710FFD4E915104FF4967788 +:10221000401AC7F100093A46494604F03FFA0A213C +:10222000FFF781FB297906467143C81701EB50601F +:10223000C822C011514204F031FAE061A97B4CF28E +:1022400050327143C81701EB9060216A01EBA01076 +:102250005142206204F022FAC117206200EBD150F3 +:10226000E16901EB6020E061404608F03EFB8046FA +:10227000A669A06C301A08F02FFB254908F0AAFACD +:10228000414608F0DDFA08F035FB3A464946A664B7 +:1022900004F004FA0A21FFF746FB6F6B80463946CB +:1022A0004FF07E5008F090FA0646404608F014FBC6 +:1022B000314608F08FFA06463946206C08F08AFA53 +:1022C000314608F02FFA206408F014FB4FF47A72BC +:1022D000514204F0E3F908F0FFFA206409F004FA2F +:1022E0000521FFF720FB6062297E96224143C81733 +:1022F00001EB107000116FF0950104F0CFF9E16966 +:10230000081AE0610120A8E6BD378635C408002020 +:102310000024744970B5994D0446286807F0F3F815 +:102320000028FAD0E1B2286807F0D4F8204670BD42 +:1023300086B005F029FD0020FFF797FAFFF75CF85B +:102340008F4C002594F8090118B101281ED00928E6 +:102350001CD08DF8105084F8095104A804F0CAFB71 +:1023600004F0A4F90E20FFF797FA00F039F960792C +:1023700001260E280DD008280BD08DF8065000BF7E +:102380004FF48070FFF795FA50B905E08DF8100012 +:10239000E3E78DF80660F3E70820FFF78AFA00B15B +:1023A00001208DF802004FF4004B5846FFF781FAE8 +:1023B0008DF803000120FFF77CFA8DF8010008205A +:1023C000FFF777FADFF8B48180F001008DF80000A4 +:1023D0006C4F98F812008DF8040097F8B400C0F321 +:1023E00080008DF80500B4F8DE00ADF80800B4F800 +:1023F000E000ADF80A004FF48040FFF75AFA08B148 +:10240000B4F8DA00ADF80C00B7F8B000ADF80E0083 +:1024100094F80901012823D0092824D08DF8075009 +:10242000684605F063FB5849002040F2DE5200BFC9 +:1024300021F81020401CC0B21228F9D35449534847 +:102440000827086088F811703846FFF732FAB0B1F3 +:1024500094F8120158B1012809D002281CD10AE0D1 +:102460008DF80760DCE707208DF80700D8E74848BB +:1024700003F008FE10E0464804F0D3FA0CE094F8AC +:102480001C0128B194F91D01002801DA84F81D51BE +:1024900094F81D0103F017FC0120FFF70AFA30B190 +:1024A0004FF48060FFF705FA08B101F0C1FF394928 +:1024B0004FF0100AC1F800A0A1F10409B846C9F80C +:1024C00000700025A9F10407386880F0100038601A +:1024D000386880F008003860192005F035FC0120CC +:1024E00005F03DFC192005F02FFC002005F037FC1D +:1024F0006D1CEDB20A2DE7D3C9F80080C9F800A021 +:1025000001F04EFCFFF7ECF90220FFF7D2F908B119 +:1025100001F012FDD4F8200102F0BBF85846FFF795 +:10252000C8F928B194F82811D4F8240106F0F0FE77 +:102530004FF40060FFF7BDF908B103F051FF05F05B +:10254000DAFB154908606079052803D113494FF477 +:10255000C870088012494FF47A7008801149C82069 +:102560000880114880F80D6000F058FFFCE704482F +:10257000B0F9D40000F015F9FEE70000DC080020F7 +:102580006C040020E8070020800A0020CF2F0008FC +:1025900004010020140C0140000100207E010020F5 +:1025A00080010020AE010020700A00200146FE4894 +:1025B00000EBC100B0F97000122804DA082902DA31 +:1025C000FA4931F910007047F74A02EBC00090F960 +:1025D0007200084202D04FF0FF3070470120704770 +:1025E0002DE9F041F24EF34F707907EBC0004078CF +:1025F00000B10120F04CA0742020FFF75AF908B177 +:102600000120A0747079ED4CED4D122808D017F818 +:10261000301007EBC0002170426842B3002024E074 +:102620005FF0000006EB00110A6912F0FF4F1ED0A8 +:10263000D1E9057C05EB0013C969401CC3E902C15F +:10264000C3E900272178491C21700C28EADB0EE041 +:1026500002EB001305EB0016D3E9007CD3E90283FB +:10266000C6E90283C6E9007C401C8842F0DB4FF4D7 +:102670008040FFF71EF900281AD02778012F17D9BC +:10268000002613E005EB06144FF0FF384146A06822 +:1026900008F016F9A0604146606808F011F9606022 +:1026A0004146E06808F00CF9761CE060BE42E9DBC8 +:1026B000BDE8F081F0B5401C0021BD4A0B4600BFCB +:1026C00002EB0114491C23610C29F9DBB94B03EB24 +:1026D000C0014C68002C11D0002113F830000BE031 +:1026E00004EB011302EB011593E8C010DB68491CF1 +:1026F000C5E906C3C5E904678842F1DCF0BDAE4810 +:1027000010B5807C002839D0A948AC4C4079A41C75 +:1027100005280ED004DC01281BD0042804D112E0C7 +:10272000082825D00E2829D02020FFF7C2F800283D +:1027300024D02188002005F069FA61880120BDE8D5 +:10274000104005F063BA2189002005F05FFA618925 +:10275000F4E79A499448891C90F8B300498908B174 +:102760000020ECE7974840780028F9D10021F7E7EE +:10277000E188002005F04AFA2189DFE710BD70B535 +:102780008F4E0024183E8D4D07E000BF36F8141020 +:10279000204605F030FA641CE4B228788442F5D370 +:1027A00070BD864A864B00211278183B04E000BFBA +:1027B00023F81100491CC9B29142F9D3DFE72DE992 +:1027C000FC5F7E4C804EDFF804922078032814D9F9 +:1027D000B9F904004142002801DD024600E00A4642 +:1027E00002F1640200DC08466FF06301A1EB000116 +:1027F000B6F9040003F052FFB0807048DFF8C0A1C2 +:10280000DFF8A4810778AAF1180A012F38D900242B +:1028100034E000BF98F9B200B6F9041040424843D2 +:1028200008F05AF8664901EB0415E96807F0D2FF91 +:102830000190B6F9000008F04FF8696807F0CAFF88 +:102840000090B6F9020008F047F8A96807F0C2FF47 +:102850008346B9F9060008F03FF8296807F0BAFF87 +:10286000594607F05FFF009907F05CFF019907F0F8 +:1028700059FF08F03FF82AF81400641CBC42C9D381 +:102880004B4D4E4CDFF848B16879A41C052842D066 +:1028900004DC012831D004283CD102E00828FBD117 +:1028A00056E00420FFF782FE034602210420FFF7D2 +:1028B0008BFEB6F9041000FB01F701210420FFF79D +:1028C00083FEB6F9021000FB017018442081052038 +:1028D000FFF76CFE034602210520FFF775FEB6F9EF +:1028E000041000FB01F701210520FFF76DFEB6F98A +:1028F000021000FB017018440BE00520FFF756FEA4 +:10290000034601210520FFF75FFEB6F9041000FB26 +:102910000130608199E098F97200BBF9021032260B +:10292000484390FBF6F708F172025B460020FFF780 +:102930003DFE3844208092F90800B3F90010484366 +:1029400090FBF6F20120FFF731FE104460807CE03E +:102950001C4F7878F0B3B5F8D220B5F8D010B9F99B +:10296000060003F09BFEE081AAF80000B87A4FF061 +:10297000010100284FF003003BD0FFF725FEB9F915 +:1029800002104B4600FB01F602210320FFF71CFE5C +:10299000B3F9001000FB0160E08001210420FFF783 +:1029A00013FEB3F9021016E0E8070020800A0020A9 +:1029B0006C040020ECCB0008DC080020B4000020F0 +:1029C00008090020700A0020360100204401002080 +:1029D000340000200AE000FB01F602210420FFF78A +:1029E000F3FDB3F9001000FB016021E0B5F8D4005D +:1029F000B9E7FFF7E9FDB6F9021000FB01F3022188 +:102A00000320FFF7E1FDB6F9001000FB0130E08084 +:102A100001210420FFF7D8FDB6F9021000FB01F3F5 +:102A200002210420FFF7D0FDB6F9001000FB0130B1 +:102A300020810320FFF7BAFDE1880844E0800420EC +:102A4000FFF7B4FD2189084420812020FEF731FFE3 +:102A5000C0B30020FFF7AAFD20800120FFF7A6FDEC +:102A600062496080097A69B398F8B42041469207B8 +:102A700015D591F97220BBF9023056425E433223DC +:102A800098F97A10BBF9002096FBF3F6514391FBBD +:102A9000F3F1721A238831449A1A228010E098F9CF +:102AA0007230BBF90210278803FB01F6322196FB36 +:102AB000F1F63E442680BBF90020534393FBF1F12D +:102AC000084460800026474607EBC6006C30B0F92A +:102AD0000220B0F9001034F9160003F0DFFD24F8ED +:102AE0001600761C082EEFD397F8B400DFF800919B +:102AF000400711D500262020FEF7DBFE00B102269C +:102B000000244F4607EB44000189A019C0B205F02C +:102B10007DF8641C042CF5D336495646BAF900708A +:102B200001200B7806E000BF36F91020BA4200DD24 +:102B30001746401C9842F7D300244FF4804A884639 +:102B40004DE000BFB5F8D200B84205DA36F81410EF +:102B5000381A081A26F814005046FEF7AAFE98B153 +:102B6000B9F9060040F2DC51884204DDB5F8D22004 +:102B7000B5F8D81003E0B5F8D620B5F8D41036F97A +:102B8000140003F08BFD15E0B5F8D220B5F8D01095 +:102B900036F9140003F082FD26F81400B9F9060096 +:102BA000B5F81611884207DA1020FEF782FE38B118 +:102BB000B5F8D40026F814000F48407818B10DE09D +:102BC000B5F8D000F6E75046FEF773FE10B1B5F841 +:102BD000DA0001E0B5F8D40026F81400641C98F877 +:102BE00000008442AED3BDE8FC9F0000C60A00206E +:102BF000800A0020B4000020700A00202DE9F04770 +:102C00001746894606460025DFF83C841AE0002472 +:102C100011E000BFD8F8001081F00801C8F80010DA +:102C2000012005F09CF8484605F08EF8002005F0DC +:102C300096F8641CE4B2B442ECD33C2005F084F86E +:102C40006D1CEDB2BD42E2D3BDE8F0872DE9FC5F1B +:102C5000FE4C002540F2DC51B4F90600FC4E4FF466 +:102C6000FA73884201DA64210CE0F949B0F5FA6F91 +:102C700091F8251004DAA0F2DC52514391FBF3F1F4 +:102C8000C1F164018946F34996F866E096F867B0A9 +:102C9000B1F814410022B246EC49EE4B40F2E63C5A +:102CA00031F91260311B01F2F317674503D800298F +:102CB00003DCA11B01E04FF4FA71022A34D0BEF10B +:102CC000000F05D08E4502DAA1EB0E0100E00021D5 +:102CD000642391FBF3F3DD4F6FF01808243707EB03 +:102CE000430C37F91370BCF902C003FB08F3ACEBDB +:102CF000070C01EB83030CFB03FC64239CFBF3F345 +:102D00003B44D54F27F812309AF823304B434FF409 +:102D1000FA7193FBF1F1C1F1640189B201FB09F190 +:102D2000642391FBF3F11CE0BBF1000F05D08B4550 +:102D300002DAA1EB0B0100E0002193F9EC30DFF89F +:102D400018C35B424B43ACF804309AF82430002996 +:102D500000DC49424B434FF4FA7193FBF1F1C1F1AE +:102D600064010AEB0207642397F801C0DFF8E882E8 +:102D70000CFB01FC9CFBF3FCA8F1540808F802C012 +:102D800097F80BC008F103080CFB01FC9CFBF3FC5B +:102D900008F802C07F7D4F4397FBF3F108F103036E +:102DA000A642995405DAAC4931F812305B4221F859 +:102DB0001230521C032AFFF66FAFDFF898A24FF4CF +:102DC000FA625446BAF8161103F068FCB4F816110A +:102DD0004FF47A72401A5043C1F5FA61B0FBF1F139 +:102DE000642291FBF2F0994B6FF01806303303EB3D +:102DF000400433F910307043B4F9024001EB800015 +:102E0000E41A444394FBF2F0DFF84C828F4E1844EE +:102E1000103EA8F80600707AA8F17C04E8B38F4849 +:102E2000B4F91E10B0F90000401A07F055FD8C49A6 +:102E300007F0D0FC8B4907F003FD074608F094FB30 +:102E40000190384608F076FF00904746B8F9000038 +:102E500007F042FD8346009907F0BCFC8046B7F9B5 +:102E6000020007F039FD8146019907F0B3FC4146A5 +:102E700007F058FC07F03EFD80464846009907F0F1 +:102E8000A9FC81465846019907F0A4FC494607F081 +:102E90009BFC07F02FFD388000E001E0A7F80280DE +:102EA0000220FEF706FD002750B3E078401CC0B2B8 +:102EB0000621B0FBF1F2E07001FB1200B8B900206E +:102EC00003F08AFE2179614A01F00703AC3A491CFC +:102ED00022F813002171002032F81010401C294400 +:102EE0008DB20828F8DBE80801F00EF8A072A07A8D +:102EF000E18C884203D89AF80811814201D9A77061 +:102F000001E00420A070A07803F05FF956484E4D10 +:102F1000008818B10220FEF7B7FC10B953480088AA +:102F200020B1286880F00800286011E0B1780820FE +:102F300011B14549091D0860717811B14249083144 +:102F400008604FF40060FEF7B4FC08B103F05DFACE +:102F50008020FEF7AEFC48B1E16C606B411A05D4ED +:102F60004CF250310844E06405F010FAA16C606B3B +:102F7000411A03D4717BF9B10120B07002F011F84D +:102F80002020FEF781FC68B1216D606B411A09D4E5 +:102F9000E17A052906D3364908442065286880F07F +:102FA000100028603348816800290ED002B02A48FA +:102FB000BDE8F05F5C380847B770296881F0080108 +:102FC00029602D490844A064D8E7BDE8FC9F10B5EE +:102FD000204C204490F80A0104F022FEA0F2EE21D9 +:102FE00040F2DD52914201D3B4F8140110BD2DE935 +:102FF000F047194EDFF854807C3EA8F19C087079A8 +:10300000124F401C00247071A14608F14005F16B7D +:1030100020468847727908EBC40102F0030221F8C8 +:10302000120025F81490002035F8143031F81020E3 +:10303000401C1A44C0B225F814200428F4D335F9F2 +:103040001400801CC11719E00C0C0140800A0020FC +:10305000E80700206C04002044010020B00100209B +:10306000DB0F4940000034437E0100208001002036 +:10307000F04902004C0C002020A1070000EB9170E9 +:10308000801025F8140037F91410C91E884202DA9E +:10309000811C27F8141037F91410C91C884202DD6E +:1030A000801E27F81400641CE4B2082CAFD3CBE5D3 +:1030B000FE480288FE48417852B9827842B1002920 +:1030C00005D101214170FB48FB490088C883704746 +:1030D0000029FCD10122FF2102208FE52DE9FC5FB0 +:1030E0000020F54982467C31054607460190B1F93A +:1030F00002004342002801DD044600E01C468B46E6 +:10310000B1F900104A42002901DD0E4600E01646E2 +:10311000B44203DD002806DC184604E0002901DD86 +:10312000084600E01046DFF8949300240090E04E3B +:10313000F07808B93079E8B3022C3FDADE484FF472 +:10314000FA72443030F914103BF9140001EB4000DE +:10315000514203F0A3FADA49DFF868A331F91410F9 +:10316000411A0AEB4400B0F9280001EB00089AF874 +:103170000810642001FB08F191FBF0F09AF81C1094 +:1031800001EB8102494201EB810103F087FA0190D2 +:10319000C94842F21072743050F8241001EB080054 +:1031A000514203F07BFAC449743141F824009AF883 +:1031B000121000E008E048434FEA203AF07818B1D6 +:1031C000307908B9022C48D13BF91450B84F05EBBF +:1031D00085000101BB48A83F00EB04084FF47A5278 +:1031E00098F8010091FBF0F039F91410401A57F8E3 +:1031F00024100844514203F051FA47F8240039F9E9 +:10320000140000F52070B0F5A06F02D857F8240024 +:1032100002E0002047F824007D2190FBF1F098F8AF +:103220000B10484387113079A8B1022C13DA0098AB +:10323000009AC0F5FA710198009B484305FB020013 +:103240004FF4FA7201FB0AF107FB031190FBF2F055 +:1032500091FBF2F608E0F07820B1022C02DA564633 +:10326000019801E028463E46934A39F91410283265 +:103270005023125DDFF838824A4392FBF3F28E4B03 +:10328000821A6833A8F13C0833F9140023F81410AB +:10329000081A08F10C0158F8243051F824C041F8FC +:1032A00024309C44844448F8240083482E30005D38 +:1032B00000FB0CF0C11700EBD1609119A1EB60107D +:1032C0007D496E3121F81400641C032CFFF62FAFEA +:1032D0007BE62DE9F05F764E4FF0000BDFF8E4A1BE +:1032E000DFF8D4915C46A83E714DE87808B928799A +:1032F000D0B1022C18DA70484FF4FA72443030F929 +:103300001410383030F9140001EB4000514203F042 +:10331000C5F96B4931F91410411A0AEB4400B0F9B0 +:10332000280001EB000B01E0022C52D0E878E0B35A +:103330009AF8080000FB0BF0001160490AEB040743 +:1033400031F91410FA7A451A787856F8241068433F +:103350004FEAE018B9F80C006843C01200FB0210F5 +:103360004FF4001246F82400514203F097F946F852 +:10337000240043134E480C3850F8241040F82450D1 +:10338000B9F80C00691A02094FF6FF70B0FBF2F0B1 +:10339000484347498011243901F10C0251F824C0F7 +:1033A00052F824506544054400E01CE042F824C073 +:1033B00041F82400787D6843011208EB03000844BB +:1033C0003D496E3121F81400641C032C8CDBBDE8F0 +:1033D000F09F9AF8240038491B307C31B1F9041071 +:1033E00048434011A9E7344A9AF823007C321B3045 +:1033F00032F9142050432A790011002A9DD09AF8FE +:10340000121001FB0BF100EB212096E72A4901285D +:1034100001D02D4800E02D48086470472DE9F84F91 +:103420000027B946B8460820FEF743FADFF8A0B0F7 +:1034300068B19BF8120120B1012802D0022806D100 +:1034400002E002F042FE01E003F00AFB8046DFF8F2 +:1034500068A0174C4FF00005DAF83410DAF8540081 +:103460004FF00106081A02D5B8F1000F7DD044F6DE +:1034700020621144CAF85410FFF7B9FD4FF48040A0 +:10348000FEF717FA28B10A485630007808B900F05C +:103490007DFC9BF81B0168B305494FF47A7210312B +:1034A00001EB40000021B0F9060013E0800100208C +:1034B000700A0020B0010020C80000206800002031 +:1034C00034000020E8070020DD300008D332000877 +:1034D0006C040020A0F57A7003F0E0F807F0FCF926 +:1034E000FE4907F0ADF9FE4907F074F907F01BFA41 +:1034F000AAF822004FF40070FEF7DBF9B0B3DFF852 +:10350000E483BAF90E2098F8ACC00CEB8C01914220 +:103510001DDA6078D8B1BBF91431F349002000BF3F +:1035200021F81030401C0328FADBB8F8AE30CB800D +:1035300098F8AD00604400EB8000904202DA00F0A1 +:1035400025FC2570BAF81010491CAAF8101098F83C +:10355000AC0000EB8001BAF90E00814204DA607819 +:1035600010B900F013FC257001E068E204E0BAF83D +:103570000E10491CAAF80E10BBF816C1BBF8182192 +:10358000DFF864830020BF0838F91030634501DD9F +:1035900047F08007934201DA47F04007401C0428B7 +:1035A000F1DB9AF8071050468F4205D18179FA294C +:1035B00003D2491C817100E085718AF807704FF4CD +:1035C00080473846FEF775F958B1BBF81411BBF8BF +:1035D000DC00B8F906200B1A934202DA0844904244 +:1035E00009DC3846FEF765F9E8B9B8F90610BBF80A +:1035F0001601814217DABC48B8380560456085601D +:10360000BA4805604560B748C08F60B1B6484630DB +:10361000007820B1207810B1FFF74AFD03E0607810 +:1036200008B100F0B3FB9AF80600142817D16078AF +:10363000B0B1AC4FF88F28B99AF807005F2801D1D4 +:1036400000F0A4FB9BF81A01002808D0F88F00288E +:1036500005D19AF807007D2801D100F097FB8FE093 +:103660009AF80700572809D00420FEF722F9E8B19C +:103670009AF8071050465A2921D017E09C494FF478 +:103680007A7008804FF48070FEF713F908B101F0EA +:1036900068FF0420FEF7F8F810B196490A20088068 +:1036A0000820FEF7F1F808B9934805809AF807005A +:1036B0005D2817D05B2817D05E2817D023E0818AB9 +:1036C00019B18582AAF816601DE0818C21B1002114 +:1036D000818419B1022102E00121F9E703218AF86E +:1036E000001010E0012702E0022700E00327781E07 +:1036F0008BF8780300210846FDF701FF3A462821A0 +:103700000220FFF77BFA774FF88F18B99AF8071065 +:103710006F290ED09BF81A1121B118B99AF8070039 +:103720007E2806D09AF80700972805D0A72808D049 +:1037300008E0FFF7BDFC05E070494FF4C870088051 +:1037400000E0A6739AF80700BB2806D0B72807D078 +:10375000BE2809D0BD280AD012E0788D801C01E077 +:10376000788D801E788505E0388D801C01E0388DCD +:10377000801E388501210846FDF7C1FE8AF80650F3 +:103780000420FEF796F820B3BAF8242050463221E0 +:103790006AB162785AB1B8F90630BBF81621934283 +:1037A00005DD514A463212780AB9418285844E4A73 +:1037B0004632527C32B1028B838A1A4309D1AAF86D +:1037C000121006E0818A21B1617811B98582AAF8C8 +:1037D00016600020C64640F2A46700BF0EEB400111 +:1037E000B1F9082040F214518A4201DA012300E0C5 +:1037F000002300EB40018B40A2F2155CBCF5C77FB3 +:1038000002D84FF0010C01E04FF0000C01F101086B +:103810000CFA08FC43EA0C03BA4201DD012200E085 +:103820000022891C8A40134343EA0903401C1FFA03 +:1038300083F90428D2DB2C4F00204637294901EBBD +:103840004001C98F11EA090100D001213954401CFF +:103850001428F3DB787840B9224890F8AC0000EBEC +:103860008001BAF90E0081420ADA0220FEF70CF854 +:1038700030B1E07828B91D4805604560E67000E089 +:10388000E570B87838B1E570207928B91748056037 +:103890004560267100E025713878B84600B9267079 +:1038A000E178102009B9217909B1154901E01449DD +:1038B000091F08600420FDF7E7FF70B198F80300C6 +:1038C000474650B3A07938BB0E48A67101680E4830 +:1038D000016006480830C18818E02BE000007A44F7 +:1038E00000C07F44E8070020800A00203C0100203F +:1038F00080010020AE010020B00100207E010020E8 +:10390000140C01405C00002060000020FF48AAF871 +:103910001A100560FE48056000E0A5714FF40050E4 +:10392000FDF7C7FF30B1387918B1E07B10B9E67305 +:1039300000E0E5730220FDF7A7FF18B90820FDF7A6 +:10394000A3FFD0B198F80510404639B1617931B97B +:10395000F04966710A88F0490A8000E06571817952 +:1039600019B1617A11B9667200E0657298F80700C2 +:1039700018B1E8480188AAF81E102020FDF784FF3E +:10398000F0B3E07AE8B39AF80B005746052844D321 +:1039900098F80A1059B1E07990BBE671DF492572B9 +:1039A0003D72081F02F09BFA0220787039E0E57141 +:1039B00098F80B0030B3D94A143AB2F90000002845 +:1039C00000DC4042D649B1F8C01088421DDAB2F995 +:1039D0000200002800DC4042884216DA207A78B9DA +:1039E000CE4826720C383D7200F1100102680A6060 +:1039F000406841F8040FC948001D02F070FA02E067 +:103A00000FE00AE001E07E700BE02572387A40B9E1 +:103A10008AF8086002F038FA03E0E57125728AF846 +:103A2000015098F80C0008B1A67200E0A5729BF84E +:103A30000500082801D00E2843D1657241E0DAF86C +:103A40005C005746042801DD401FF865052838D280 +:103A5000DFE800F0030B151F2A000820FE65FDF7C4 +:103A600013FF10B100F06DFC58BBF86D401CF865F9 +:103A70000420FDF709FF10B100F073FB08BBF86DDF +:103A8000401CF8650420FDF7FFFE10B1FEF7D7FAE1 +:103A9000B8B9F86D401CF8654FF48070FDF709FF68 +:103AA00010B102F0C0F90CE0F86D401CF865102070 +:103AB000FDF7EAFE08B100F0C6FC4FF40050FDF738 +:103AC000F8FE04F018F9CAF83400BBF80C20574689 +:103AD00012B1BB6DC31A71D41044D946B865FEF754 +:103AE00045FAFFF7B3F804F006F97863398F411A05 +:103AF000B981B8630820FDF7C7FE48B38749143978 +:103B0000B1F9042002F145008A2822D8607900B377 +:103B10008048038880480088181A00B210F1B40F5A +:103B200002DC00F5B47000B2B42802DBA0F5B4707A +:103B300000B299F9EC305B42434318B2637B3BB16E +:103B4000774B5B7A43431E2093FBF0F0101A88807A +:103B500003E070480188704801800420FDF794FE5E +:103B600058B3A07948B36E4991F8690038B36B48EF +:103B7000B7F91A201438B0F90630A3EB020CBCF1E7 +:103B8000000F01DCA2EB030C91F868108C4509DDF5 +:103B9000DFF878C19342CCF800507E7200DD4942D4 +:103BA000194409E0797A21B15E490B685E490B60DE +:103BB0007D72574909881144C1803AE0E4E0FFE78B +:103BC000DFF85881B7F91A00A8F11408B8F90630DF +:103BD0001A1A002A01DD134600E0C31A91F8681092 +:103BE0008B420FDDB98B4FF4FA6C114409B291FB93 +:103BF000FCF34D4A0CFB131115681D441560B98385 +:103C00007E7207E0797A29B146490A6846490A6016 +:103C1000BD837D723E490988084400B2A8F80600B9 +:103C2000B9F8D010B9F8D220963102F037FDA8F8D3 +:103C300006003B4D95F86A0050B1E07808B920794C +:103C400030B13648394A1438C18812881144C180CD +:103C50002020FDF719FEE8B3E07908B9207AC8B34F +:103C6000207BB8B32B4CB4F9000006F035FE304E83 +:103C7000314606F0AFFD08F05DF80090B4F90000A1 +:103C800006F02AFE314606F0A5FD07F06DFC234C38 +:103C9000064695F8B900303CDFF898A0A4F11C085E +:103CA00010B3A146B4F90200241DB4F90210401A61 +:103CB00001F008FA15F8B92F514202F0EFFC6188C3 +:103CC00008446080B9F90000B4F90010401A01F00E +:103CD000F9F900E04EE02A78514202F0DFFC218839 +:103CE000084400B2208001E0B4F9000006F0F4FDC1 +:103CF0008346009906F06EFD0546B4F9020006F011 +:103D0000EBFD8146314606F065FD15E028000020F8 +:103D100024000020B0010020B20100205801002042 +:103D2000E80700205C000020600000200A0000205E +:103D300035FA8E3C00002041294606F045FD5546E7 +:103D4000514606F07DFD06F0D5FDA8F8000044467A +:103D50005846314606F03EFD06464846009906F0B4 +:103D600039FD314606F0DEFC294606F069FD06F015 +:103D7000C1FD6080386C8047FEF721FDFEF7BFFC77 +:103D8000BDE8F84FFEF7FBBCBDE8F88F034841786B +:103D9000002901D00021417070470000700A002006 +:103DA0002DE9F843FE4CFF4BFF490026B4F8EE2006 +:103DB0009846A1F1100004F0EAFB08B101260EE0DC +:103DC000B4F8EE10F84804F0F1FD40B9B4F8EE1084 +:103DD000F54803F082FD10B9032004F05FF8F34DBD +:103DE0005FF0000794F8ED0006283CD2DFE800F011 +:103DF0000707192833030220FDF753FD33E08DF840 +:103E000000704FF44870E849ADF802001039684678 +:103E100002F085FF08B10120287094F8ED00012818 +:103E200021D06EB1E049B4F8EE204346A1F1100074 +:103E300004F0ADFB0220287094F8ED0002281DD09C +:103E4000D948103804F0ACFC28B10320287094F84D +:103E5000ED00032812D0D448103805F01AFB10B139 +:103E6000042028700AE0287840B994F8ED0010B1D9 +:103E700084F8ED70B6E70220FDF713FDCA48103054 +:103E800004F097FE38B9C848103002F0EFFF10B9BF +:103E90000420FDF706FD0220FDF7F6FC28B1C2491B +:103EA00094F8E300103909688847BF4914F8E20F15 +:103EB00009688847A07803F0F3F810B90820FDF7E7 +:103EC000F0FCBB486421B0F9262092FBF1F001FB25 +:103ED000102406B20820FDF7D7FCB64D90B120465D +:103EE00006F0FAFCB44906F075FC0446304606F0CC +:103EF000F3FC214606F016FCB04906F06BFC286086 +:103F0000BDE8F8832F60FBE770B50546A44890F83C +:103F1000060106F0EAFC0446284606F0E6FCA8493D +:103F200006F058FCA74906F08BFC214606F052FC2F +:103F300006F0F9FC80B270BD70B500252C4600205B +:103F400002F04AFE05440A2003F0FEFE641C202C09 +:103F5000F5D3C5F34F10FFF7D7FF914A022192F82E +:103F6000073100BF03FB01F4844202D8491C062933 +:103F7000F8D39548017092F80801484393490880A6 +:103F800070BD2DE9F05FDFF82492914E884FB9F8AB +:103F90000220834C0025C2B38E4900204FF4C8781C +:103FA000424501D141F8205051F8203036F910C077 +:103FB000634441F8203026F8105004EB4003401CC5 +:103FC000A3F8FA500328EBDB012A19D10868C8309E +:103FD00090FBF8F024F8FA0F4868C83090FBF8F02E +:103FE00060808868C83090FBF8F1B9F80600081ABC +:103FF000A0803D850121FA3C7D850846FDF77FFACA +:10400000B9F80210491EA9F802100420FDF751FC6E +:10401000002874D0704BDFF894816E491A8808F13B +:1040200020080C31A8F1180A322A05D0F2B300207A +:104030009B46322A14D015E034F8FA0FA8F8000095 +:104040006088A8F80200A088A8F80400B7F828C083 +:10405000AAF800C0B7F82AC0FA3CAAF802C0E6E7FE +:1040600041F8205051F8203036F910C0634441F82F +:10407000203026F8105004EB4003401CA3F8FA50FF +:104080000328D6DB012A1AD15448554B058001205C +:104090001880544B02201870B8F8000024F8FA0F6A +:1040A000B8F802006080B8F8040000E00AE0A080E0 +:1040B000BAF800303B85BAF80200FA3C7885521E07 +:1040C000ABF8002048480288012A18D105800A6808 +:1040D000322092FBF0F224F8FA2F4A6892FBF0F2B9 +:1040E0006280896891FBF0F1B9F80600081AA08097 +:1040F0003D850121FA3C7D850846FDF700FA3088B0 +:1041000034F8FA1F401A308070886188401A708035 +:10411000B088A188401AB080BDE8F09F224810B551 +:10412000103841682A488847BDE8104029E730B573 +:104130001E4C1F4AE06892F82F200146401C824224 +:1041400000D10020294A1368224A183242F821304F +:10415000274952F820200D682B449A1A0A60E06023 +:1041600030BD70B52348114C00682169411A01D552 +:10417000002070BD20610C4D6069103578B1286950 +:1041800080476868804728882169084420616A69F7 +:1041900019491648904700206061022070BD2DE04B +:1041A0006C040020EC0800204C0C00207C01002056 +:1041B000E8070020300000208988883C000020416A +:1041C0003333534000F07F4568010020EE000020AB +:1041D0007A0000201C0B0020DA000020E000002004 +:1041E000DC000020C8000020DE000020A00000202D +:1041F0001C000020FC000020A4000020A8688047CC +:10420000E8688047FFF793FF0120606168882169B3 +:1042100008442061012070BD2DE9F05FA24DA888FF +:1042200000286AD0DFF884820024A3464FF47A790C +:10423000A8F10C06A888484507D104EB840208EBD6 +:10424000820146F824B0C1F810B0994F56F82410F6 +:1042500037F91400014446F8241006F03DFB0146EE +:1042600004EB840208EB8200824600F0EFF827F8A6 +:1042700014B0904F27F814B0A888012837D1DAF885 +:104280001000012808DD401E06F026FB0146DAF882 +:104290000C0006F0D5FA00E0002007F011FE82467F +:1042A000854890F8F800A8B106F01FFB514606F0CB +:1042B0004FFB0FD27D49A5F80490C8F810B0C1F8A3 +:1042C00024B0C1F838B0C6F808B0C6F804B0C6F8D3 +:1042D00000B00CE056F82400012200F5FA7090FBC3 +:1042E000F9F027F814000F210A20FEF787FC641C60 +:1042F000032C9FDBA888401EA8806D496D4A0020D2 +:1043000031F8103032F810401B1B21F81030401CDF +:104310000328F5DB00E7654810B54C304168644878 +:104320008847BDE8104077E710B564481024046062 +:1043300002F005FF6148001F04605B4901204870DE +:1043400010BD2DE9F0415E48574C0068A169411A43 +:1043500002D50020BDE8F0815A490844A0615A48BE +:1043600002F0B5FEDFF864C14F4B00269CF80E004A +:104370005549514A26339D1D88B1A069E06100204E +:1043800002EB4007A7F8006131F8107023F81070B5 +:1043900025F81070401C0328F2D38CF80E6060786A +:1043A00070B10888B2F80071C01B08804888B2F864 +:1043B0000271C01B48808888B2F80471C01B8880D5 +:1043C000E06998B3A769381A414FB84218D23B4800 +:1043D0000838026882F008020260002031F91020DB +:1043E00033F91040A24201DA23F8102035F91040C9 +:1043F000A24201DD25F81020401C0328EED315E071 +:104400000020E66133F9101035F91040214402EB29 +:10441000400401EBD17141F34F01401CA4F800119D +:104420000328EFD301210846FDF769F8012091E741 +:1044300010B5012004F001FA1020FDF72DFA2549EE +:104440000020086010BD234804F04BBA2DE9F0416C +:10445000044600690E46401C206101281FD006F06A +:104460003BFA256880462946304606F0ADF90746F6 +:10447000414606F0E5F9294606F054F90546606024 +:104480002946304606F0A0F90146384606F0A2F962 +:10449000A16806F047F92560E060A0605AE7666011 +:1044A00000202660F9E700007C010020000C0020BD +:1044B00074000020A80000206C040020140C0140AF +:1044C000FC000020A086010086000020700A002069 +:1044D00080C3C901B000002070B5FB4CFB4EC1B2D7 +:1044E0000546A170306804F0F5FFE079A1784840F6 +:1044F000E071C5F30721A170306804F0EBFFE079AB +:10450000A1784840E071C5F30741A170306804F01C +:10451000E1FFE079A1784840E071290EA170306890 +:1045200004F0D8FFE079A1784840E07170BD70B523 +:10453000E54CE64EC1B20546E170306804F0CAFFB2 +:10454000E079E1784840E071C5F30721E170306817 +:1045500004F0C0FFE079E1784840E07170BD10B52B +:104560000446DA482146006804F0B4FFD648C17911 +:104570006140C17110BDD44AD548117A405C491CD4 +:104580001172704700B5FFF7F6FF0346FFF7F3FF20 +:1045900003EB002080B200BD10B5FFF7F3FF044627 +:1045A000FFF7F0FF04EB004010BD70B504460D4668 +:1045B0002420FFF7D4FF4D20FFF7D1FF0CB12120BD +:1045C00000E03E20FFF7CBFFBF4C0020E071284603 +:1045D000FFF7C5FF607ABDE87040C0E701460020E4 +:1045E000E3E701460120E0E7B748C079B7E770B5D7 +:1045F00004460D460846FFF7F1FF03E014F8010BEF +:10460000FFF7ADFF2800A5F10105EDB2F6D170BDB1 +:1046100010B5044603E000BFFFF7A1FF641C20783B +:104620000028F9D110BD2DE9F05FDFF89CB2DFF86A +:10463000989201274FF0000A0BF10C0B00251AE0AD +:10464000A3481438405D00EB40010BEB8108D8F81B +:10465000040006F03AF806460FB1B2440AE000241E +:1046600006E000BFD8F80400005DFFF778FF641C87 +:10467000B442F7DB6D1C99F800008542E0DB002FA7 +:1046800005D00AF0FF00FFF7A9FF0027D6E7BDE835 +:10469000F09F70B50246032300218E4803F0D4FC3E +:1046A0008A49FF2208608A481421143805F0C7FFA0 +:1046B000874D0020143D012428700220FDF7E4F806 +:1046C00020B1012068700220A87003240420FDF7A7 +:1046D000DBF850B103202855641C4FF40050FDF75F +:1046E000E8F810B104202855641C0220FDF7CCF82E +:1046F00018B90820FDF7C8F840B105202855641CFA +:1047000006202855641C07202855641C2020FDF72E +:10471000D0F810B108202855641C4FF48070FDF7C4 +:10472000C8F828B10A202855641C0B202855641CA1 +:1047300069484079082801D00E2802D10C2028555C +:10474000641C0D202855641C0420FDF7B2F810B13C +:1047500011202855641C132028555B48641C0470E4 +:1047600070BD2DE9F05F584EDFF864B14FF00008DE +:10477000717A594D594C5A4FC1464FF0010AABF16D +:10478000140B782978D011DC3046A1F1640100784F +:1047900014293BD2DFE801F0FCFBFAF9F8F7F6F553 +:1047A000F4F3F2F1F0EFEEEDECEBEAE94C48CF294F +:1047B000407871D014DCCA295FD008DCA0296CD005 +:1047C000A4296BD0C82927D0C9291FD138E0CB290B +:1047D00065D0CC2971D0CD2970D0CE2916D17BE3FC +:1047E000D4296CD00ADCD0296AD04FF00008D12936 +:1047F00067D0D22966D0D32908D1DFE0EF2918D0BD +:10480000F02960D0FA2979D0FE2978D00020FFF76E +:10481000E8FEBDE8F05FE7E60024324DFFF7B2FEA8 +:1048200025F81400641C082CF8D30020FFF7D6FEEE +:10483000EFE7FFF7A7FE6085FFF7A4FE2085F4E70A +:10484000FFF799FEF872FFF796FE27490870FFF709 +:10485000A3FE264C2060FFF79FFE6060FFF792FEEC +:1048600023490880FFF78EFE2249088022480178FC +:1048700041F002010170D8E761E10023FFF77BFE00 +:10488000E5186870FFF777FEE872FFF774FE5B1CAF +:1048900068750A2BF2D3C8E749E04BE35CE30025D7 +:1048A0005F4606E0FFF76EFE795D6D1C04EB41018B +:1048B000C88730788542F5D3B7E721E005E358E1B2 +:1048C000FDE2C9E26BE02BE3B4010020DC0800202C +:1048D000880C0020003801406C040020E80700200C +:1048E000700A0020800A0020D30000204C01002024 +:1048F000760100207801002064010020F1E2F2E25C +:10490000FFF739FE04F81F0FFFF735FE6070FFF761 +:1049100032FE2071FFF72FFE6071FFF72CFEA071B1 +:10492000FFF729FEA070FFF726FEE0707DE7FFF796 +:1049300029FEFFF727FEE93525F8190CFFF72CFEB5 +:10494000FFF720FEA4F8AE00FFF71CFEFFF724FEE1 +:10495000FFF718FE00EB80004000E084FFF70BFE3D +:104960006877FFF708FEE87713E0D2E150E2B3E1A1 +:10497000CCE10CE2DAE1B6E19CE183E174E16AE1C9 +:1049800051E13EE120E111E10BE1D5E0A1E028E0B9 +:1049900018E0FFF7F0FDA877FFF7EDFD45E70028E9 +:1049A0008AD1FFF7E8FD85F87803022801D985F858 +:1049B000788300210020FCF7A2FD36E7FFF7E2FD37 +:1049C000F94987E20720FFF709FEE620FFF7C7FD58 +:1049D0006879FFF7C4FD0020FFF7C1FD4FF00040EC +:1049E000B7E20B20FFF7FAFDF048008800B2FFF7AE +:1049F0009EFD02F0AEFE00B2FFF799FD0220FCF72B +:104A000043FF04460420FCF73FFF44EA400408202B +:104A1000FCF73AFF44EA80042020FCF735FF44EA23 +:104A2000C0041020FCF730FF44EA0010FFF77FFDC0 +:104A3000F9783A79490041EA8201BA79002041EADD +:104A4000C2017A79367841EA42117A7AD44641EA4B +:104A50008211D74AD37941EAC311137A41EA03217B +:104A6000537A41EA4321FB7941EA83213B7A41EAC7 +:104A7000C321BB7A41EA0331537B41EA4331937B43 +:104A800041EA8331137C41EA0341137941EA03117E +:104A9000537C41EA4341937CD27C41EA834141EA21 +:104AA000C24479785F460C43002208E0BB5C0CFAF4 +:104AB00003F3234202D00CFA02F10843521CB24223 +:104AC000F4D3FFF709FD95F8780300BFFFF747FD22 +:104AD0009FE61220FFF782FDB648B74D4FF0000465 +:104AE0000088B0F5806F0BD935F91400C11700EBC1 +:104AF0005170C010FFF71BFD641C032CF4D306E0BB +:104B000035F91400FFF713FD641C032CF8D3AB4DEB +:104B1000002400BF35F91400FFF709FD641C032CC5 +:104B2000F8D3A74D002400BF35F91400FFF7FFFCB0 +:104B3000641C032CF8D36CE61021A24833E0382023 +:104B4000FFF74CFD5FF0000504EBC50636F96C0F6E +:104B5000FFF7EDFCB6F90200FFF7E9FCB6F9040037 +:104B6000FFF7E5FCB079FFF7FAFC6D1C082DEBD3DD +:104B70004FE60020FFF732FD5FF00005FFF702FD72 +:104B800004EBC50626F86C0FFFF7FCFC7080FFF7FE +:104B9000F9FCB080FFF7EFFC6D1CB071082DEDD370 +:104BA00037E610218848FFF722FD32E61020FFF794 +:104BB00015FD864D002400BF35F91400FFF7B7FC42 +:104BC000641C082CF8D324E61020FFF707FDF87AC0 +:104BD000FFF7C5FC7E480078FFF7C1FC7D4C2068DC +:104BE000FFF77AFC6068FFF777FC7B48008800B22B +:104BF000FFF79DFC7948008800B2FFF798FC7848E1 +:104C00003DE00520FFF7EAFC7648008800B2FFF798 +:104C10008EFC7548B0F90000FFF789FC73480078F6 +:104C200000F0010052E70820FFF7D8FC704D002487 +:104C300035F91400FFF77BFC641C022CF8D36D4897 +:104C4000B0F90000FFF773FC6B48B0F9000000BF3B +:104C5000FFF76DFCDDE50620FFF7C0FC6748006844 +:104C6000FFF73AFC66480AE00520FFF7B7FC654805 +:104C70000078FFF774FC0020FFF759FC62480088B9 +:104C800000B2E5E70720FFF7A9FC14F81F0FFFF7B4 +:104C900066FC6078FFF763FC2079FFF760FC6079C1 +:104CA000FFF75DFCA079FFF75AFCA078FFF757FCEF +:104CB000E0780BE71E20FFF791FC0025661970785D +:104CC000FFF74DFCF07AFFF74AFC707DFFF747FCD9 +:104CD0006D1C0A2DF2D39CE52F20FFF77FFC4B487B +:104CE000FFF796FC95E54006000EFFF777FC0025E0 +:104CF0005F4607E0785D04EB4000B0F93E00FFF747 +:104D000016FC6D1C30788542F4D382E5FFF78BFCEE +:104D10007FE5FFF763FC00245D4603E0285DFFF7B5 +:104D20001EFC641C30788442F8D372E53220FFF711 +:104D300055FC0020FFF7FBFB35F9D00FFFF7F7FB21 +:104D4000B5F90200FFF7F3FBB5F90400FFF7EFFB3D +:104D5000B4F9AE00FFF7EBFB0020FFF7E8FB002003 +:104D6000FFF7BAFBB4F926000A2190FBF1F000B27C +:104D7000FFF7DDFB95F83600FFF7F1FB95F83800FB +:104D8000FFF7EDFB95F83700FFF7E9FB62E008203D +:104D9000FFF724FC0024601CC0B2FFF7E0FB641C9A +:104DA000082CF8D335E50000B2010020D400002023 +:104DB000C60A002082010020800000206800002038 +:104DC00086000020B6000020F0080020800A0020A5 +:104DD000D30000204C010020760100207801002043 +:104DE000660100207201002074010020640100208F +:104DF00034000020B0010020E60000205C0000200C +:104E00002C000020D2000020EA00002084CC000802 +:104E1000FFF7B1FB04461220FFF7E0FB14B1102CA2 +:104E200002D004E0954800E09548D0E9008920468A +:104E3000FFF795FB4046FFF74FFB4846FFF74CFB5B +:104E400090480068FFF748FB0020FFF770FB002048 +:104E5000FFF76DFB002039E6FFF78DFB8446FFF777 +:104E60009BFB0546FFF798FB0646FFF795FB0446BC +:104E7000FFF788FBFFF786FBFFF77DFBBCF1000F18 +:104E800011D0BCF1100F7FF4DAAC7D49C1E90056B6 +:104E90000CB17C4804607C4A0220091D10707848DF +:104EA00001F01DF8C1E47548002CC0E9005687F8F0 +:104EB000078087F80CA0F5D072480460B5E400289C +:104EC000F0D10120FCF7D1FCAFE40028EAD16F4912 +:104ED0004FF4C8700880A8E40028E3D187F80EA03A +:104EE000A3E4012166E50820FFF778FB68486A4AD9 +:104EF0006A4D016867481268B1FBF0F1B2FBF0F04F +:104F000000EB4002C2EBC01001EBC000E8800024BF +:104F100035F91400FFF70BFB641C042CF8D378E47C +:104F20000420FFF75BFBB4F92A00FFF700FBB4F99C +:104F300028008DE60C20FFF751FB59480068FFF769 +:104F4000CBFA5748001D0068FFF7C6FA54480830EE +:104F50000068FFF7C1FA5CE4524D29780AEB810042 +:104F6000C0B2FFF73BFB2878FFF7F9FA00244E4E5A +:104F70004E4FDFF83C81DFF83C910EE0305DFFF7EB +:104F8000EEFA385DFFF7EBFA18F80400FFF7E7FADE +:104F900019F80400FFF7E3FA641C28788442EDD383 +:104FA00037E470B5444C454E0025607810B3BDE839 +:104FB0007040FBF7B5BF306804F09FFAA17951B19A +:104FC00001291CD002291FD0032923D0042929D06C +:104FD00005293FD12CE0242803D00021A17149B933 +:104FE00001E00121FAE7232802D0522832D102E061 +:104FF000FBF796FF2EE0012002F071FF2AE04D281A +:1050000004D10220A07125E03C2801D00020F9E75E +:105010000320F7E740281CD8607125712572E071E4 +:105020000420EFE76072E1794140E1710520E9E792 +:1050300021796279914207D2E2794240E271204AB5 +:105040005054491C217105E0E179814201D1FFF7FB +:1050500088FBA571306804F04DFA0028ABD1607868 +:10506000002809D14FF40060FCF723FC002803D08E +:10507000BDE8704001F0E3B970BD000054010020AC +:105080005C01002060000020C90000207E0100209B +:105090000804002040420F000C0400206A01002098 +:1050A000E8F7FF1F7A010020DA0A0020EA0A002050 +:1050B000FA0A00200A0B0020B4010020DC080020BE +:1050C000880C002044F25061884201DDA0EB4100D1 +:1050D000FE49884202DA48F6A041084470472DE9AB +:1050E000F04706465068994614460D46301A05F0BA +:1050F000F3FB296805F0A4FB2061A768394605F099 +:1051000063FB8046F24890F8B80005F0EEFBF149E9 +:1051100005F060FB01464FF07E5005F091FB2D68D5 +:10512000294605F0FFFA0146284605F089FB41466D +:1051300005F050FB394605F0F5FA2061C4E901603D +:105140000146D9F8080005F045FBBDE8F04705F039 +:10515000D1BB2DE9F0411D4614460E4605F0BCFBBF +:10516000696805F037FB316805F034FB216805F00C +:10517000D9FA2060ED680746284605F0BBFB0646D5 +:1051800085F0004005F0B6FB0546384605F0B2FB59 +:105190003246294601F082FA05F09EFB2060BDE808 +:1051A000F04105F0A7BB70B5CB4CD4E90D01401A16 +:1051B000FFF788FF0028D4E90D01A0EB010002DD14 +:1051C000FFF780FF02E0FFF77DFF404241F29411BC +:1051D000884228DAD4E90D01401A05F07DFBBF4969 +:1051E00005F0F8FA0646E06B05F07FFB0546304611 +:1051F00006F0A0FD294605F0EDFA05F07BFB00B2B4 +:1052000040F6B8322082514201F048FA616B0844FE +:1052100048F6A0416064884200DD401A002800DAA8 +:105220000844606470BD606BFBE72DE9FE4F0546E6 +:10523000FFF7B9FFA84842F22831406C081A05F080 +:105240004BFBA64905F0C6FA044606F08DF901901D +:10525000204606F06FFD00900024284605F03CFB38 +:10526000DFF874A2DFF87892DFF878B20AF1300A3A +:10527000029099481A3030F9140005F02DFB0546CC +:105280005DF82410029805F0A5FA294605F09CFA6D +:1052900005F030FB00B24FF47A7255462AF814003C +:1052A000514201F0FBF98E4900B225F81400603933 +:1052B00000F03CFE04EB8406894B8749074609EB66 +:1052C0008602904635F91400603B2831FFF741FF14 +:1052D000834B81490744424635F91400603B28312D +:1052E000FFF7FDFE384400B240F6B8325D462BF8B9 +:1052F0001400514201F0D2F925F81400784859F809 +:1053000026102838641C40F82610022CB1DBBDE8BA +:10531000FE8F2DE9F05F704E0024DFF8C491503607 +:10532000DFF8C0B1A6F1360AA9F128096C4956F890 +:105330002400803900F0FAFD3AF81410664F401A44 +:105340003037674900B227F81400703900F0EEFDDD +:10535000054637F9140056F8241004EB8407084476 +:105360005F4B5D4909EB87029046703B2831FFF7A0 +:10537000F0FE28445A4B58492BF814005D4642462B +:1053800056F82400703B2831FFF7A9FE4FF4FA626B +:10539000514201F083F93AF914103131622900D8F1 +:1053A000002035F8141040F6B832084400B225F851 +:1053B0001400514201F072F925F81400484859F8D8 +:1053C0002710641C40F82710022CAFDBBDE8F09FCB +:1053D00070B50546086819681446401A05F07CFA4D +:1053E0003D49C96A05F0F6F905F084FA01463A48E4 +:1053F0005030416029682268891A016070BD2DE92A +:10540000F0410F46DDE90685116800681E46081A5E +:1054100005F062FA044630683968401A05F05CFA13 +:105420002D49C96A05F0D6F90646014605F0D2F9BC +:1054300007462146084605F0CDF9394605F072F9D0 +:1054400006F03EFD284905F0C5F905F06CFAC8F8EC +:10545000000084F00040314605F05CFF234905F070 +:10546000B9F9234905F05EF905F044FA28600028EF +:1054700003DA48F6A04108442860BDE8F0812DE930 +:10548000F0471C48144CD0E90056617804F14809F3 +:1054900091B34FF07E50A16A05F0D2F98246D9F857 +:1054A0000400301A05F018FAE16A05F093F9514644 +:1054B00005F090F905F01EFA07B2D9F8000004F1E2 +:1054C0001A08281A05F008FA514616E0B0B9FFFF8D +:1054D000E8070020DB0FC940BC020020D3023739A7 +:1054E000680D0020280100202C7D8E3FA00CB345C4 +:1054F00000A00C464C0100201AE005F06BF905F005 +:10550000F9F901B204F12400B0F902203A4402EBA7 +:10551000D27242F34F02A8F80220B0F900301944C9 +:1055200001EBD17141F34F01A8F8001042800180D6 +:1055300001206070C9E90056BDE8F08710B5044647 +:1055400005F0CAF9002C01DC80F00040F74905F0B5 +:1055500077F9F74905F03EF906F006F8F549C86213 +:1055600010BD10B5F44CE07A002811D0F348007853 +:1055700005280DD3F249F34A086810604968516064 +:10558000FFF7DCFFF048EB49008888820120207398 +:1055900010BD2DE9F043E749EC48E74B8E7A012531 +:1055A00002790024062E29D004DC022E09D0032E15 +:1055B00004D116E0122E33D0302E3DD00020BDE8AD +:1055C000F083DF4A466856608668166000694FF4CB +:1055D0007A7290FBF2F0DE4A1080C87AD8724D736E +:1055E00051E04079C00701D0032A03D00020C872DF +:1055F00010B148E00120FAE7DC7244E0C27AD20739 +:1056000002D0827A032A03D00022CA7212B102E0C9 +:105610000122FAE7DC72C94A90F82F00107032E0DC +:10562000CC4B828A1A80806942F2107290FBF2F0B1 +:10563000C94A10808D7326E0C84B102A1A7001D910 +:1056400010221A700022C64EC64FDFF81CC3DFF8C6 +:105650001C931D7815E000BF02EB420300EB8303AF +:1056600093F8088006F8028093F8098007F8028012 +:1056700093F80B800CF8028093F80C8009F80280F4 +:10568000521CAA42E8DB487B8A7B104097D04C73BF +:105690008C73012093E72DE9F041A64900240A46C6 +:1056A00091F809E092F807C0157A0CEB0003D78A4D +:1056B000DEB22246BEF1090F51D2DFE80EF0080536 +:1056C0000F151C2333434900622803D04A72B528C2 +:1056D00002D044E0022033E0012031E003224A728C +:1056E0000873C87108723AE004224A72CE717219C6 +:1056F0000A72887233E005224A72CE7172190A72F8 +:10570000C8822CE006234B72731907EB0020CE7180 +:1057100080B20B72C882B0F5007F01D9CA824A728A +:105720000A831CE0CE7172190A720A8BC82A01D250 +:10573000864B9854521C90B20883B8420FD1072070 +:1057400048720CE008234B72844508D04A7206E088 +:105750004A72854203D1FFF71CFF00B101242046A5 +:105760008BE670B5034600200246054611E02E2C5C +:1057700004D1521C00290FD054181D559C5C00EB1D +:1057800080004000A4F13006092E01D830382044B2 +:10579000521C9C5C002CEAD170BD2DE9F041002622 +:1057A000804635463746044604F00AFF016800E0AB +:1057B000641C2078085C2028FAD0404609E01EB11D +:1057C00006EB86025206160E10F8012B303E3244CC +:1057D000D6B2221A022AF2DC09E01DB105EB8502DD +:1057E0005206150E10F8012B303D2A44D5B28442E2 +:1057F000F3D820782E280ED1641C002007EB8702F6 +:10580000570022788B5C202B02D1303F1744641C58 +:10581000401C0428F2DB56480621454307EBC7002D +:1058200000EB071005EB8000B0FBF1F051494E434F +:1058300000EBC61021E62DE9F04700273D4C054658 +:10584000242815D0414E2046F03EC0782C2D13D090 +:105850002A2D11D021460D2D497964D00A2D62D010 +:105860000F2802D23554401CE07000295CD0BAE009 +:10587000A770E7702771B6E03754A0784FF00109A0 +:1058800028B1A179012921D002294ED0A2E0A77127 +:105890003078472807D17078502804D1B07847284D +:1058A00002D0522809D095E0F078472804D1307909 +:1058B000412801D184F806908CE0F0784D2804D17D +:1058C0003079432801D10220A07183E0DFF8708095 +:1058D00002280CD003280FD0042816D0052819D090 +:1058E000062849D0072850D0092855D072E017481B +:1058F000F038FFF752FF05E0307853286AD1D8F826 +:1059000000004042C8F8000064E01048F038FFF79B +:1059100044FF05E0307857285CD1D8F804004042B5 +:10592000C8F8040056E063E05AE03BE08096184B6C +:1059300035FA8E3CBC020020700A0020D300002003 +:105940004C01002054010020B0010020B80D0020BF +:105950007601002078010020660100207A010020F5 +:10596000DA0A0020EA0A0020FA0A00200A0B0020C6 +:1059700040420F002D3101003078302801D901203C +:1059800000E00020FE49C87224E00021FD48FFF736 +:10599000E8FEFD4908701DE00021FA48FFF7E1FE2E +:1059A000FA4916E0072802D008280DD012E001219C +:1059B000F448FFF7D6FE41F2184148434FF47A719C +:1059C000B0FBF1F0F24904E00121EE48FFF7C9FE17 +:1059D000F0490880A078401CA070E7702A2D04D000 +:1059E0002079684020710020A6E584F80590FAE748 +:1059F0000029F8D0307800F0C7FA0501707800F07F +:105A0000C3FA28442179C0B288426771EBD1A079EA +:105A10000128E8D190E52DE9FF5FDF49C0B291F898 +:105A20001C1119B1012904D002297CD1FFF703FF11 +:105A300001E0FFF730FE002875D0D24C1034A0688A +:105A4000E06002F072F9A0602020FBF725FFD34848 +:105A50004FF0000B0178012910D001210170C848D6 +:105A6000C17A00295FD0C849097805295BD38246ED +:105A7000407830B19AF80C1031B108E080F800B0ED +:105A8000EDE78AF80CB002E008B1FFF76AFDC44800 +:105A900005218E460278C44C521CB2FBF1F301FB87 +:105AA0001322C0490270002091F90090BC4954F8BB +:105AB00020306831BA4D41F82030BC49783593FB2D +:105AC000F1F145F82010BA4D00EB80074D4303EB90 +:105AD000C51342F2107593FBF5F5AEB2B04D4035EB +:105AE00025F81060A74DC83505EB8707AC4D57F872 +:105AF00022C0603555F8208047F82230A8EB0C0C06 +:105B0000634445F8203093FBFEF3A94D6D42694391 +:105B100003EBC111A24B7033B9F1010F43F8201010 +:105B200007D1B61E00E080E0B6F5797F01D844F8D1 +:105B30002010401C0228B9DB02F0F7F8984D296AC2 +:105B4000401A04F0D2FE9B4904F07AFEA86202F0EB +:105B5000ECF82862A86A4FF07E51884200DB0846C4 +:105B6000A86203A902A8944BCDE900011A1F211DC8 +:105B70008D48FFF744FC02986426B0FBF6F08F498D +:105B80008F4A57460880039890FBF6F010809AF8E9 +:105B90000C0018B9A1F800B0A2F800B0FFF76FFC34 +:105BA000387A10B9F87900283FD07D49343101F1B5 +:105BB000080000F11C07CDE900013B1D3A46211DFC +:105BC0007948FFF71CFC231D774A391D3846FFF73B +:105BD000FFFB744C94F90000012828D0022824D13E +:105BE000784F0121B7F9BE0000F0ABF9FFF71DFBBC +:105BF00097F8BA00744A18B1686C90FBF6F0108000 +:105C0000B7F8B600E96B88420BD2D5E90D01401A0E +:105C1000FFF758FA002800DC404242F21071884237 +:105C200003DD01202070A88A1080BDE8FF9FFFF7E8 +:105C300070FBFAE72DE9F047624C607904F055FEFD +:105C4000DFF88891494604F0FBFD4E4D2035286071 +:105C5000E07B04F04AFE494604F0F2FD5C4EEE6043 +:105C60006860A07904F041FE5A4F394604F0E8FD1F +:105C700010352860207C04F038FE494604F0E0FD31 +:105C80006860A07E04F031FEDFF82881414604F010 +:105C9000D7FDC5E90206E07904F027FE394604F095 +:105CA000CFFD10352860607C04F01FFE494604F0EB +:105CB000C7FD6860E07E04F018FE414604F0C0FDB8 +:105CC000C5E9020638E42DE9F0412E4C06461034B1 +:105CD0000027032527704FF48070FBF7EAFD0028AA +:105CE00019D0667002F021F8C4E901702A4890F8D2 +:105CF0001C0100B90125FFF79DFF374906EB46005F +:105D00002B4651F820203549354802F09DF9354998 +:105D100048600120207023E52DE9F041194C03274C +:105D200010341D4A60782F4D00EB400192F81C3171 +:105D3000294E686813B1012B1ED105E056F82110D9 +:105D400003F0DEFB27700BE52378012B4CD056F8CF +:105D5000211003F0D5FBDFF88080002608F13C0815 +:105D6000686818F8061003F0B5FB042001F0ECFF9A +:105D7000761C8C2EF4D3277000206060F0E40000C5 +:105D8000700A0020C80C0020D300002076010020FB +:105D900078010020660100206C04002064010020CE +:105DA000BC020020C90000204C0100208096980011 +:105DB000D3CEFEFF00007A4458010020720100207B +:105DC00074010020E8070020B20100200000C84252 +:105DD0000000FA4400002041B4CC0008175A000823 +:105DE00000440040DC0800200027904607EB4700F5 +:105DF00056F82010686803F083FB98F91D0100EB4A +:105E0000400006EB80004168686803F066FBC8202C +:105E100001F09AFF7F1C052FE8DB98F81D016070E8 +:105E200002202070A8E710B55E4C207805282AD201 +:105E3000DFE800F02903031C0600BDE810406BE713 +:105E400060680521401C60606078401CC0B2B0FBF7 +:105E5000F1F201FB1200607001F067FF5249A0608F +:105E6000002008705149C87201200BE001F05DFF6D +:105E7000A168401A40F6C411884204D92020FBF7DB +:105E800010FD0420207010BD2DE9F05FDFF814A193 +:105E90000024474FDFF81C81DFF81C910AF1400A0B +:105EA00025460AF1280B00BF27F8145028F8145093 +:105EB00004EB840629F814500AEB860000F06DF814 +:105EC0000BEB860000F069F83648903000EB860056 +:105ED00000F063F8641C022CE6DBBDE8F09F7CB5A3 +:105EE000364C02682260096861600068FFF726FB93 +:105EF000A4F1240101F10800314ECDE90001231D78 +:105F00002246311D3046FFF77AFAA4F15805331DB9 +:105F1000686B68643246211D2046FFF759FA686BAA +:105F2000A8632848B0F8BC0068827CBD10B50C4658 +:105F300004F0D2FC216804F04DFCBDE8104004F0F0 +:105F4000D9BC70B51D4C583CE26B21B1B0EB520F7F +:105F50000BD3500809E0904200D31046194900B213 +:105F6000B1F8BC10814200DB0846B4F9125000B20F +:105F7000A84208DD1449A06A04F02CFC04F0BAFC25 +:105F8000284400B2608270BD3038C0B2092801D9FF +:105F9000C01FC0B200F00F007047002101604160D7 +:105FA00081607047D80C0020D3000020700A0020C8 +:105FB0000C0100202C0100202801002014030020E7 +:105FC0004C010020E80700200000C842F0B5404A1C +:105FD000404C1178E9B192F805C01779032104F11A +:105FE0001C035E1816F8015CFD4005F00F05072D37 +:105FF00009D213F801E016F8016C06EA0C060EEB64 +:10600000062644F82560891CC9B21029E9D300216D +:106010001170314907280ED2937863B151782E4A16 +:10602000104490F80A0149B154F820004FF47771F8 +:1060300001EB500006E0B1F81401F0BD34F8200087 +:1060400000F5777080B2F0BD70B5214C0126054691 +:10605000A67001F050FEA168421AC4E9020241F2A2 +:1060600088300021824200D9E1701A4AE0781C325F +:1060700015540F2802D0401CE07070BD17482670E0 +:10608000018070BD70B504461348114990F8122183 +:10609000032007252AB1012A08D108714D7101207A +:1060A00003E002220A7148710020487001234FF476 +:1060B000E1320B490B4801F0C7FF01460A48C160B5 +:1060C0000CB10A492160457470BD014800787047E1 +:1060D0003C030020800E00206C040020D60000202D +:1060E0004960000800440040DC080020CD5F000843 +:1060F00070B57C4C06460125207880B901F015FE6C +:10610000A1683231884207D32570012001F027FEB3 +:1061100001F00BFEA06070BD20780028FBD001F0DC +:1061200004FEA16831448842F5D30020207001F0BC +:1061300016FE01F0FAFD6C49A060087808B1401E17 +:106140000870657070BDF8B5664D8DF800008DF86B +:1061500001108DF802208DF80330A8791DF8001089 +:1061600044292DD04C2929D04D2925D04E292AD07B +:1061700032240026032806D274B12046FFF7B8FF68 +:10618000A879032808D301F0D0FDA968001B884234 +:1061900002D95548AE7106706878012801D0002CEC +:1061A00009D1A879032801D2401CA8716E702E7005 +:1061B000002001F0D4FDF8BD6424DAE7C824D8E754 +:1061C0004FF4FA64D5E70024D3E72DE9F047DFF870 +:1061D0001CA10546434C9AF80D004FF0010900261A +:1061E00010B184F8029000E0A6704FF40070FBF745 +:1061F00060FB3F4F18B33F493F484FF0020C91F806 +:10620000AC30B0F9000003EB830282420FDA97F85A +:106210000180B8F1000F0AD084F8049091F8AD1015 +:10622000194401EB8101814201DA84F804C0824201 +:1062300003DA797809B984F804C000B926712020FE +:10624000FBF722FB40B19AF80A1011B99AF80B003B +:1062500008B1F87AA8B1E6702079022814D0012894 +:1062600017D0E078012817D0A078012817D0042D86 +:1062700019D0022D1ED0012D1ED0607901281ED00C +:1062800022E084F80390E7E74E22442311464C2095 +:106290000DE04D234C2208E04D234E2201E04D231A +:1062A0005322532102E044234D224D215320BDE8C7 +:1062B000F04748E7442305E044234E22F5E7787889 +:1062C00010B14E234D22ECE70748007818B1BDE825 +:1062D000F04732200CE72670BDE8F047002001F0BF +:1062E0003EBD00004C030020C8000020C60A00206C +:1062F000700A0020E8070020D600002010B5D84C16 +:106300005E28A26807D05D280CD001461046BDE883 +:10631000104003F0DFB85D21104603F0DBF83E21AA +:10632000A068F4E75D21104603F0D4F83D21A06891 +:10633000EDE72DE9F041132000F04AF9C94C20683F +:10634000002800DC4042C84D90FBF5F000B200F0A0 +:1063500051F91B2000F03CF92068002800DC404285 +:106360000A2690FBF6F042F2107790FBF7F107FB5C +:10637000110000B200F03EF9232000F029F9206856 +:10638000002801DA532000E04E2000F033F91220FB +:1063900000F01EF96068002800DC404290FBF5F038 +:1063A00000B200F027F91A2000F012F96068002806 +:1063B00000DC404290FBF6F090FBF7F107FB110088 +:1063C00000B200F017F9222000F002F960680028FE +:1063D00001DA572000E04520BDE8F04100F00AB99D +:1063E00010B54FF40040FBF764FAA04A9C4920B175 +:1063F00092F82901012806D002E0002082F8290144 +:106400000868886010BD9A48FBE770B5974890F817 +:10641000291111B9974A52780AB1012400E00024E9 +:10642000954D2A78944209D039B914B14FF41650D9 +:1064300001E0D0F82001FEF72CF92C7070BD2DE999 +:10644000F0478A4890F8290118B98A48407800280E +:106450007ED08348806803F04DF8002878D101F0A1 +:1064600064FC854D6968401A7D2871D301F05DFC9C +:1064700068606878814F401CDFF80482DFF804927E +:106480006870002404F12400C0B200F0A1F838883C +:1064900004F02BFA064638F9140004F01DFA3146D0 +:1064A00004F0CEF9494604F095F904F023FA00B25D +:1064B00000F0A0F8641C032CE4DB00F096F8687888 +:1064C0004FF06404800724D1102000F081F86E4E54 +:1064D000306890FBF4F000B200F08CF8212000F05E +:1064E00077F8306890FBF4F104FB110000B200F083 +:1064F00081F8142000F06CF86448B0F9000000F056 +:1065000079F81C2000F064F8002000F073F800F027 +:106510006CF86878400735D1022000F059F85C48E3 +:106520004FF00A08B0F9001091FBF8F000B200F04B +:1065300061F80220FBF7BDF9E0B100F065F85548BD +:106540006E21007848431521B0FBF1F63A2000E0B7 +:106550003CE000F03DF8B6FBF4F738B200F04AF842 +:106560003B2000F035F804FB1760401DB0FBF8F04D +:1065700000F040F82020FBF787F908B1FFF7D9FEBB +:1065800000F033F86878282820D10020687001F0E6 +:10659000CCFB4FF47A71B0FBF1F43C25B4FBF5F67B +:1065A000B6FBF5F005FB1067172000F011F8380274 +:1065B00000B200F01FF8182000F00AF805FB1640A2 +:1065C00000F018F8BDE8F04700F00FB8BDE8F0871C +:1065D00070B5234C05465E21A06802F07BFF29467A +:1065E000A068BDE8704002F075BF1D485E2180685C +:1065F00002F070BF10B50446C0B2FFF77FFEC4F3CF +:106600000720BDE8104079E670B52248224E40F6DA +:10661000340200783178184DB0FBF1F050432A2253 +:10662000B0FBF2F06A88B2FBF1F301FB13214FF6E5 +:10663000FF7202EA011141EA0024C0F3032004437F +:106640000620FFF7C5FF20B2FFF7D4FF6888317836 +:10665000401C80B2B0FBF1F201FB1200688070BDFB +:10666000DC0800204C010020A08601006C04002002 +:10667000D8140020700A0020580300208201002056 +:106680008000002000007A4420000020B00100209B +:10669000E8000020D200002068010020884201DAD2 +:1066A000084670479042FCDD104670472DE9F047E0 +:1066B000BD49BD48E831B0F9E600B1F90050B1F983 +:1066C000024010B90DB9002C7ED0B84A00211170DB +:1066D00004F002F9B64F394604F07CF8DFF8D492A2 +:1066E000494604F0ADF88046284604F0F5F83946EE +:1066F00004F070F8494604F0A3F80646204604F07A +:10670000EBF8394604F066F8494604F099F8074674 +:10671000304604F029FF0446404604F025FF214698 +:1067200004F058F8A44C2060384604F01DFF0546DC +:10673000404605F0FFFA294604F04CF80546384675 +:1067400005F0F8FA8246304605F0F4FA81464046F4 +:1067500004F00AFF494604F03DF8514604F03AF8C7 +:10676000294604F031F86060384605F0E3FA054642 +:10677000404605F0DFFA294604F02CF80546384675 +:1067800004F0F2FE8246304605F0D4FA81464046D7 +:1067900004F0EAFE494604F01DF8514604F01AF8E8 +:1067A000294603F0BFFFA060304604F0DDFE054639 +:1067B000404605F0BFFA294604F00CF8E060384680 +:1067C00004F0D2FE054600E057E0404604F0CCFE5F +:1067D000294603F0FFFF0546384605F0ABFA82462E +:1067E000304605F0A7FA8146404605F0A3FA49462F +:1067F00003F0F0FF514603F0EDFF294603F092FF4E +:106800002061384605F096FA0546404604F0ACFE95 +:10681000294603F0DFFF0546384604F0A5FE824610 +:10682000304605F087FA8146404605F083FA49462E +:1068300003F0D0FF514603F0CDFF294603F0C4FF1B +:106840006061304605F076FA80F00040A06138467D +:1068500005F070FA0546304604F086FE294603F03E +:10686000B9FFE061384604F07FFE0546304604F08B +:106870007BFE294603F0AEFF2062BDE8F0872DE9DC +:10688000F0470546B0F90080B0F90260B0F90400A5 +:1068900004F022F8484C8246A16803F09BFF0746AB +:1068A000304604F019F88146616803F093FF06460C +:1068B000404604F011F88046216803F08BFF314612 +:1068C00003F030FF394603F02DFF04F013F8288061 +:1068D0005046616903F07EFF07464846216903F090 +:1068E00079FF06464046E16803F074FF314603F045 +:1068F00019FF394603F016FF03F0FCFF688050468D +:10690000216A03F067FF07464846E16903F062FF2A +:1069100006464046A16903F05DFF314603F002FFE1 +:10692000394603F0FFFE03F0E5FFA880A5E7092A3A +:1069300011D2DFE802F0100509161C21262A2E00CC +:1069400002880A80428803E042880A8002880CE0BC +:106950004A808088888015480078002822D108461F +:106960008DE7028852420A8042885242F0E742880C +:1069700052420A800288EBE7028852420A8042882B +:106980000CE042880A80028808E002880A80428877 +:1069900003E0428852420A80028852424A8080883C +:1069A0004042D7E7704700006C04002060030020DD +:1069B000DB0F494000003443AC0E0020444908443A +:1069C000444990F80A0151F820004FF4777101EB27 +:1069D000500080B2704710B5044601F08CF93E4972 +:1069E00002464868131A0020B3F57A6F00D9487040 +:1069F0004A604A780AB90F2C0AD1087032B1354B77 +:106A000020331344182A03F8014C02D0521C4A7058 +:106A100010BD304A2032D27D0AB901220A70487076 +:106A200010BD10B504462A4800212A4BB0F81401C5 +:106A30004200A2F5F76200BF43F82120491C082953 +:106A4000FADB0123254A2649264801F0FDFA0146D2 +:106A50002548C1600CB1254921600821417410BD51 +:106A60001D4B10B5187840B11A484FF00002203085 +:106A7000817DC908C90702D01A70002010BD1C49C9 +:106A8000401C0A8030F8011CC1F30A0411490C6053 +:106A90000488C4F3CA044C600468C4F38A348C606C +:106AA000B0F80340C4F34A04CC608488C4F30A14E9 +:106AB0000C614468C4F3CA344C61B0F80740C4F3B5 +:106AC0008A048C6100894009C8611A70012010BDD8 +:106AD0006C040020D00E002064030020A08601007A +:106AE000D769000800440040DC080020BD690008A8 +:106AF000D60000202DE9F0410646007890B008B19C +:106B0000012500E00025DFF8D880404602F0BCFEF9 +:106B10003448009000243448CDE90104012725B110 +:106B20000220CDE90304802002E0CDE903740020B7 +:106B300005904FF480700690800007902020089008 +:106B40000002CDE909046946404602F00AFF01212E +:106B5000404602F030FF8DF830500B948DF83170C4 +:106B60004FF46020CDE90D040DB1022000E00120BA +:106B70001C4C8DF83C004C3C0BA9204602F0F0FD6B +:106B8000032301220421204602F03FFE2DB131787B +:106B900003230222204602F038FE0121204602F0A3 +:106BA00008FE0121204602F0FAFD204602F00BFE0D +:106BB000204602F00DFE0028FAD1204602F00FFE1A +:106BC000204602F011FE0028FAD10121204602F0F1 +:106BD00012FE10B0BDE8F081034931F81000704793 +:106BE000080002404C2401406C0300202DE9FF47BF +:106BF000DFF86C81814698F80000D0B300273E464C +:106C00003D463C46641CE4B202AB082232215320CC +:106C100000F063FD9DF808009DF80910202C00EBA2 +:106C2000012000B207449DF80A009DF80B1000EB0C +:106C3000012000B206449DF80C009DF80D1000EBF9 +:106C4000012000B205449DF80F0000F07F0001D242 +:106C50000028D7D197FBF4F0ADF8000096FBF4F0D4 +:106C6000ADF8020095FBF4F0ADF8040088F802409E +:106C70001EE0FFE702AB06223221532000F02DFD7B +:106C80009DF808009DF8091000EB0120ADF8000008 +:106C90009DF80A009DF80B1000EB0120ADF80200F2 +:106CA0009DF80C009DF80D1000EB0120ADF80400DC +:106CB00098F8012049466846FFF739FEBDE8FF878E +:106CC00070B5274D04464FF0080228784FF02D018B +:106CD00000284FF053000ED000F0F9FC0A223121B9 +:106CE000532000F0F4FC0C222C21532000F0EFFC88 +:106CF0009022382108E000F0EAFC0A2231215320DA +:106D000000F0E5FC0A222C21532000F0E0FC15499C +:106D100040F20910002C088000D06C7070BD38B5AE +:106D2000054600208DF800000F480C460F4900680A +:106D300088420AD06B4601220021532000F0CDFC8E +:106D400018B19DF80000E52801D0002038BD0449A5 +:106D5000287808700648206006486060012038BD29 +:106D600070030020820100200C040020001BB700EB +:106D7000C16C0008ED6B000810B54FF4804420464C +:106D800002F076FE012805D1204602F07FFEB949C7 +:106D90000120087010BD70B50D46B649B64A0646CA +:106DA00088885389B2F91440C01A13895843B2F93C +:106DB0001230C013DB02044493FBF4F31844D06197 +:106DC00000EB8000082202EB40000411886800F00C +:106DD000D0F806B13060002D00D02C6070BD38B501 +:106DE000A44C207810B96088401C60806B46032258 +:106DF000F621772000F071FC9DF800009DF801104D +:106E0000000440EA01209DF8021008439A49B1F9B4 +:106E10002010C1F10801C840A06038BD9648342157 +:106E200090F8200001EB80109249C2B20020087057 +:106E3000F421772000F04BBC38B58E4C207810B987 +:106E40006088401C60806B460222F621772000F0AB +:106E500044FCBDF8000040BAA08038BD8549002040 +:106E60002E220870F421772000F031BC2DE9F04388 +:106E700004468248824985B00068884203D10020D8 +:106E800005B0BDE8F083DFF8EC9199F8010008B196 +:106E90000120F5E74FF40055ADF80C5002208DF8B5 +:106EA0000F001020774E8DF80E0003A9304601F038 +:106EB00039FF6F00ADF80C7004208DF80E0003A9A7 +:106EC000304601F02FFF35610E21022003F052FA07 +:106ED00000208DF8080008208DF809004FF0010807 +:106EE000019747468DF80A8001A802F08BFD282003 +:106EF0008DF810000F208DF811008DF812008DF81C +:106F0000137004A802F0F9FB142000F01DFF6B467B +:106F10000122D021772000F0E0FB574F9DF80000C0 +:106F20000321F8753984552801D07561A7E76B46B0 +:106F30000122D121772000F0D0FB9DF8000000F065 +:106F40000F0139760009787600F05CF889F8018045 +:106F500041F27070208046F6781060804A48606088 +:106F60004A48A0604A48E0604A4820614A48606157 +:106F70008EE770B54049CA69B1F90E40A2F57A6250 +:106F800002FB02F31D136C43E512B1F90240B1F9A3 +:106F90000460544305EBE424B1F9005004EB85058B +:106FA00091F82040A54056437213B1F90C601B13B1 +:106FB0005E4302EB2642921C9210C98802F5004201 +:106FC000AD1C5143C90B4CF25032A0EBA500E2407E +:106FD0005043B0F1004F03D24000B0FBF1F002E0AB +:106FE000B0FBF1F040000112494340F6DE3251435C +:106FF0002A4A0914424301EB224101F6CF6100EB1A +:10700000211070BD00B587B06B461622AA217720EB +:1070100000F063FBBDF8000041BA17480180BDF8DD +:10702000021049BA4180BDF8041049BA8180BDF808 +:10703000061049BAC180BDF8081049BA0181BDF8EF +:107040000A1049BA4181BDF80C1049BA8181BDF8D6 +:107050000E1049BAC181BDF8101049BA0182BDF8BD +:10706000121049BA4182BDF8141049BA818207B0A2 +:1070700000BD0000740300200C0F00200C04002051 +:10708000001BB700001001405D6E0008396E00085B +:107090001D6E0008DF6D0008976D000843E3FFFFD9 +:1070A00038B5044600208DF800006B4601220A2105 +:1070B0001E2000F012FB18B19DF80000482801D0F6 +:1070C000002038BD0CB18D480470012038BD7FB55B +:1070D000054602AB062203211E2000F0FEFABDF891 +:1070E000080040BA00B203F0F7FB844C241D21686D +:1070F00003F070FB03F0FEFBADF80000BDF80A00E2 +:1071000040BA00B203F0E8FBA16803F063FB03F0B0 +:10711000F1FBADF80400BDF80C0040BA00B203F07A +:10712000DBFB616803F056FB03F0E4FBADF8020003 +:10713000201F294602786846FFF7F9FB7FBD2DE93D +:10714000F0476F4800246F49006825468EB02E46F0 +:107150004FF0010888420CD14FF48050ADF8280060 +:1071600002208DF82B0004208DF82A000AA9664819 +:1071700008E06649884207D14FF48040ADF8280006 +:107180000AA9634801F0CEFD322000F0DDFD112296 +:1071900000211E2000F09BFA602201211E2000F039 +:1071A00096FA642000F0D0FD6846FFF790FFDFF804 +:1071B00058A1DFF8609100270AF10C0A0122022190 +:1071C0001E2000F084FA322000F0BEFD6846FFF772 +:1071D0007EFFBDF90210BDF90400BDF900200D4489 +:1071E00014440644814201DA0B4600E00346934210 +:1071F00001DD104602E0814200DA0846484502DC23 +:107200004FF0000808E0DAF8001081F01001CAF829 +:1072100000107F1C0A2FD1DB122200211E2000F05B +:1072200056FA0027012202211E2000F050FA3220D7 +:1072300000F08AFD6846FFF74AFFBDF90020BDF95E +:107240000210BDF90400A41A6D1A361A814201DA3F +:107250000B4600E00346934201DD104602E0814206 +:1072600000DA0846484502DC4FF0000808E0DAF88A +:10727000001081F01001CAF800107F1C0A2FD1DB2A +:10728000204603F029FB244F0146384603F0D8FA84 +:107290001A4C20F00040241D2060284603F01CFBFF +:1072A0000146384603F0CCFA20F0004060603046DA +:1072B00003F012FB0146194803F0C2FA20F0004027 +:1072C000A060702200211E2000F001FA202201217E +:1072D0001E2000F0FCF9002202211E2000F0F7F928 +:1072E000642000F031FDB8F1000F04D14FF07E5062 +:1072F00020606060A0600EB0BDE8F08780030020D1 +:107300000C04002000127A00000C0140001BB700A2 +:107310000010014000F0FFFF00406F4601C05E46D4 +:1073200030B587B005464FF44060ADF81400022038 +:107330008DF817001C208DF8160005A9FB4801F0F8 +:10734000F1FCFB4CE56000F007FAE06802F0A4FBFA +:10735000684602F00CFC00224FF44071E06802F035 +:107360003CFC0025ADF804504BF6FF70ADF806006C +:107370004FF48040ADF80C00EE4800900121E06829 +:1073800002F003FC6946E06802F099FB4FF4A0604C +:1073900002F0AEF922208DF810008DF811508DF812 +:1073A000125001208DF8130004A802F0A6F9212044 +:1073B0008DF810008DF8115004A802F09EF907B066 +:1073C00030BD38B5DA4CE068818A009111F4706FF5 +:1073D00001D001212170009911F4E06F25D0018BBB +:1073E00000224FF4806102F0F8FB009880051CD465 +:1073F000E0680188890518D40188C9050CD5018881 +:10740000C905FCD4012102F0D4FBE068018889059C +:10741000FCD4FFF785FF08E0012102F0CAFB00223F +:107420004FF44071E06802F0D8FBE068818A21F4F3 +:10743000706181820020207138BDC2E72DE9F041E2 +:10744000BB4CE068818A4FF00105C9B2CA074FF012 +:10745000000627D0018821F400610180012102F09B +:10746000B2FBE670607A20B1607860B9A079FF283D +:1074700009D061790022E06802F0BCFBA079FF2806 +:1074800048D0FF20C9E06570E079022804D1E068A7 +:10749000018841F40061018061790122E06802F015 +:1074A000A9FB37E08A074FF4806745D5BFF3508FBB +:1074B000E079012810D1607A70B1607860B1002164 +:1074C000E06802F080FBBFF3508FE068018B012180 +:1074D00002F06FFBA57018E0E068008BBFF3508FDF +:1074E000E079022808D1607A30B1607820B10021BB +:1074F000E06802F068FB06E0E079032805D1607AD5 +:1075000018B1607808B1002200E001223946E06835 +:1075100002F063FB94F90310E079401C814209D129 +:107520006670A07828B100224FF44071E06802F044 +:1075300054FB2671BDE8F0814A0753D5A570627AE5 +:107540007B494978CAB3C9B3E17902291FD900211F +:1075500002F039FBE06802F04AFB94F9031062691B +:107560005054491CE1700121E06802F022FBA57033 +:10757000E06802F03CFB94F9031062695054491C26 +:10758000E17001223946E06802F027FB25E0012185 +:1075900002F00FFBE06802F02AFB94F90310626925 +:1075A0005054491CE170E06802F021FB94F903108B +:1075B00062695054891CE1700FE000E000E009B9F5 +:1075C000217A31B1012102F0F4FAE078401CE07038 +:1075D00003E0012102F0E3FA6570E0680188C90563 +:1075E000FCD497E74A061AD502F001FB94F9031080 +:1075F00062695054491C48B2E070E179C01C814274 +:1076000004D100223946E06802F0E7FAE17994F902 +:1076100003008142E5D100F10100E0707AE709063C +:10762000DFD594F903104B1C5AB20BD02369595C77 +:10763000E27002F0DAFAE07994F9031088423FF43C +:107640005AAF67E7E270A17902F0CFFA607A0028BA +:107650007FF451AFE0790028F1D05BE7EEE6B0E6C9 +:10766000ECE670B5324C4FEA400047F2305560719D +:10767000A171012020720021617223616361E271B6 +:1076800020712170E068818889050ED40188C905C0 +:1076900005D401888905FCD4012102F080FA012279 +:1076A0004FF44071E06802F098FA207910B16D1E35 +:1076B000FBD104E01DB1207880F0010070BD60892D +:1076C000401C6081E068FFF72BFE002070BD07B50D +:1076D00002AB0122FFF7C5FF0EBD70B5144C4FEA97 +:1076E000400047F230556071A171002020720121E5 +:1076F000617263612361E27121712070E0688188A9 +:1077000089050ED40188C90505D401888905FCD4F2 +:10771000012102F044FA01224FF44071E06802F0C6 +:107720005CFA207940B16D1EFBD10AE0000C0140EB +:1077300090030020801A06001DB1207880F001001F +:1077400070BD6089401C6081E068FFF7E9FD0020A2 +:1077500070BD2A48408970472DE9F84F4FF44067C3 +:10776000ADF800704FF0020A8DF803A01420DFF886 +:1077700090B08DF802006946584601F0D3FA204DCA +:1077800010352F60DFF8789000262C1505F10408DD +:1077900009F1080902E00A2000F0CAFAD9F800004D +:1077A0004005F8D5C8F800400A2000F0C1FA2C6066 +:1077B0000A2000F0BDFA761CF6B2082EEED34FF484 +:1077C00000694646C8F800900A2000F0B1FA34601B +:1077D0000A2000F0ADFA2C600A2000F0A9FAC5F8E2 +:1077E0000090ADF800708DF803A01C208DF8020009 +:1077F0006946584601F096FABDE8F88F90030020DC +:10780000000C014038B504466B4602221B2168205B +:10781000FFF763FFBDF8000043F2903140BA08441F +:107820004FF48C71B0FBF1F02330208038BD1FB5D0 +:10783000044602AB06221D216820FFF74EFFBDF86B +:107840000800214640BA02B2D01702EB90708010B7 +:10785000ADF80000BDF80A0040BA02B2D01702EB42 +:1078600090708010ADF80200BDF80C0040BA02B272 +:10787000D01702EB90708010ADF804002F484278CA +:107880006846FFF754F81FBD70B50446192000F094 +:107890005BFA002215216820FFF719FF10B90320B9 +:1078A00000F0FCFA254D1621287840F018026820D7 +:1078B000FFF70DFF002217216820FFF708FF0122C4 +:1078C0003D216820FFF703FF01223E216820FFF7DA +:1078D000FEFE002C00D06C7070BD70B504460D46E5 +:1078E000192000F031FA002215216820FFF7EFFE81 +:1078F00000281CD012482060124860601248A06026 +:107900001248E0600D48622D12D004DC0A2D13D01D +:10791000142D05D10EE0BC2D06D0B5F5807F01D029 +:10792000032102E0002100E001210170012070BD6F +:107930000221FAE70421F8E70521F6E7A803002071 +:10794000897800082F7800080578000818449231DB +:10795000FEB5064614460D46684602F025FC012099 +:10796000ADF804000021ADF80050ADF80610ADF8F8 +:107970000810ADF802406946304602F065FBFEBDD6 +:1079800070B51646D04A02EB0015D04A02EB00143F +:107990000122206801F0EFFAD4E90101182200F079 +:1079A00087F9217B3246206800F03FF9A07B18B1AF +:1079B0000121206802F00AFC0121206802F0FCFB92 +:1079C000207B30B1042807D008280AD00C2806D123 +:1079D0000AE02068343001E020683830286028460A +:1079E00070BD20683C30F9E720684030F6E72DE9AB +:1079F000F0410546B4480F4600EB0516B348B27196 +:107A000000EB05142822D4E9010100F051F9217B93 +:107A100000222068FFF79CFF01224FF6FF712046ED +:107A200001F0C6FA3A462946204601F087FA304668 +:107A3000BDE8F08170B5A648002402894281018129 +:107A4000891A8BB240F68C218B4201D9C47070BD6B +:107A50009F49A3F2EF2540F2DB569E4AC978B54212 +:107A60001BD2082919D2984DE035042925F8113088 +:107A700007D2C588AB4204D9012305798B402B433B +:107A8000037103790F2B08D10471B2F90030142B64 +:107A900002DD143B138000E01480491CC170148087 +:107AA00070BD70B5884A894B02EB001203EB0013DE +:107AB000D47918681B7B8CB151811489824D091BC4 +:107AC00091819479E03525F814100024D471224670 +:107AD0001946FFF73DFF7F48048070BD11810121E9 +:107AE000D171BDE870400222194631E72DE9F04717 +:107AF0000446774DE1890020E980A17901B1022097 +:107B0000617801B1401C7449DFF8D081002651F83A +:107B100020704FF47A79BA5D02F00F0002F0F001A4 +:107B2000FF2A65D0A2781AB102285ED003285CD063 +:107B3000E2783AB1042858D0052856D0062854D007 +:107B4000072852D0E2790AB182424ED011F0300FAC +:107B500002D0227802B90021227932B1A27922B969 +:107B6000082801D0092800D1802162792AB1A279A0 +:107B70001AB9021F032A00D88021CA0605D500229F +:107B80005749FFF734FF082008E08A0608D5AA788D +:107B90005449FFF72CFFA87800F10100A87024E0F9 +:107BA0004A0612D52289B8FBF2F1A28989B202B93C +:107BB0004A46FFF7E5FE0146434A2878F03242F88C +:107BC000201000F1010028700FE009060DD5628930 +:107BD000B8FBF2F189B24A46FFF7D2FE0146424AAB +:107BE000687842F82010401C6870761C0E2E92DBDC +:107BF0000020BDE8F087364A1278904205D23A4A12 +:107C0000303A52F82000006801807047304A5278BC +:107C1000904204D2344A52F8200000680180704734 +:107C20003149403931F8100070477FB50646154696 +:107C30000C46684602F0AEFA7020ADF80000012054 +:107C4000ADF802000020ADF804000220ADF80800F5 +:107C5000C001ADF80650ADF80C0074B1042C15D07D +:107C6000082C1CD00C2C07D16946304602F038F99C +:107C70000821304602F0D3FA7FBD6946304602F053 +:107C800084F80821304602F0B4FA7FBD69463046D8 +:107C900002F0B0F80821304602F0B1FA7FBD694623 +:107CA000304602F0E3F80821304602F0B2FA7FBD18 +:107CB00008B5ADF800108DF8022002218DF80310F0 +:107CC000694601F02FF808BD300F0020F0CD000804 +:107CD000AA030020D6000020B4CD000840420F00C7 +:107CE000357A0008A37A00085010002080484168C7 +:107CF000491C4160704710B57D484FF0E023416852 +:107D00009A694468A142FAD10368006803EB43040E +:107D1000C4EBC313C2EBC302B2FBF0F001EB4102B0 +:107D2000C2EBC11100EBC10010BD71484068704743 +:107D300030B50546FFF7DFFF4FEA0004FFF7DBFF32 +:107D4000001BA842FAD330BD30B504464FF47A7513 +:107D500002E02846FFF7ECFF641EFAD230BD64490A +:107D6000896808474FF4805108B1624801E06148D2 +:107D7000001F016070474FF4805110B15D48001F33 +:107D800000E05C48016070472DE9F04F8DB018228B +:107D90005949684602F041FC032701F002FC012129 +:107DA000564801F08DFF012144F61D2001F07FFFB0 +:107DB0000121084601F072FF01F09DFF4FF6FF70B0 +:107DC000ADF818004B484FF0000A8DF81AA006A92C +:107DD000143800F0A7FF06A9494800F0A3FF06A940 +:107DE000484800F09FFF4848416841F000714160F9 +:107DF000464DDFF81C813E4E2968414501D145487A +:107E000000E04548B0600020FFF7A9FF3C4908208A +:107E10001031086010200860A946002483466D4692 +:107E2000D9F80010414506D105EBC4008179142929 +:107E300001D180F806B005EBC401091D55F83400E6 +:107E400000F070FF641CBC42EAD307A801F0E0FE1A +:107E500032490798B0FBF1F0306031484FF47A7145 +:107E60000068B0FBF1F0B0F1807F0CD220F07F41D0 +:107E70004FF0E020491E41612A4AF0211170C0F8FC +:107E800018A0072101612848FFF74AFA00F0B5FF62 +:107E90006420FFF759FF0DB0BDE8F08F184A10219C +:107EA000143211600821121F11600446151F40F2A0 +:107EB000DB104443286880F010002860286880F0B8 +:107EC00008002860A01EFFF73FFF0120FFF747FFD3 +:107ED0001920FFF739FF0020FFF741FFEAE710B153 +:107EE0001349124808600F49124817390860704753 +:107EF000B803002014080140C4CD0008070040006A +:107F0000000C014000100140000001400C04002062 +:107F1000001BB700777D0008657D000840420F0018 +:107F20000804002023ED00E000580040EFBEADDE65 +:107F3000F04F00200400FA057CB5FA4C0D46FA49D2 +:107F40002160A060A4F53070606100F58070A061D0 +:107F50004FF48070E0602061F4482063F348012111 +:107F600014386063880301F0A2FE02208DF803003C +:107F70000002ADF8000018208DF80200EC4EA807B2 +:107F800003D56946304600F0CDFE4FF48060ADF871 +:107F9000000048208DF80200E80703D0694630460B +:107FA00000F0C0FE0E208DF8040001208DF80500C1 +:107FB0008DF806008DF8070001A801F09EFB204611 +:107FC0007CBD2DE9FC41D74C0D464C34D64921608F +:107FD000A0608020E06040202061A4F58670606190 +:107FE0008030A061D3480121A064480401F068FEFC +:107FF00002268DF803600420ADF8000018208DF8EB +:108000000200CB4FA80703D56946384600F08AFE28 +:108010000820ADF8000048208DF80200E80703D0E2 +:108020006946384600F07EFE26208DF804000120C7 +:108030008DF805008DF806608DF8070001A801F0A5 +:108040005CFB2046BDE8FC812DE9F04389460646ED +:10805000B9490024B7488FB01D4617468E4204D157 +:1080600019461046FFF768FF05E0864204D119461D +:108070001046FFF7A6FF04464FF00008C4F8208022 +:10808000C4F81C80C4F82880C4F82C90C4F824805C +:10809000A6642571A760ADF83080ADF834800B97E9 +:1080A000ADF83280ADF83880ADF83680E80702D000 +:1080B0000420ADF83600A80705D5BDF8360040F01D +:1080C0000800ADF836000BA9304602F0CFF80121C8 +:1080D000304602F023F9684601F060FC301D009044 +:1080E0004FF48050CDE909088020CDF81080CDE90B +:1080F00005084746CDF81C80E80723D0206BD8B18F +:10810000E068CDE902702020089060690190206B42 +:1081100001F0BAFB6946206B01F023FC0121206BC2 +:1081200001F049FC01224021304602F019F9206B90 +:1081300001F056FC206405E0012240F22551304652 +:1081400002F0F6F8A80724D5606BE0B1206903902F +:10815000102008970290606B01F096FB6946606BF7 +:1081600001F0FFFB01220221606B01F02FFC0021D6 +:10817000606B01F033FC606B476001228021304668 +:1081800002F0EEF805E0012240F22771304602F0DD +:10819000CFF80FB02046BDE8F0837FB5044600203D +:1081A000ADF80400ADF808000091ADF80600ADF898 +:1081B0000C00ADF80A0020790D46C00702D004205B +:1081C000ADF80A002079800705D5BDF80A0040F017 +:1081D0000800ADF80A006946A06C02F047F8A560F7 +:1081E0007FBD826A81691144426BD160D0E9092167 +:1081F00000238A4205D9511A426B5160416A81625B +:1082000004E00269511A426B5160836280F8443085 +:10821000406B012101F0CFBB016B11B14968006CCB +:1082200001E01C3003C8814201D0012070470020CA +:108230007047416B11B190F844007047243003C877 +:10824000814201D1012070470020704710B50146DE +:10825000036BC268406943B10B6CD21A805C5B1E31 +:108260000B6401D1CA680A6410BD0B6AC05C5B1C58 +:10827000B3FBF2F402FB14320A6210BD436A826956 +:10828000D154416A0269491CB1FBF2F302FB13119C +:108290004162416B19B10968C90706D1A1E7806C39 +:1082A000012240F2277102F043B8704710B51D4C0F +:1082B0004FF4005001F097FB0021606B01F07BFB55 +:1082C000D4E90901884203D02046BDE8104088E780 +:1082D000012084F8440010BD1249886C02881206FF +:1082E0000ED5D1E909329A420BD08B699A5C828013 +:1082F000886A0A69401CB0FBF2F302FB1300886233 +:108300007047002240F2277102F012B870B5054C98 +:108310004C34A06C0588A9061CD58088E16A69B137 +:10832000884717E030130020DCCD000858000240D9 +:10833000000801400044004000380140E2696169E2 +:108340008854E069E16800F10100B0FBF1F201FB43 +:108350001200E06128060FD5D4E9091088420CD03C +:10836000A169085CA16C8880A06A2169401CB0FBEF +:10837000F1F201FB1200A06270BDA06CBDE870407C +:10838000002240F2277101F0D3BF0000FEB52C4C53 +:108390000125207878B1012823D0022820D164203B +:1083A0008DF8000027488DF8015000264078E0B392 +:1083B0008DF802503CE07A208DF8000022486B4690 +:1083C0000222B0F90000FF21C0F1B40000EBD07030 +:1083D000C0F347008DF801006D20FFF742F92570CA +:1083E000FEBD1A4E79208DF80000B6F900000A256E +:1083F00090FBF5F05A30B4220021FEF74FF98DF8CA +:108400000100B6F90200B42290FBF5F05A300021C9 +:10841000FEF744F98DF802006B460322FF216D2020 +:10842000FFF71FF902202070FEBDFFE78DF8026004 +:108430006B460322FF216D20FFF713F92670F3E747 +:10844000C4030020700A0020B00100203400002086 +:108450001FB5044602AB062243216820FFF73DF911 +:10846000BDF80800214640BA02B2D01702EB907066 +:108470008010ADF80000BDF80A0040BA02B2D01773 +:1084800002EB90708010ADF80200BDF80C0040BA0D +:1084900002B2D01702EB90708010ADF804007C4857 +:1084A00042786846FEF743FA1FBD38B504464FF4DC +:1084B0000050ADF8000002208DF8030004208DF874 +:1084C0000200744874490068884202D169467348C2 +:1084D00004E07349884203D16946724800F022FCE7 +:1084E00080226B216820FFF7F2F80520FFF72CFCB3 +:1084F000002219216820FFF7EAF803226B21682087 +:10850000FFF7E5F8022237216820FFF7E0F8604D19 +:108510001A2168202A78FFF7DAF818221B21682030 +:10852000FFF7D5F810221C216820FFF7D0F8002CA7 +:1085300000D06C7038BD1FB5044602AB06223B214B +:108540006820FFF7CAF8BDF80800214640BAADF828 +:108550000000BDF80A0040BAADF80200BDF80C00FA +:1085600040BAADF804004A4882786846FEF7DFF961 +:108570001FBD47494C4ACB7813B14FF4FF6301E06C +:108580004FF480531380002800D0887070472DE985 +:10859000FE4F8146984692460D462320FFF7D4FBB6 +:1085A0006B46012275216820FFF797F8002804D058 +:1085B0009DF80000682802D00020BDE8FE8F06224A +:1085C00001AB11466820FFF788F89DF809009DF877 +:1085D0000710C007400F01F0010140EA41009DF87B +:1085E00005102B4C01F0010108434FF001064FF03C +:1085F000000704D0012833D002280DD02CE06B46B0 +:1086000001220C216820FFF768F89DF8000010F0A7 +:108610000F0021D0042823D0E7702449C9F80010A6 +:1086200023492448C9F80410286023486860234877 +:10863000E860B8F1000F02D0E17888F800105046E9 +:10864000BAF1620F19D00DDC05281ED00A281AD005 +:10865000BAF1140F0BD114E00520FFF71FFCDCE783 +:10866000E670DAE7BC2806D0BAF5807F01D0032097 +:1086700004E0277003E0267001E002202070012052 +:108680009BE70420FAE70520F8E70620F6E700005C +:10869000C50300200C04002000127A00000C0140E9 +:1086A000001BB70000100140820100207385000804 +:1086B00037850008AB8400085184000819449231C2 +:1086C0001FB5044602AB062201211C20FFF705F866 +:1086D000BDF80800214640BA40F38D02D01702EBE6 +:1086E00090708010ADF80000BDF80A0040BA40F369 +:1086F0008D02D01702EB90708010ADF80200BDF82B +:108700000C0040BA40F38D02D01702EB907080103D +:10871000ADF80400334802786846FEF708F91FBD3B +:1087200038B504462020ADF8000002208DF8030083 +:1087300004208DF8020069462B4800F0F3FA00226D +:108740002A211C20FEF7C3FF02220E211C20FEF767 +:10875000BEFF03220F211C20FEF7B9FF12222B219E +:108760001C20FEF7B4FF02222C211C20FEF7AFFFD5 +:1087700001222D211C20FEF7AAFF00222E211C2001 +:10878000FEF7A5FF05222A211C20FEF7A0FF1749AE +:108790004FF48070002C088001D01248047038BD5E +:1087A00038B5044600208DF80000114811490068D2 +:1087B00088420CD06B4601220D211C20FEF78DFF54 +:1087C00028B19DF800002A2803D01A2801D00020E3 +:1087D00038BD09492160094961600249487001209A +:1087E00038BD0000C90300200008014082010020BC +:1087F0000C040020001BB70021870008C186000878 +:10880000434810B50068434CA188084203D0FFF7E5 +:1088100072FAA0600AE0FFF76EFAA168884205D9F3 +:10882000401A3B2190FBF1F061690860E068BDE807 +:10883000104001F02BB9E3E7E2E7FEB50125354C26 +:10884000022110B1012810D109E04FF4807060803E +:108850004000A080E06009202070172004E06580BF +:10886000A180E1602570072060706088ADF800008D +:108870001026274F8DF802608DF80310083F6946D7 +:10888000384600F04FFAA088ADF8000004208DF8BB +:1088900002006946384600F045FA2178012001F0CF +:1088A00069FDE06801F0F2F8E068019000208DF8C1 +:1088B00008008DF809608DF80A5001A801F0A2F8AF +:1088C00094F9010000F01F018D4040094FF0E021B4 +:1088D00001EB8000C0F80051FFF727FA3C38206117 +:1088E000FEBD70B50546FFF720FA0A4C21693C3100 +:1088F00088420CD3C4E90405054960880831086042 +:108900000B20FFF715FA024960880C31086070BD32 +:10891000080C0140CC0300201FB5044602AB062220 +:10892000A8216820FEF7D9FEBDF80800214640BA0C +:1089300002B2D01702EB90708010ADF80000BDF8C5 +:108940000A0040BA02B2D01702EB90708010ADF866 +:108950000200BDF80C0040BA02B2D01702EB9070D2 +:108960008010ADF80400264842786846FDF7DFFF26 +:108970001FBD70B504466420FFF7E6F9F0222321FD +:108980006820FEF7A4FE10B90320FFF787FA052040 +:10899000FFF7DAF91A4D2021287840F00F026820FD +:1089A000FEF795FE002C00D06C7070BD38B5044603 +:1089B0000D461920FFF7C8F96B4601220F216820E8 +:1089C000FEF78BFE9DF80000D32801D0002038BDB3 +:1089D0000C4820600C4860600C48E0600848362D68 +:1089E00005D04E2D07D05D2D07D0002100E040219D +:1089F0000170012038BD8021FAE7C021F8E70000AE +:108A0000E40300207389000819890008DDE9A73113 +:108A10002DE9F04FB74C83468E46608926890102C6 +:108A2000B5484FF0000A4068421AA6FB027CA088B5 +:108A30004FEAE2754FEA10414FEA00430AFB02C0D9 +:108A400006FB05064FEAD71040EA466013EB000923 +:108A500041EBE611E6886388A6FB02C84FEA534063 +:108A60004FEAC3370AFB028306FB05364FEA1C2395 +:108A700043EA0663FB1840EB2620A689A6FB027C8E +:108A80000AFB02C206FB05244FEAD75242EA4422FF +:108A90004FF4FA654FEAE454521944F10004A24637 +:108AA000551B74F1000448DA944D5519A5FB056770 +:108AB0004AF1FF3404FB057705FB047C0525A6FB82 +:108AC00005480CFB0585002706FB07556F104FEA8C +:108AD000340CB9EB0C0961EB0701A40844EA857476 +:108AE0001B1B60EBA500864D551B7AF1FF3424DA81 +:108AF00040F2DC555619A6FB06474AF1000505FB76 +:108B0000067706FB05750726A4FB06C805FB068647 +:108B1000002704FB0767B9EB0C0961EB07010B2782 +:108B2000A4FB07C805FB0785002604FB0654641058 +:108B30004FEA3C055B1B60EB04006F4CA56800240A +:108B4000A5FB036704FB037305FB0030740D44EAC7 +:108B5000C0244015B4EB090360EB0100410441EA75 +:108B6000D330BBF1000F01D0CBF80000BEF1000FF5 +:108B700001D0CEF80020BDE8F08F10B500F072F8FB +:108B80005D49886010BD5C48012200784030C1B268 +:108B90007720FEF79CBD10B500F064F85649486098 +:108BA00010BD5548012200785030C1B27720FEF741 +:108BB0008EBD2DE9FE430546524853490068884260 +:108BC0000FD04FF40054ADF8004002208DF80300A0 +:108BD00010204E4E8DF802006946304600F0A2F893 +:108BE00074610A20FFF7B0F801AB0122A0217720C1 +:108BF000FEF773FD002823D001221E217720FEF707 +:108C000066FD4FF42F60FFF793F80024DFF8E4804F +:108C10002646A02707EB4400C1B202AB0222772010 +:108C20000296FEF75AFDBDF8080040BA28F8140075 +:108C3000641C082CEEDB2F4800F026F810B1002051 +:108C4000BDE8FE8342F2107028806880304868607A +:108C50003048A8603048E860304828613048686192 +:108C60000120EDE708B56B46032200217720FEF7CF +:108C700034FD9DF800009DF80110000440EA012039 +:108C80009DF80210084308BDF0B5C289002102F426 +:108C90007F4502F00F040123C5810A4630F81260B7 +:108CA00006B10023521C082AF8DB4FF0FF36F3B957 +:108CB0000022D30722F0010302D0C35C594002E036 +:108CC000C35A81EA132108230F0401D581F4C0514E +:108CD00049005B1E002BF7DC521C102AE9DB254300 +:108CE000C581C1F30330844201D10020F0BD30467C +:108CF000F0BD0000C8130020E803002030F8FFFF9B +:108D000024FAFFFF0C040020001BB70000100140F4 +:108D1000A38B0008978B0008878B00087B8B0008CB +:108D2000118A0008F0B500234FF0010C0A880CFAF4 +:108D300003F52A4228D04FEAD30200EB82064FEA1D +:108D4000437491F802E04FEAD46734680EF00F02E2 +:108D50005FEACE6E03D591F803E04EEA02024FF0CF +:108D60000F0E0EFA07FE24EA0E04BA4022433260C8 +:108D70008A78282A02D0482A03D005E0C268AA438C +:108D800001E0C2682A43C2605B1C102BCED3F0BD49 +:108D90004FF4805108B14E4801E04D48001F01607A +:108DA00070472DE9F04104464A4817460D460088B1 +:108DB000484E0C3E1CE015B115F8010B00E0FF20F9 +:108DC00080460221304601F0EDFB0028F9D04146F3 +:108DD000304601F0E3FB0121304601F0E3FB0028BF +:108DE000F9D0304601F0DCFBC0B20CB104F8010B45 +:108DF0007F1EE0D20120BDE8F081F0B501218C0397 +:108E000089B0204600F05CFF0121204600F06AFF97 +:108E100018208DF816004FF42040ADF814002C4EA9 +:108E200003208DF81700143E05A93046FFF77AFF9E +:108E3000ADF8144004208DF8160005A93046FFF760 +:108E400071FFA010ADF8140010258DF8165005A97B +:108E50003046FFF767FF1F4E0C3E304601F054FBD3 +:108E60004FF48270ADF8020068010024ADF80A00EA +:108E70000720ADF81000ADF804400220ADF80E4018 +:108E8000ADF806000127ADF80040ADF80870ADF868 +:108E90000C506946304601F05BFB0121304601F081 +:108EA00073FB0DA0006806900120FFF771FF0422FC +:108EB00006A907A8FFF775FF0020FFF769FF9DF8D7 +:108EC0001D00EF2802D0204609B0F0BD3846FBE770 +:108ED000140C01400C3800409F0000002DE9F041C7 +:108EE00080461D4616460C46084600F0E7F8074641 +:108EF000404600F0D8F807EB8000C0B2102805D239 +:108F0000734901EB0010856004710673BDE8F081C0 +:108F100051B104290BD008290CD00C290DD1012204 +:108F20005FF0100101F05DB901220221FAE7012290 +:108F30000421F7E701220821F4E7704770B50D46D8 +:108F40000446017B134600682A46FFF7C7FF217BD2 +:108F50002068BDE87040DBE708B58DF80000002010 +:108F60008DF8010001208DF802008DF8030068469D +:108F700000F0C3FB08BDFEB5064614460D46684624 +:108F800001F0FFF853486D1E44435348ADF80450B8 +:108F900069460068B0FBF4F0401EADF80000002008 +:108FA000ADF80600ADF80200304600F0B5FEFEBD9B +:108FB00010B504460068FFF7DEFF0121206801F0CC +:108FC000FBF8607BBDE81040C6E770B50546084673 +:108FD00000F074F80446284600F065F804EB8000C1 +:108FE0003B49C0B201EB001070BD70B505460221CF +:108FF00001F028F9012825D00421284601F022F9A2 +:1090000001282CD00821284601F01CF9012833D072 +:109010001021284601F016F901283AD110212846DE +:1090200001F01CF90C212846FFF7CFFF0446284623 +:1090300001F005F9A2680146002A2AD0207BBDE88C +:10904000704010470221284601F008F90021284607 +:10905000FFF7BBFF0446284601F0EBF8EAE70421DE +:10906000284601F0FBF804212846FFF7AEFF04462E +:10907000284601F0E0F8DDE70821284601F0EEF887 +:1090800008212846FFF7A1FF0446284601F0D5F83D +:10909000D0E770BD1148A8E74FF08040A5E7104821 +:1090A000A3E71048A1E7014600200F4A01E0401C59 +:1090B000C0B252F820308B42F9D1704701460020EF +:1090C0000A4A01E0401CC0B2135C8B42FAD17047DF +:1090D000D813002040420F0008040020002C01405B +:1090E0000004004000080040F4030020D0CE000837 +:1090F000016B4A68926889680A4290F8441204D069 +:109100000020002900D10120704701200029FBD157 +:1091100000207047D0F8343101299A685B6801D08B +:1091200021B107E090F8440230B103E090F8440226 +:10913000012801D05A6170471A617047018940685F +:1091400089B2482200F052B970B5044601EB4100E3 +:10915000AC491646B1FBF0F081B21D460322204611 +:10916000FFF726FF2A4631462046BDE87040FFF74C +:10917000E5BE0189406889B2102200F037B900B518 +:109180000346032083F83C021846FFF7B1FF30B1D5 +:10919000B3F8400293F839120843A3F8400293F859 +:1091A0003902400083F8390293F83E02401E10F065 +:1091B000FF0083F83E0205D1012083F83802022027 +:1091C00083F83C0200BDC268016A521E914201D37D +:1091D000002100E0491C0162704710B501240346DC +:1091E00080F83C42FFF784FF01280FD1002083F86C +:1091F000380283F83A4293F84002A3F840021A6A10 +:1092000059698854BDE810401846DCE710BD00B528 +:109210000346FFF76DFF012101280BD003F23A232B +:1092200000201870D880042098700820187103F866 +:10923000011C00BD83F83C1200BD90F83C12491E91 +:1092400011F0FF0180F83C1208D190F83A1201B1F8 +:10925000DDE790F8381201B1BFE790E77047D0E939 +:109260000910814201D1012070470020704730B5BC +:10927000044690F83B020025F8B194F83D02401EE8 +:1092800010F0FF0084F83D0216D1B4F8420200F05D +:1092900001014008A4F842022046FFF73BFF0320EB +:1092A00084F83D0294F83F02401E10F0FF0084F85D +:1092B0003F0201D184F83B5230BD2046FFF7CFFF7B +:1092C0000028F9D1A16AA269481CA062515C2269F8 +:1092D000904200D3A5624FF4007004F23B2440EAB0 +:1092E0004100A4F807000A2020710120A07020701E +:1092F00030BD00EBC00101EB801010B5424901EB1D +:10930000C0042046FFF7B3FF2046BDE8104094E7B5 +:1093100070B53D4C06463D48206003202071A66094 +:1093200084F844123A4820631030C4F83401002510 +:1093300004F13401256261614FF48070E0602061C6 +:1093400004F59C71C4E90615A562656284F83B5278 +:10935000012084F83A0284F8385284F83C02206BE9 +:10936000FFF7ECFED4F83401FFF703FF012120469C +:10937000FFF7D0FE3220FEF7E7FCAFF289032A4662 +:109380003146206BBDE87040DEE6D0E9072191420E +:1093900002D14FF00000704702D9A1EB020003E0B8 +:1093A000C0680844A0EB0200C0B2704700B5034695 +:1093B000FFF7EBFF00280BD05969D869095CDA6820 +:1093C000521E904201D2401C00E00020D8610846A5 +:1093D00000BD436A8269D154416A0269491CB1FBEC +:1093E000F2F302FB131141627047704708B5ADF804 +:1093F00000108DF8022002218DF803106946FFF756 +:1094000091FC08BDC0C62D00D8140020D4CE0008A1 +:1094100030CE00081FB5044602AB062202211820F8 +:10942000FEF75BF99DF808009DF80910800800EB35 +:109430000120ADF800009DF80A009DF80B1080088F +:1094400000EB0120ADF802009DF80C009DF80D1016 +:10945000800800EB0120ADF804001A48214602788C +:109460006846FDF764FA1FBD10B5044608220F21B7 +:109470001820FEF72CF90E2210211820FEF727F9EC +:1094800011494FF48050002C088001D00D48047021 +:1094900010BD38B5044600208DF8000001466B462B +:1094A00001221820FEF719F918B19DF80000FB28D9 +:1094B00001D0002038BD05482060054860600120CB +:1094C00038BD0000040400208201002069940008D7 +:1094D0001594000802681268104770B50C460546DE +:1094E00003E02A6828461268904714F8011B0029F7 +:1094F000F7D170BD01684968084701688968084765 +:109500000268D26810470168096908476E48016817 +:1095100041F00101016041686C4A114041600168FD +:109520006B4A11400160016821F4802101604168AB +:1095300021F4FE0141604FF41F0181606549C003C1 +:1095400008607047604A10B55068634B10F00C011A +:10955000624803D0042903D0082903D0036016E031 +:10956000416813E05168536801F470114FF0020430 +:1095700013F4803F04EB914106D053689B0343688A +:1095800000D55B084B43E9E7554B594301605168EF +:10959000524AC1F303110832515C0268CA400260AA +:1095A00010BD3EB4002100914FF4E01301914648F4 +:1095B000CDE901314B4A046844F480340460846985 +:1095C00044F0100484614FF4A064056805F400358C +:1095D0000195009D6D1C0095019D15B9009DA5424A +:1095E000F3D10568AD0301D5022114E0056845F00B +:1095F000010505600091016801F0020101910099E7 +:10960000491C0091019911B90099A142F3D1016857 +:10961000890739D50121029133490C6844F01004BF +:109620000C600C6824F003040C600C6844F0020425 +:109630000C604168416041684160416841F480616B +:109640004160116821F070411160244C2249616031 +:10965000416821F47C114160116841F000411160C2 +:109660002049091FCA6822F40042CA6089680904B7 +:1096700003D51E494FF480136160029901930129BB +:1096800008D002290AD100E0FEE7416843F48032A5 +:10969000114302E0416841F460114160016841F00A +:1096A0008071016001688901FCD5416821F00301E6 +:1096B0004160416841F0020141604168C1F38101AC +:1096C0000229FAD13EBC3DE7001002400000FFF83D +:1096D000FFFFF6FE08ED00E000127A00080400200B +:1096E00000093D000410014000200240001BB700AB +:1096F00018490843184908607047F0B50F21C4782D +:10970000027801234FF0E026DCB1134C2468457841 +:1097100004F4E064C4F5E064240AC4F10407E14001 +:109720008478BD400C402C4321010C4C115500782D +:1097300000F01F018B40400906EB8000C0F80031AB +:10974000F0BD02F01F008340500906EB8000C0F816 +:109750008031F0BD0000FA050CED00E000E400E00F +:1097600010B54268464B0C791A400B6842EA042255 +:10977000134343608368434A1340D1E902422243C2 +:109780004C7943EA44031A438260C26A097C22F49A +:109790007002491EC9B242EA0151C16210BD0029DE +:1097A000816802D041F0010101E021F001018160F6 +:1097B00070470029816802D041F4807101E021F4F2 +:1097C000807181607047816841F008018160704755 +:1097D000014600208968090700D50120704781688B +:1097E00041F0040181607047014600208968490703 +:1097F00000D5012070470029816802D041F4A00102 +:1098000001E021F4A0018160704770B507240929A7 +:109810000AD9C568A1F10A0606EB4606B440A5437D +:10982000B3401D43C56007E0056901EB4106B44044 +:10983000A543B3401D4305611F23072A09D2446B8A +:10984000521E02EB820293409C4391400C434463BE +:1098500070BD0D2A09D2046BD21F02EB8202934025 +:109860009C4391400C43046370BDC46A0D3A02EB03 +:10987000820293409C4391400C43C46270BD00003F +:10988000FFFEF0FFFDF7F1FF01684FF6FE72114099 +:1098900001600021016041608160C1605749574A01 +:1098A0000839904203D1486840F00F0006E0534A5F +:1098B0001432904204D1486840F0F000486070478C +:1098C0004E4A2832904203D1486840F47060F5E770 +:1098D0004A4A3C32904203D1486840F47040EDE778 +:1098E000464A5032904203D1486840F47020E5E780 +:1098F000424A6432904203D1486840F47000DDE788 +:109900003E4A7832904203D1486840F07060D5E713 +:109910003B4A111F904203D1086840F00F0006E057 +:10992000374A1432904204D1086840F0F0000860D1 +:109930007047334A2832904203D1086840F470607F +:10994000F5E72F4A3C32904203D1086840F470405A +:10995000EDE72B4A50329042EAD1086840F470207B +:10996000E5E730B5036847F6F07293430C6A8A68FE +:109970002243D1E904452C4322438C692243CC691C +:1099800022434C6A22438C6A22431A430260CA680B +:1099900042600A6882604968C16030BD0021016090 +:1099A00041608160C160016141618161C1610162A9 +:1099B0004162816270470029016802D041F00101D3 +:1099C00002E04FF6FE72114001607047002A026803 +:1099D00001D00A4300E08A4302607047416070474B +:1099E000406880B27047C10003D50549091F08606F +:1099F000704702490839486070470000080002407B +:109A00000804024030B523498379026853B30B68D8 +:109A100093430B600A1D13680468A3431360027923 +:109A20000A4413680468234313601A4A083213680F +:109A30000468A3431360131D1C680568AC431C60D5 +:109A40004479102C05D021440A68006802430A605A +:109A500030BD116804682143116019680068014332 +:109A6000196030BD0079084401689143016030BD40 +:109A7000084A014600201268064B0A4014331B684E +:109A80000B4202D0002A00D0012070470149143156 +:109A900008607047000401405A4910B588424FF0F1 +:109AA000010101D14C0501E04FF48004204600F093 +:109AB00019F92046BDE81040002100F013B970B537 +:109AC0000446808886B00D4620F03F06684600F0C8 +:109AD0009FF84D490298B0FBF1F189B20E43A68080 +:109AE000228822F001022280484B2A689A421CD820 +:109AF0005200B0FBF2F080B2042800D20420491CCE +:109B00002184A083208840F00100208021884FF626 +:109B1000F5300140A8886A89104308432080A8894D +:109B200029890843208106B070BDEB88A3F53F4624 +:109B3000FF3E05D102EB4202B0FBF2F080B208E03A +:109B400002EBC20303EB0212B0FBF2F080B240F46E +:109B50008040020501D140F001004FF4967251435C +:109B60004FF47A72B1FBF2F140F40040C7E741F2E2 +:109B700088310160002181804BF6FF72C280018133 +:109B800041814FF48041818170470029018802D0D2 +:109B900041F0010101E021F001010180704700293D +:109BA000018802D041F4807101E021F480710180CC +:109BB00070470029018802D041F4007101E021F4CE +:109BC0000071018070470029018802D041F4806152 +:109BD00001E021F4806101807047002A828801D071 +:109BE0000A4300E08A438280704701827047008AFE +:109BF000C0B2704712B141F0010101E001F0FE0175 +:109C0000018270470054004040420F00A0860100CE +:109C100030B53C494A683C4B12F00C0405D03B4A35 +:109C2000042C126803D0082C24D0036000E00260EA +:109C30004A680F2303EA1212354B9C5C0268E2402B +:109C400042604C68072505EA14241C5D22FA04F4DE +:109C500084604C6805EAD4241B5DDA40C260496820 +:109C6000032303EA91312A4B1B1F595CB2FBF1F12C +:109C7000016130BD4B684C6803F470134FF002056E +:109C800014F4803F05EB934305D04C68A40300D542 +:109C900052085A43CBE71F4A5343C6E7194A0029E3 +:109CA000516901D0014300E0814351617047154A79 +:109CB0000029916901D0014300E08143916170471F +:109CC000104A0029D16901D0014300E08143D161EC +:109CD00070470C4A0029D16801D0014300E081435C +:109CE000D1607047074A0029116901D0014300E0A3 +:109CF0008143116170470348416A41F080714162BC +:109D0000704700000010024000127A000C0400208E +:109D10002404002000093D0030B50288FD4BFE4CB4 +:109D200098420DD0A0420BD0B0F1804F08D0FB4D2F +:109D3000A84205D0FA4DA84202D0FA4DA84203D15C +:109D400022F070054A882A43F74DA84206D0F74D05 +:109D5000A84203D022F44075CA882A4302808A8828 +:109D600082850A88028598420AD0A04208D0F04A2B +:109D7000904205D0EF4A904202D0EF4A904201D182 +:109D8000097A01860121818230BD30B5028C22F032 +:109D900001020284028C8388048B22F0020224F0E8 +:109DA00073050C882C430D8915434A882A43D94DE5 +:109DB000A8420BD0D84DA84208D0DD4DA84205D00E +:109DC000DC4DA84202D0DC4DA8420DD122F008059E +:109DD0004A8923F440732A4322F004058A882A43DF +:109DE0008D891D43CB892B4383800483C988818659 +:109DF000028430BD70B5028C22F010020284028C05 +:109E00008488038B0D8823F4E6464FF6FF7303EA3C +:109E1000052535430E8922F0200203EA0616164373 +:109E20004A8803EA02123243BA4EB04202D0BA4E16 +:109E3000B04215D122F080064A8924F4406403EA36 +:109E40000212324322F040068A8803EA02123243A9 +:109E50008E8903EA86062643CC8903EA84043443C8 +:109E600084800583C9880187028470BD70B5028C27 +:109E700022F480720284028C8488838B0D8823F004 +:109E800073031D4322F400730E894FF6FF7202EA3A +:109E900006261E434B8802EA032333439D4EB042FD +:109EA00002D09D4EB04215D123F400664B8924F4B4 +:109EB000405402EA0323334323F480668B8802EA8A +:109EC000032333438E8902EA06162643CC8902EA2D +:109ED0000414344384808583C9888187038470BDDA +:109EE00070B5028C22F480520284048C8288838BA9 +:109EF0000D8823F4E6464FF6FF7303EA0525354344 +:109F000024F400560C8903EA043434434E8803EAEF +:109F1000063626437F4CA04202D07F4CA04205D19A +:109F200022F480448A8903EA821222438280858354 +:109F3000C988A0F84010068470BD828B22F440626C +:109F40008283828B4FF6FF7303EA01210A438283E7 +:109F50007047828B22F00C028283828B0A438283B9 +:109F60007047028B22F440620283028B4FF6FF732C +:109F700003EA01210A4302837047F0B5048C24F000 +:109F800010040484078B048C4FF6FF7527F4734785 +:109F900005EA03333B4305EA02221A435D4B05EA17 +:109FA000011698420ED05C4B98420BD0B0F1804F16 +:109FB00008D05A4B984205D0594B984202D0594B81 +:109FC000984205D124F02001314341F0100104E012 +:109FD00024F0A0030B4343F0100102830184F0BD81 +:109FE000028B22F00C020283028B0A430283704729 +:109FF00070B5048C24F001040484058B048C4FF6A6 +:10A00000FF7606EA0313134325F0F305414A2B4379 +:10A0100090420ED0404A90420BD0B0F1804F08D011 +:10A020003E4A904205D03E4A904202D03D4A90427C +:10A0300002D124F0020201E024F00A020A4342F0B5 +:10A0400001010383018470BD2DE9F05F0D460446D4 +:10A050000888304FDFF8C0C0DFF8C0804988AA8880 +:10A060002B894FF0804960B3042832D04FF6FF7E31 +:10A07000082836D0208C9B4620F480502084A38B67 +:10A08000268C704600EA022223F473431A4300EA46 +:10A090000B3010430EEA013EBC420BD0644509D0A0 +:10A0A0004C4507D0444505D01D4A944202D01D4B73 +:10A0B0009C425AD126F4005141EA0E0141F48051EC +:10A0C00058E02046FFF794FFE9882046BDE8F05F9E +:10A0D00086E72046FFF751FFE9882046BDE8F05F9C +:10A0E0003FE7208C20F480702084B4F81CA0208CE2 +:10A0F0000EEA031313432AF0F30A0EEA012B43EA94 +:10A100000A03BC4220D064451ED04C451CD04445B7 +:10A110001AD013E0002C014000340140000400403C +:10A1200000080040000C00400010004000140040F7 +:10A13000004001400044014000480140494A944227 +:10A1400002D0494A944204D120F4007040EA0B0046 +:10A1500002E020F42060084340F48070A383208450 +:10A16000E9882046BDE8F05FF3E626F402420A43A0 +:10A1700042F48051A08320462184E988BDE8F05F45 +:10A18000DBE64FF6FF71818000210180C1804180B4 +:10A19000017270470021018041808180C18001816E +:10A1A00041818181C181704700210180418001226C +:10A1B0008280C180018170470029018802D041F06E +:10A1C000010101E021F0010101807047002930F810 +:10A1D000441F02D041F4004101E0C1F30E010180AF +:10A1E0007047002A828901D00A4300E08A438281B5 +:10A1F0007047028B22F008020A4302837047028BE9 +:10A200004FF6FF7322F4006203EA01211143018338 +:10A210007047828B22F008020A4382837047828B48 +:10A220004FF6FF7322F4006203EA01211143818398 +:10A230007047808E7047008F7047808F7047B0F8EE +:10A240004000704702460020138A92890B4202EABE +:10A25000010202D0002A00D001207047C9430182C8 +:10A260007047000000080040000C004030B5044674 +:10A27000008A85B00D464CF6FF710840E98801431D +:10A280002182A1894EF6F3100140A8882A89104343 +:10A290006A890A431043A081A08A4FF6FF41084013 +:10A2A000A9890143A1826846FFF7B2FC3048844285 +:10A2B00001D1039800E00298A1890904002900EB6C +:10A2C000C00101EB0010296802DA4FEA410101E008 +:10A2D0004FEA8101B0FBF1F06422B0FBF2F14FEAEA +:10A2E00001114FEA11136FF018056B4300EB830067 +:10A2F000A3891D044FF0320306D503EBC000B0FB69 +:10A30000F2F000F0070005E003EB0010B0FBF2F004 +:10A3100000F00F000843208105B030BD002981897D +:10A3200002D041F4005101E021F4005181817047D5 +:10A3300010B5C1F3421301F01F040121A140012B0C +:10A3400007D0022B07D01430002A026805D00A4338 +:10A3500004E00C30F8E71030F6E78A43026010BDE5 +:10A36000002A828A01D00A4300E08A438282704731 +:10A370000038014010B58A0721F003040649130F85 +:10A3800021440F228C689A4094438C608A689840DC +:10A3900002438A6010BD000000000140394838497E +:10A3A00041603949416070473648016941F0800198 +:10A3B0000161704733490420CA68D20701D00120E7 +:10A3C0007047CA68520701D502207047C968C9069C +:10A3D000FBD50320704700B50346FFF7EBFF02E013 +:10A3E000FFF7E8FF5B1E012803D0002B00D10520FA +:10A3F00000BD002BF4D1FAE770B505464FF43026C6 +:10A400003046FFF7E8FF042811D11E4C206940F0C8 +:10A41000020020616561206940F040002061304603 +:10A42000FFF7D9FF216941F6FD721140216170BD2E +:10A43000F8B5064600204FF4005C00900D466046DB +:10A44000FFF7C9FF042816D10E4C206940F0010027 +:10A45000206135806046FFF7BEFF41F6FE77042895 +:10A4600006D1B61C280C009630806046FFF7B3FF7B +:10A47000216939402161F8BD0249C8607047000078 +:10A480002301674500200240AB89EFCD14481549F0 +:10A49000026800608A4203D013488047134800478F +:10A4A000134E4FF0090030601248016821F07061CE +:10A4B000016041020160104C182020600F491048D3 +:10A4C00008601048D0F800D040680047FEE7FEE77B +:10A4D000FEE7FEE7FEE7FEE7FEE7FEE7FEE7FEE754 +:10A4E000F04F0020EFBEADDE0D950008ED00000836 +:10A4F0001810024004000140140C0140000C0140FF +:10A500004434434400F0FF1F2A4910B588420AD161 +:10A51000841401212046FFF7DCFB2046BDE81040F3 +:10A520000021FFF7D6BB2449884202D1012104143F +:10A5300004E0224988420AD10121C4132046FFF7D2 +:10A54000D1FB2046BDE810400021FFF7CBBB10BD7A +:10A5500030B502884C8802F441530A88CD882243E2 +:10A560008C882C4322430C8922434C8922438C89BA +:10A570002243CC8922431A430280828B22F4006258 +:10A580008283098A018230BD0029018802D041F00E +:10A59000400101E021F04001018070478181704756 +:10A5A000808970470246002012890A4200D00120AB +:10A5B000704700000030014000380040003C00407F +:10A5C00000487047ACD00008A0F16101192900D8FB +:10A5D000203870472DE9F05F994615460F468346AF +:10A5E0004FF0FF36DDF828A011E0A819441009FB50 +:10A5F000047080460146584652469047002802D0D3 +:10A6000004DA254603E04046BDE8F09F2646A5EB68 +:10A6100006000128E9DC0020F6E740EA01039B0779 +:10A6200003D009E008C9121F08C0042AFAD203E0C7 +:10A6300011F8013B00F8013B521EF9D27047D2B22B +:10A6400001E000F8012B491EFBD270470022F6E71B +:10A6500010B513460A4604461946FFF7F0FF204698 +:10A6600010BD421E12F8013F002BFBD111F8013B37 +:10A6700002F8013B002BF9D1704730B505462A4658 +:10A680000B4612F8010B13F8014B08B1A042F8D0A9 +:10A690001CB1002802D06D1CF1E7284630BD10B572 +:10A6A000044604E00B7800F8013B03B1491C521E3C +:10A6B000F8D2204610BDCAB2401E10F8011F8A42CF +:10A6C00002D00029F9D100207047421C10F8011B6C +:10A6D0000029FBD1801A70472DE9F0410546002082 +:10A6E00090460E46044600E0641C44450BD2285DAB +:10A6F00000F058F90746305D00F054F9381A02D1DD +:10A70000295D0029F0D1BDE8F08170B5064600F062 +:10A7100059FC046805460A220021304600F048F939 +:10A720002C6070BDF0B480EA0102D40F4200B2EB9D +:10A73000410F02D20246084611464A0042D0C30DDC +:10A74000DDB2C1F3C752AD1A202D35DAC1F31601BF +:10A7500041F4000204B15242C5F1200602FA06F1AA +:10A760002A411044B3EBD05F23D0C4B1012DA0EB3C +:10A77000C35009DCF0BC4FF0004202EAC35200F5BE +:10A780000000DBB200F055B9400000F1807000EB32 +:10A79000C350A0F1807040EAD170490009E0490837 +:10A7A00041EAC071A0EBC35000F50000400800EB87 +:10A7B000C350F0BC00F034B96142012202EB410108 +:10A7C000001BF6E7F0BC704781F00041AAE780F07B +:10A7D0000040A7E780EA010210B502F00043400004 +:10A7E00026D04A0023D04FEA106101EB1261C0F37A +:10A7F0005600C2F3560240F4000042F40002A0FBEF +:10A800000220A1F17F014FEA0040140401D000F1C1 +:10A81000010050EA124001D44000491EC2B20C06A9 +:10A8200004EBD010401C4008802A02D003E0002036 +:10A8300010BD20F00100002900DA0020184310BDEF +:10A8400030B480EA010202F0004530F0004221F00D +:10A85000004015D0A0B1C0F3C753C2F3C754C2F330 +:10A860001601C0F31600E41A41F4000140F400029E +:10A870007D34914201D3641C00E04900002C02DACF +:10A8800030BC002070474FF400000023914201D3F8 +:10A89000891A034340084FEA4101F7D151B191426F +:10A8A00002D14FF0004105E002D24FF0010101E07A +:10A8B0006FF0010103EBC450284430BC00F0B0B885 +:10A8C000420005D0C0F3C7525242914201DC002041 +:10A8D000704700EBC1507047C10F80EAE070084438 +:10A8E000CA079623002100F0A4B89623002211463F +:10A8F00000F09FB800F0004220F00040C10DC0F30E +:10A90000160040F400007F2901DA002070479629E4 +:10A9100003DCC1F19601C84001E096398840002A65 +:10A92000F4D04042704720F00040C10DC0F3160043 +:10A9300040F400007F2901DA00207047962903DCEB +:10A94000C1F19601C84070479639884070470000B1 +:10A95000002801DBC0F10040002901DBC1F100410A +:10A9600081427047002801DBC0F10040002901DB73 +:10A97000C1F100418842704730B50B4601460020C6 +:10A980002022012409E021FA02F59D4205D303FAB1 +:10A9900002F5491B04FA02F52844151EA2F1010232 +:10A9A000F1DC30BDA0F14101192900D820307047F9 +:10A9B0002DE9F04791460F4680460446002614F8DC +:10A9C000015B2DB1FFF7FCFD0068405DC007F6D1CB +:10A9D0002B2D02D02D2D18D0641E4A463946204614 +:10A9E00000F0E1F927B13968A14201D1C7F8008030 +:10A9F00071054FF002040BD54042002803DD00F042 +:10AA0000E1FA0460A007BDE8F08746F48066E4E759 +:10AA10000028F8DA00F0D6FA04606FF00040F2E7A0 +:10AA20000029A8BF7047401C490008BF20F0010062 +:10AA3000704710B4B0FA80FC00FA0CF050EA010440 +:10AA400004BF10BC704749B1CCF1200421FA04F4D2 +:10AA500011FA0CF118BF012121430843A3EB0C01AB +:10AA6000CB1D0106000A002BBEBF002010BC7047A2 +:10AA700000EBC35010440029A4BF10BC7047401C19 +:10AA8000490008BF20F0010010BC7047F0B4002856 +:10AA900002DCF0BC00207047C0F3C751C0F31600C1 +:10AAA00040F40000CA0701D14000491E3F2202EBDA +:10AAB0006105002211464FF4000626FA01F3134403 +:10AAC000D418844201D8001B1A464000491C17299B +:10AAD000F3DD5100814202D24FF0FF3100E000214E +:10AAE00002EBC550F0BCFFF79BBF10B541000CD086 +:10AAF000C0F3C751962908DC7E2909DC06DB410238 +:10AB000004D000F0004040F07E5010BD002010BD89 +:10AB1000C1F19604C4F1200100FA01F1E040FFF711 +:10AB20007FFFA04010BD2DE9FE4F804681EA030063 +:10AB3000C00F0C46009021F0004123F00045B8EB17 +:10AB40000200A94105D24046214690461C460B46CC +:10AB5000024623F00040104304D14046214603B092 +:10AB6000BDE8F08F270DC7F30A00C3F30A51029026 +:10AB7000401A0190402866DAC3F3130040F4801BAA +:10AB80000098924620B10023D2EB030A63EB0B0B33 +:10AB900001985946C0F14002504600F0D3F80646ED +:10ABA0000D4650465946019A00F0EBF810EB0800AC +:10ABB0006141002487EA115284EAE7731A433BD0CB +:10ABC000009A3AB3019A012A4FEA075210DC001B9F +:10ABD00061EB02014FF0004202EA0752CDE9004268 +:10ABE000001C41F5801132462B4600F038F9B6E7DB +:10ABF000001B61EB0201001C41F5801300185B4152 +:10AC00002018A2F5001747EB030140EAD570B619EA +:10AC10006D4111E06D084FEA360645EAC0754FEA0E +:10AC20000752001B61EB0201001C41F5801149082D +:10AC30004FEA30000019514132462B4603B0BDE8BF +:10AC4000F04F00F0FFB80098012240000023D0EB45 +:10AC5000020263EBE073009821464FEAE074B8EB20 +:10AC6000000061EB0401E9E783F000435BE781F05A +:10AC7000004158E710B500F0004420F00040C20D3C +:10AC8000C0F3160040F400007F2A07DA7D2A00DABC +:10AC90007D22763A00FA02F1002008E0962A09DCCB +:10ACA000A2F1760100FA01F1C2F19602D040FFF75D +:10ACB000B7FE01E0963A9040002C00D0404210BD13 +:10ACC00000F0004230F000400AD0C10D01F5607183 +:10ACD000C0F3160042EA0151C20840071143704711 +:10ACE00000200146704701F0004330B421F00041DC +:10ACF00050EA010206D00A0DA2F56072C1F31301F9 +:10AD0000002A02DC30BC00207047440F44EAC10432 +:10AD1000C100E01830BC00EBC250FFF781BE00005C +:10AD2000064C074D06E0E06840F0010394E8070098 +:10AD300098471034AC42F6D3F5F7DCF9BCD90008DB +:10AD4000DCD90008202A04DB203A00FA02F10020B6 +:10AD500070479140C2F1200320FA03F31943904059 +:10AD60007047202A04DB203A21FA02F000217047C4 +:10AD700021FA02F3D040C2F1200291400843194663 +:10AD80007047202A06DBCB17203A41FA02F043EA4B +:10AD9000E07306E041FA02F3D040C2F12002914094 +:10ADA0000843194670472DE9F05F82460078002776 +:10ADB00015468B460AF10104B946302801D09DB1F1 +:10ADC00013E014F8010B0127782803D0582801D08C +:10ADD00045B10AE00DB1102D07D10027102514F858 +:10ADE000010B02E0082500E00A250026B0460EE02F +:10ADF00005FB080005FB06F1012701EB10461FFAD1 +:10AE000080F8B6F5803F00D3B94614F8010B294607 +:10AE100000F077F80028EBDABBF1000F05D00FB196 +:10AE2000641E00E05446CBF80040B9F1000F06D094 +:10AE300000F0C8F802210160C81EBDE8F09F48EA92 +:10AE40000640FAE710B5002B08DA401C41F100017A +:10AE500092185B411A4301D120F0010010BD2DE989 +:10AE6000F04D92469B4611B1B1FA81F202E0B0FA80 +:10AE700080F220329046FFF765FF04460F4640EA15 +:10AE80000A0041EA0B0153465A46084303D12046C3 +:10AE90003946BDE8F08D114653EA010015D0C8F1DE +:10AEA00040025046FFF75DFF05460E4650465946A4 +:10AEB0004246FFF747FF084301D0012000E0002091 +:10AEC000054346EAE0762C4337430A984FEA445359 +:10AED000A0EB08004FEAD4240A304FF0000244EA05 +:10AEE00047544FEAD72502D500200146D1E7010596 +:10AEF00010196941DDE9084500196941BDE8F04DC7 +:10AF0000A0E73A2800D2303820F02002412A01D3AD +:10AF1000A2F13700884201D34FF0FF30704770B57F +:10AF200001EB020410F8015B15F0070301D110F8E2 +:10AF3000013B2A1106D110F8012B03E010F8016B38 +:10AF400001F8016B5B1EF9D12B0705D40023521EBB +:10AF50000FD401F8013BFAE710F8013B02F10202BD +:10AF6000A1EB030303E013F8015B01F8015B521E40 +:10AF7000F9D5A142D6D3002070BD00000FB4054B17 +:10AF800010B503A9044A029800F0E8F810BC5DF877 +:10AF900014FB0000152300083404002041000802BF +:10AFA00018BF04200A0E18BF40F001004FF07F4286 +:10AFB00032EA010108BF40F00200012808BF052065 +:10AFC0007047000000487047380400206FF05E01B1 +:10AFD0000807FFF775BC00002DE9F04D0E4614463A +:10AFE0004FF07F41B1EB440F9EBF4FF0FF31316016 +:10AFF000BDE8F08D4FF0004040EA0421C4F3C75093 +:10B000007838431100F01F00DFF814C1C0F12002AE +:10B01000FC445CF823500CEB83038540D3F804C058 +:10B020002CFA02F72F439D680CFA00FC25FA02F86F +:10B03000DB6805FA00F023FA02F240EA02054CEA66 +:10B04000080CA7FB0132ACFB01C0A5FB015101EBD1 +:10B050000C058D4234BF4FF0010C4FF0000CC118AD +:10B060006144BCF1000F02D0814202D903E0814269 +:10B0700001D2012000E00020104400F120024FEA3C +:10B0800092188006CA0C40EA42304F03C6F800808E +:10B09000FFF722FC82463846FFF727FC6FF01201CB +:10B0A000FFF70EFC07462846FFF71FFC6FF025014F +:10B0B000FFF706FC834639465046FFF733FB5946F7 +:10B0C000FFF730FB00F500656FF30B05514628468E +:10B0D000FFF77AFB3946FFF777FB5946FFF777FB17 +:10B0E0001049FFF777FB07460F492846FFF772FB29 +:10B0F0003946FFF717FB07460C492846FFF76AFB5E +:10B100003946FFF70FFB14F0004F08BFBDE8F08D84 +:10B11000C8F1805180F000403160BDE8F08D000042 +:10B120009C200000DB0FC92F22AAFD290000C92F97 +:10B1300002E008C8121F08C1002AFAD17047704700 +:10B14000002001E001C1121F002AFBD1704700005E +:10B150000149086070470000380400202DE9FF4FC6 +:10B160008BB09A460F4605460026C9E0252837D100 +:10B1700000246D1C6649A04601222B78203B02FA70 +:10B1800003F0084202D004436D1CF6E728782E280D +:10B1900017D115F8010F44F004042A280ED06FF0DF +:10B1A0002F022878A0F1300109290AD808EB88017C +:10B1B00002EB410100EB01086D1CF2E757F8048B2C +:10B1C0006D1C287869283FD006DC002871D06328E0 +:10B1D0000CD0642804D137E0732811D075284ED0E4 +:10B1E00052460D99904706F1010688E017F8040BC6 +:10B1F0008DF8000000208DF80100E946012003E0F1 +:10B2000057F8049B4FF0FF3061074FF0000401D462 +:10B210000AE0641C44450DDA8442FADB19F8041094 +:10B220000029F6D106E0641C8442FCDB19F8041006 +:10B230000029F8D1264404E019F8010B52460D9973 +:10B240009047641EF8D25AE001CF4FF00A0B002855 +:10B2500004DAC0F100004FF02D0102E0210504D511 +:10B260002B218DF82410012103E0E10705D02021D6 +:10B27000F7E70DF1200908910CE00021F9E701CF73 +:10B280004FF00A0BF9E75946FFF776FB01F1300260 +:10B2900009F8012D0028F6D1ADEB090000F1200BD3 +:10B2A000600701D44FF00108D84503DDA8EB0B007F +:10B2B00001E029E000208046002406E009A852466B +:10B2C000005D0D999047761C641C08988442F5DB5C +:10B2D00004E0302052460D999047761CB8F10001E9 +:10B2E000A8F10108F5DC05E019F8010B52460D99AB +:10B2F0009047761CBBF10001ABF1010BF4DC6D1C37 +:10B30000287800287FF432AF0FB03046BDE8F08FC8 +:10B31000092801002DE9F0474FF0684202EB400395 +:10B320000C460546B3F1654F3CBF02EB4102B2F15A +:10B33000654F3FD34FF07F42B2EB400F28BFB2EBD7 +:10B34000410F03D2BDE8F047FFF7ECB940EA010333 +:10B350005B0008BF44F0FF410AD0B2EB400F08BFCA +:10B36000B2EB410F06D125F0804024F08041054624 +:10B370000C461FE0B2EB400F12BF5FEA410245F0FE +:10B38000FF4004F0004115D04FEA410292EA400329 +:10B3900010D4002AB4BF4FF03E564FF09F463146BE +:10B3A000FFF718FA054631462046FFF713FA044620 +:10B3B00028462146C0F3C753C1F3C7529A1A1B2A25 +:10B3C00006DD10F0004F14BF54485548BDE8F08723 +:10B3D00012F11A0F17DA11F0004F06D010F0004FDB +:10B3E0000CBF50485048BDE8F08721462846FFF77B +:10B3F00027FA0446FFF7D2FD042808BFFFF7E6FD51 +:10B400002046BDE8F0874200B2EB410F25D910F08D +:10B41000004F19BF454F464E464F474E224685F0D6 +:10B42000004415460A4680F0004110460A1A5200B0 +:10B43000B2F1807F3ED248404049DFF804A110F0CD +:10B44000004F18D04FF03F483846FFF7BDF9074688 +:10B4500051463046FFF7B8F917E011F0004F04BF2E +:10B4600000263746E2D010F0004F19BF354F364E58 +:10B47000364F374EDAE74FF07C583846FFF752F92F +:10B48000074651463046FFF74DF9064641462846E5 +:10B49000FFF7A0F92146FFF745F9824621464046CD +:10B4A000FFF798F92946FFF792F95146FFF7C8F9D7 +:10B4B000044604E021462846FFF7C2F90446014647 +:10B4C000FFF788F980462349FFF784F92249FFF7FF +:10B4D00029F94146FFF77EF92049FFF723F9414654 +:10B4E000FFF778F91E49FFF71DF94146FFF772F99A +:10B4F0001C49FFF717F9054641462046FFF76AF950 +:10B500002946FFF767F93146FFF70CF92146FFF7A7 +:10B5100009F93946BDE8F047FFF704B9DB0FC9BFA9 +:10B52000DB0FC93FDB0F4940DB0F49C00000C9BF3B +:10B5300022AAFDB90000C93F22AAFD390060ED3EF4 +:10B54000C30ACE37000049C022AA7DBA0000494094 +:10B5500022AA7D3A2DAD65BD8FB8D53D0FB511BE80 +:10B5600061C84C3EA8AAAABE2DE9F843044602468B +:10B5700050486946B0EB420F09D94FF0E640B0EBB6 +:10B58000420F94BF00204FF0FF30009034E04A4B50 +:10B5900022F0004083422BD948492046FFF71AF990 +:10B5A000FFF7A3FA8046FFF7A5F900F0030000902B +:10B5B00043494046FFF70EF9054642494046FFF72A +:10B5C00009F9064640494046FFF704F907463F4956 +:10B5D0004046FFF7FFF82146FFF7F9F83946FFF735 +:10B5E000F3F83146FFF7F0F82946FFF7EDF802E0EF +:10B5F0001046FFF7F1FC04462546009C002C18DAA3 +:10B600006800B0F17F4F3CBF4FF07E50BDE8F8833B +:10B6100009D14FF00100FFF79BFDBDE8F843002181 +:10B620000846FFF70DB92846BDE8F8430121FFF7AA +:10B6300047B9294614F0010F08461CD0FFF7CAF895 +:10B6400006462349FFF7C6F82249FFF7C0F83146FE +:10B65000FFF7C0F82049FFF765F83146FFF7BAF861 +:10B660002946FFF7B7F82946FFF75CF814F0020FF8 +:10B670001CD0BDE8F883FFF7ADF805461749FFF782 +:10B68000A9F81749FFF74EF82946FFF7A3F815491F +:10B69000FFF748F82946FFF79DF84FF07E51FFF776 +:10B6A00041F814F0020F08BFBDE8F88380F00040B5 +:10B6B000BDE8F883B61F927E490E494683F9223FC2 +:10B6C0001A61342C0020A23300A0FD390000C93FCC +:10B6D000336D4C39DA82083CA0AA2ABEB93AB2BA14 +:10B6E000CA9F2A3DDDFFFFBE70B50546FFF7C2FACF +:10B6F00004464000801C0DD12846FFF7F6F90546A8 +:10B700002046FFF7E9F82946FFF722F91CBF012080 +:10B71000FFF71EFD204670BD2DE9F04D0F460E4689 +:10B72000A0F50001804604464FF0007084B04FF051 +:10B730007E554FF0000B00EB47004FF07F4AB1F110 +:10B74000FE4F04D2B0F1804F80F0018141E0B0F1B2 +:10B75000804F3ED304F1FF40B0F1FE4F1FD200BF37 +:10B7600028F00048C6F3C75044467F2809DB9728D5 +:10B770007DDAC0F19600012101FA00F0411E31424C +:10B7800009D00120FFF7E4FC04B00021BDE8F04D32 +:10B790000846FFF755B8304218BFFE4DD7E06000AD +:10B7A00000281CBF4FF08070B0EB440F0BD91B2159 +:10B7B0004046FFF785F8804604466FF01A0B10F0FC +:10B7C000004FCDD1C3E0A4F50000B0F1FE4F1BD275 +:10B7D000BDE0B0F1007F11D300213846FFF7B8F883 +:10B7E00006D16000002818BFBAEB440F71D8B1E74A +:10B7F00006F0004040F0FC563746ABE7B0F1807FE2 +:10B8000038BFA6F50007A5D324F000406FF0FF4233 +:10B81000E14B8118994210D326F000410A449A4224 +:10B820000BD3B4F17E5F18BF5FEA460251D0B0F18E +:10B83000FF4F98BFB1F1FF4F06D904B039464046DB +:10B84000BDE8F04DFEF76EBFB4F1FF4F10D0C6F368 +:10B85000C7507F2809DB972812DAC0F19600012132 +:10B8600001FA00F0411E314206D0002009E06EE0EE +:10B8700016F0004F5DD127E0304218BF012000D103 +:10B88000022014F5000F13D024B3B4F1004F27D0D9 +:10B8900014F1814F56D04FF0FE40B0EB440F94BFEF +:10B8A00001200020012101EBE671884241D10BE02B +:10B8B00016F0004F02D001283FD03AE0012802BF25 +:10B8C000B64804B0BDE8F08D4FF0FF4004B0BDE8CD +:10B8D000F08D37E016F000400ED104B0BDE8F08DD9 +:10B8E000B6F1FF4F25D016F5000F05D016F0004F2A +:10B8F00018D008B101280AD00220FFF729FC04B0B3 +:10B900000021BDE8F04D4FF07E50FEF799BF0220B8 +:10B91000FFF71EFC04B04146BDE8F04D4FF07E50ED +:10B92000FEF78EBF002804BF04B0BDE8F08D0128EB +:10B9300003D004B00020BDE8F08D04B04FF000400B +:10B94000BDE8F08D04B04FF07E50BDE8F08D944816 +:10B950002044B0F5005F44D84046FFF7B1F900221B +:10B96000904BFFF781F9FFF7BEF904466FF0010134 +:10B97000FEF7A6FF8C49FEF72AFF2146FEF72AFFB5 +:10B980004FF07C51FEF723FF064621460846FEF79E +:10B9900021FF80F000403146FEF71CFF80468349BE +:10B9A0002046FEF717FF064681494046FEF712FF84 +:10B9B000804680492046FEF70DFF4146FEF7B2FE65 +:10B9C000044601463046FEF7ADFE00F5006B6FF30E +:10B9D0000B0B59463046FEF7F7FE2146FEF7A2FE56 +:10B9E000D4E004F58020C00C00F00F06C0F307106F +:10B9F0007F38A4EBC05483443046FEF76DFF6FF0F0 +:10BA00000301FEF75DFF4FF07E51FEF78BFE01460E +:10BA100002902046FEF7D8FE019020460299FEF7DC +:10BA200081FE00F500686FF30B0800904146029814 +:10BA3000FEF7CAFE2146FEF775FE02904FF07E50DB +:10BA40000099FEF7FDFE014600900198FEF7C2FE48 +:10BA500000F500646FF30B0420460299FEF7BAFE6E +:10BA6000029041462046FEF7B5FE0199FEF7AFFE73 +:10BA70000299FEF7A9FE0099FEF7ACFE0146009080 +:10BA80002046FEF74FFE0146FEF7A4FE80464A49D7 +:10BA9000FEF7A0FE4449FEF745FE4146FEF79AFE3A +:10BAA000804600212046FEF70BFF019020460099BA +:10BAB000FEF738FE4146FEF78DFE04460021009851 +:10BAC000FEF7FEFE2146FEF72DFE80460146019858 +:10BAD000FEF728FE00F500646FF30B042146019881 +:10BAE000FEF772FE4146FEF71DFE804633492046B2 +:10BAF000FEF770FE009032494046FEF76BFE80462E +:10BB000030492046FEF766FE4146FEF70BFE8046B2 +:10BB100001460098FEF706FE00F500646FF30B0483 +:10BB200021460098FEF750FE4146FEF7FBFD804699 +:10BB30002548784450F8361000EBC600019146685D +:10BB40004FEA0B10FEF7C8FE009031464046FEF764 +:10BB5000E9FD2146FEF7E6FD0199FEF7E3FD0099B8 +:10BB6000FEF7E0FD00F5006B6FF30B0B58460099F4 +:10BB7000FEF72AFE0199FEF727FE2146FEF724FE76 +:10BB80003146FEF721FE4146FEF721FE804607F5CD +:10BB900000641BE0000080BFFFFF3F00000080FF4B +:10BBA000001080C00000F03FABAAAA3E00B0B84130 +:10BBB0003BAAB841D49A38BB7EE24C3E00B0384232 +:10BBC0003BAA3842D49AB8BBB21300006FF30B04FF +:10BBD00021463846FEF7F8FD074621465846FEF74F +:10BBE000F9FD064639462046FEF79CFD4146FEF724 +:10BBF000F1FD044639465846FEF7ECFD2146FEF7B6 +:10BC000091FD074601463046FEF78CFD00F50064C5 +:10BC10006FF30B0421463046FEF7D6FD3946FEF79A +:10BC200081FD804601462046FEF77CFDFFF722F8A5 +:10BC300007460611FEF750FE2146FEF7C8FD4146B5 +:10BC4000FEF770FD04463549FEF7C4FD3449FEF7A2 +:10BC500069FD2146FEF7BEFD3249FEF763FD214630 +:10BC6000FEF7B8FD0146304807F00F04784450F85D +:10BC70002400FEF7AFFD2D49794451F82410FEF75A +:10BC800051FD2B49794451F82410FEF74BFD06F184 +:10BC90007D01FC2908D23146FEF712FE04B0294688 +:10BCA000BDE8F04DFEF796BD06F1BF01B1F5BF7FCF +:10BCB00016D83146FEF704FE2946FEF78BFD0446F2 +:10BCC000BAEB440F1AD060000CD02046FFF766F99B +:10BCD000042808BFFFF77AF9204604B0BDE8F08DCC +:10BCE000002E0BDA0220FFF733FAFFF76FF9014657 +:10BCF000284604B061F31E00BDE8F08D0220FFF776 +:10BD000027FA61214FF0E040FEF7DAFD01462846B0 +:10BD100004B061F31E00BDE8F08D0000FC596337EC +:10BD2000C9FF753A1872313D781300002C130000DA +:10BD3000E01200002DE9F8430446024653486946E4 +:10BD4000B0EB420F09D94FF0E640B0EB420F94BF81 +:10BD500000204FF0FF30009034E04D4B22F00040C7 +:10BD600083422BD94B492046FEF734FDFEF7BDFE3A +:10BD70008046FEF7BFFD00F00300009046494046B4 +:10BD8000FEF728FD054645494046FEF723FD0646D9 +:10BD900043494046FEF71EFD074642494046FEF72E +:10BDA00019FD2146FEF713FD3946FEF70DFD31461C +:10BDB000FEF70AFD2946FEF707FD02E01046FFF7F1 +:10BDC0000BF904462546009C002C1DDA6800B0F1F2 +:10BDD0007F4F09D22846FFF7E1F8042808BFFFF794 +:10BDE000F5F82846BDE8F88308D10120FFF7B0F93F +:10BDF000BDE8F84300210846FEF722BD2846BDE80D +:10BE0000F8430121FEF75CBD294614F0010F0846F6 +:10BE10001ED0FEF7DFFC05462349FEF7DBFC234975 +:10BE2000FEF780FC2946FEF7D5FC2149FEF77AFC97 +:10BE30002946FEF7CFFC4FF07E51FEF773FC14F05D +:10BE4000020F08BFBDE8F88380F00040BDE8F8832A +:10BE5000FEF7C0FC06461749FEF7BCFC1649FEF784 +:10BE6000B6FC3146FEF7B6FC1449FEF75BFC3146E2 +:10BE7000FEF7B0FC2946FEF7ADFC2946FEF752FC62 +:10BE800014F0020FE0D1BDE8F8830000B61F927EE7 +:10BE9000490E494683F9223F1A61342C0020A2330F +:10BEA00000A0FD390000C93FB93AB2BACA9F2A3D85 +:10BEB000DDFFFFBE336D4C39DA82083CA0AA2ABEF2 +:10BEC00070B50546FEF7E2FD044620F00040C0F1E3 +:10BED000FF40C00F08D025F00040C0F1FF40C00F68 +:10BEE00004BF0120FFF734F9204670BD5FD1000880 +:10BEF000AFD10008F5D100085CD1000863D100087B +:10BF000005D1000800D1000850D10008F5D0000884 +:10BF1000EFD1000808D10008C0D1000804D2000801 +:10BF20001FD100088DD100082CD10008EED00008E8 +:10BF300086D10008000000009BD10008DFD1000876 +:10BF40006AD10008FBD10008B5D10008E4D100088F +:10BF500038D1000847D10008DBD1000816D100080D +:10BF6000CAD100080ED20008D0D100089FD1000825 +:10BF700013D100087BD1000800000000AAD10008FE +:10BF80000FD10008A5D1000828D10008CAD10008A7 +:10BF9000DBD10008000000003DD80008F8D0000800 +:10BFA000DFD00008FDD70008E7D000085FD3000805 +:10BFB0000000000018D80008ABD7000833030008C1 +:10BFC00013D80008A5D6000887030008F8D6000893 +:10BFD00059D70008A906000875D600088CD50008B6 +:10BFE0005B07000826D700083DD80008D1080008E4 +:10BFF00088D30008F7D40008F108000870D60008BC +:10C000003DD80008BD0900086CD600087AD60008A3 +:10C01000E9090008B3D6000876D70008730C0008B9 +:10C0200010D30008D0D00008F70C0008FDD300089A +:10C0300049D70008AB08000822D7000889D70008B4 +:10C04000310D00081BD700080FD70008710E00083B +:10C05000C9D500083DD800081B0F000856D30008BA +:10C0600002000000780400200000000028230000E7 +:10C0700022D200080200000080050020B004000069 +:10C08000A40600003ED30008020000003C0500208A +:10C0900000000000D00700004AD3000802000000A2 +:10C0A0003E05002000000000D0070000C0D20008BC +:10C0B000020000004005002000000000D007000042 +:10C0C000A7D4000802000000820500200000000044 +:10C0D000D0070000B0D40008020000008405002052 +:10C0E00000000000D0070000EED7000802000000AA +:10C0F0004205002000000000D007000078D40008AE +:10C10000020000004405002000000000D0070000ED +:10C1100028D20008020000004605002000000000B0 +:10C12000D007000018D300080200000048050020D6 +:10C1300000000000D0070000B7D300080200000094 +:10C140004A05002032000000F2010000A8D30008D8 +:10C15000020000004C05002032000000F201000047 +:10C160007FD50008000000008605002000000000C8 +:10C1700001000000D8D30008040000008C05002056 +:10C18000B004000000C20100D4D300080400000085 +:10C190009005002080250000004B000051D20008CF +:10C1A00000000000940500200000000001000000D5 +:10C1B00064D3000800000000880500200000000093 +:10C1C00003000000E8D300080100000089050020FA +:10C1D000FFFFFFFF040000006DD300080000000017 +:10C1E0007E0500200000000002000000C8D4000806 +:10C1F0000000000095050020000000000100000084 +:10C2000006D3000800000000720500200A000000AC +:10C21000C8000000DED20008000000007305002006 +:10C220000A00000032000000CBD20008000000002D +:10C23000740500200A000000320000000BD5000841 +:10C24000000000007505002000000000090000004B +:10C2500030D60008000000004E050020000000005D +:10C260000800000018D20008000000004F05002060 +:10C27000000000000800000028D4000800000000B2 +:10C2800050050020000000000800000052D5000802 +:10C2900003000000520500204CFFFFFF6801000072 +:10C2A00047D4000803000000540500204CFFFFFFA6 +:10C2B00068010000D2D700080300000056050020E6 +:10C2C0004CFFFFFF68010000E1D5000801000000FD +:10C2D00058050020FFFFFFFF010000007BD300088E +:10C2E00000000000590500200000000005000000CB +:10C2F0006DD200080000000064050020000000006E +:10C30000800000001FD40008020000005A05002031 +:10C310000000000000010000C8D600080200000074 +:10C320005C05002064000000E8030000D9D6000886 +:10C33000020000005E05002064000000E803000029 +:10C3400096D6000800000000E8070020000000006A +:10C3500001000000B7D20008000000004E080020D5 +:10C360000000000020000000B4D20008000000001F +:10C370004F0800200000000064000000DDD4000829 +:10C38000000000005008002001000000FA0000003A +:10C39000F1D2000800000000510800200000000059 +:10C3A0000100000005D6000800000000520800202F +:10C3B000000000006400000090D3000800000000AE +:10C3C0000708002000000000FA0000001FD6000847 +:10C3D00000000000080800200000000064000000C9 +:10C3E00065D20008000000000908002000000000DD +:10C3F0006400000027D60008000000000A080020A2 +:10C4000000000000FA00000098D3000800000000BF +:10C410000B0800200000000064000000F5D30008B5 +:10C42000000000000C080020000000006400000074 +:10C430001CD8000800000000940800200000000044 +:10C44000C80000002BD8000800000000950800205C +:10C4500000000000C80000002CD30008020000000B +:10C4600096080020E8030000D00700007DD20008F5 +:10C47000020000009808002064000000D0070000BF +:10C480001DD5000801000000870500200000000005 +:10C4900004000000F7D50008010000009A08002001 +:10C4A000FFFFFFFF010000003BD600080100000075 +:10C4B0009B0800200000000001000000EBD60008EF +:10C4C000000000009C08002000000000FF000000A9 +:10C4D000B9D6000800000000140800200000000089 +:10C4E000FA00000097D200080000000016080020A3 +:10C4F0000000000064000000A6D200080000000058 +:10C50000150800200000000064000000B9D40008F5 +:10C5100000000000240800200000000001000000CE +:10C5200061D400080300000012080020D4FEFFFFC1 +:10C530002C0100006AD5000803000000100800204C +:10C54000D4FEFFFF2C01000002D400080000000010 +:10C5500017080020000000003000000010D4000880 +:10C560000500000018080020000000000100000085 +:10C570002ED50008050000001C0800200000000067 +:10C580000100000031D7000805000000200800204D +:10C590000000000001000000D1D5000803000000E9 +:10C5A0000E080020B0B9FFFF5046000058D6000822 +:10C5B00000000000ED07002000000000C80000009F +:10C5C00093D4000800000000F707002000000000DE +:10C5D000C80000003DD20008000000000108002053 +:10C5E00000000000C80000004DD600080000000058 +:10C5F000EE07002000000000C800000088D40008FA +:10C6000000000000F807002000000000C800000043 +:10C6100032D20008000000000208002000000000E4 +:10C62000C800000062D6000800000000EF070020EC +:10C6300000000000C80000009DD4000800000000B9 +:10C64000F907002000000000C800000047D20008E1 +:10C65000000000000308002000000000C8000000E7 +:10C6600001D70008020000009E0800200000000022 +:10C67000D007000032D4000800000000A20800200B +:10C680000000000001000000BBD50008020000000F +:10C69000A40800200A000000D007000005D8000808 +:10C6A00002000000A60800200A000000D0070000D9 +:10C6B000C6D3000800000000A10800200000000010 +:10C6C0006400000070D4000800000000EA070020A9 +:10C6D00000000000C800000059D40008000000005D +:10C6E000F407002000000000C800000051D400083A +:10C6F00000000000FE07002000000000C80000004D +:10C7000078D5000800000000E907002000000000C4 +:10C71000C800000063D5000800000000F3070020F7 +:10C7200000000000C80000005CD500080000000008 +:10C73000FD07002000000000C8000000E8D7000846 +:10C7400000000000EB07002000000000C80000000F +:10C75000E2D7000800000000F507002000000000FC +:10C76000C8000000DCD7000800000000FF07002020 +:10C7700000000000C800000043D7000800000000CF +:10C78000EC07002000000000C80000003DD70008B2 +:10C7900000000000F607002000000000C8000000B4 +:10C7A0002BD7000800000000000800200000000057 +:10C7B000C80000004AD5000800000000F007002073 +:10C7C00000000000C800000042D500080000000082 +:10C7D000FA07002000000000C80000003AD5000859 +:10C7E000000000000408002000000000C800000055 +:10C7F0004145525431323334000000000000803F84 +:10C8000000000000A8AAAA3F000000000000803F2E +:10C81000000080BFB0AA2ABF000000000000803FD7 +:10C820000000803FB0AA2ABF000000000000803F47 +:10C83000000000000000803F000080BF0000803F3B +:10C84000000080BF000000000000803F0000803F2B +:10C850000000803F000000000000803F0000803F9B +:10C8600000000000000080BF000080BF0000803F8B +:10C87000000080BF0000803F000080BF0000803FBC +:10C88000000080BF000080BF0000803F0000803FAC +:10C890000000803F0000803F0000803F0000803F9C +:10C8A0000000803F000080BF000080BF0000803F8C +:10C8B0000000803F00000000000000000000803FFA +:10C8C000000080BF00000000000000000000803F6A +:10C8D00000000000A8AAAA3F0000803F0000803F9F +:10C8E000000080BFB0AA2ABF000080BF0000803FC8 +:10C8F0000000803FB0AA2ABF000080BF0000803F38 +:10C9000000000000A8AAAA3F000080BF0000803FEE +:10C91000000080BFB0AA2ABF0000803F0000803F17 +:10C920000000803FB0AA2ABF0000803F0000803F87 +:10C93000000080BFD0B35D3F0000803F0000803F1B +:10C94000000080BFD0B35DBF000080BF0000803F0B +:10C950000000803FD0B35D3F0000803F0000803F7B +:10C960000000803FD0B35DBF000080BF0000803F6B +:10C9700000000000D0B35DBF0000803F0000803F9A +:10C9800000000000D0B35D3F000080BF0000803F8A +:10C99000000000000000803F000080BF0000803FDA +:10C9A000000080BF000080BF000000000000803F4A +:10C9B000000000000000803F0000803F0000803F3A +:10C9C0000000803F000080BF000000000000803FAA +:10C9D000D0B35DBF0000803F0000803F0000803F7B +:10C9E000D0B35DBF000080BF0000803F0000803FEB +:10C9F000D0B35D3F0000803F000080BF0000803F5B +:10CA0000D0B35D3F000080BF000080BF0000803FCA +:10CA1000D0B35DBF00000000000080BF0000803F79 +:10CA2000D0B35D3F000000000000803F0000803F69 +:10CA3000000080BF0000803F000080BF0000803FFA +:10CA4000000080BF000080BF0000803F0000803FEA +:10CA50000000803F0000803F0000803F0000803FDA +:10CA60000000803F000080BF000080BF0000803FCA +:10CA7000000080BF0000803F0000803F0000803F3A +:10CA8000000080BF000080BF000080BF0000803F2A +:10CA90000000803F0000803F000080BF0000803F1A +:10CAA0000000803F000080BF0000803F0000803F0A +:10CAB000F704353FF70435BF0000803F0000803F9A +:10CAC000F70435BFF70435BF0000803F0000803F0A +:10CAD000F70435BFF704353F0000803F0000803F7A +:10CAE000F704353FF704353F0000803F0000803FEA +:10CAF00000000000000080BF000080BF0000803FF9 +:10CB0000000080BF00000000000080BF0000803FE8 +:10CB1000000000000000803F000080BF0000803F58 +:10CB20000000803F00000000000080BF0000803F48 +:10CB30000000803F000000BF0000803F0000803FF9 +:10CB4000000000BF000080BF0000803F0000803F69 +:10CB5000000080BF0000003F0000803F0000803FD9 +:10CB60000000003F0000803F0000803F0000803F49 +:10CB70000000003F000080BF000080BF0000803F39 +:10CB8000000080BF000000BF000080BF0000803FA9 +:10CB9000000000BF0000803F000080BF0000803F19 +:10CBA0000000803F0000003F000080BF0000803F89 +:10CBB000000000000000803F0000803F0000803F38 +:10CBC000000080BF000080BF000000000000803F28 +:10CBD000000000000000803F000080BF0000803F98 +:10CBE0000000803F000080BF0000008000000000C7 +:10CBF0000000000003010000FCC700080400000062 +:10CC00002CC80008040000006CC8000802010000E5 +:10CC1000ACC8000800010000000000000600000091 +:10CC2000CCC80008060000002CC900080101000063 +:10CC300000000000040000008CC90008060000008D +:10CC4000CCC90008080000002CCA00080800000039 +:10CC5000ACCA0008080000002CCB0008010100004D +:10CC600000000000000100000000000000010000C2 +:10CC70000000000004000000ACCB00080000000031 +:10CC800000000000524F4C4C3B50495443483B5924 +:10CC900041573B414C543B506F733B506F73523B79 +:10CCA0004E6176523B4C4556454C3B4D41473B56B9 +:10CCB000454C3B0000C2010084D90008A7D90008F8 +:10CCC00000E1000062D900084ED90008009600007B +:10CCD00018D900083AD90008004B0000F6D800081F +:10CCE000E2D80008802500003DD800083DD80008A3 +:10CCF000B56206010300F00500FF19B562060103E5 +:10CD000000F00300FD15B56206010300F00100FB11 +:10CD100011B56206010300F00000FA0FB5620601CA +:10CD20000300F00200FC13B56206010300F00400EA +:10CD3000FE17B562060103000102010E47B5620647 +:10CD40000103000103010F49B5620601030001065A +:10CD500001124FB562060103000112011E67B562A0 +:10CD60000616080003070300510800008A41B56257 +:10CD700006080600C80001000100DE6A1048494AA2 +:10CD80004B4C4D44454647FF20212223242526278E +:10CD900048494A4B4C4DFF1048498A8B8C8D8485FD +:10CDA0008687FF202122232425262748498A8B8C29 +:10CDB0008DFF000088CD00087CCD0008A3CD0008C1 +:10CDC00097CD0008000C014008001002000C014043 +:10CDD0001000100200080140001014027D820008BB +:10CDE000198200084D8200089B81000833820008E8 +:10CDF000000000400008014001000000001C00008D +:10CE0000000000400008014002000000041C000077 +:10CE1000000000400008014004000000081C000061 +:10CE20000000004000080140080000000C1C000049 +:10CE3000000400400008014040000000001D000008 +:10CE4000000400400008014080000000041D0000B4 +:10CE500000040040000C014001000000081D00001B +:10CE600000040040000C0140020000000C1D000006 +:10CE7000002C01400008014000010000001B0100DF +:10CE8000002C014000080140000800000C1B0100BC +:10CE900000080040000C014040000000001E00009F +:10CEA00000080040000C014080000000041E00004B +:10CEB00000080040000C014000010000081E0000B6 +:10CEC00000080040000C0140000200000C1E0000A1 +:10CED0000004080CD39300088B930008AD9300085E +:10CEE000EB9300085F9200080000000000000000C3 +:10CEF0000000B33FB2BE7D3A00002E40DFCF513874 +:10CF000000007E40BF51FABA00E0A44019DAC3BA6B +:10CF100000E0C840C2ED8AB90040EB40CD1F2CBAFA +:10CF2000001006412AFFFABA00C01541DFCFD13701 +:10CF300000D024419A97703A0050334189478E3689 +:10CF400000404141E75B9D3800B04E41C00A98B9AE +:10CF500000A05B41558F943A00306841DA92C0BA24 +:10CF60000040744162B3C63A0000803F00A0853F94 +:10CF700000908B3F00C0913F0030983F00F09E3FF3 +:10CF800000F0A53F0050AD3F0000B53F0000BD3FA1 +:10CF90000060C53F0020CE3F0040D73F00C0E03FCB +:10CFA00000C0EA3F0020F53F000000007D36AC39AC +:10CFB0007D3C3839EBDCF438320A7E39124C2639A4 +:10CFC0009B6AED39A4EE83397F661E39F6398A39BA +:10CFD0002B426539A48211395B991F39C3EECD39D3 +:10CFE000DDE7C637A5A22F390000803FC3AA853FE1 +:10CFF000C2958B3FD3C3913FF037983F32F59E3FA8 +:10D00000D7FEA53F3F58AD3FF304B53FA408BD3F51 +:10D010002A67C53F8C24CE3FFD44D73FDFCCE03F9D +:10D02000C7C0EA3F7D25F53F0040404040404040BA +:10D0300040404141414141404040404040404040EB +:10D04000404040404040404040050202020202028F +:10D0500002020202020202020220202020202020DE +:10D0600020202002020202020202909090909090F2 +:10D0700010101010101010101010101010101010B0 +:10D080001010101002020202020288888888888824 +:10D090000808080808080808080808080808080810 +:10D0A00008080808020202024000000029D0000817 +:10D0B000000000006E83F9A22915444ED15727FCC9 +:10D0C000C0DD34F5999562DB4190433CAB6351FE82 +:10D0D000696E64657820283020746F203229004DF5 +:10D0E00050553630353000424D41323830005654BC +:10D0F00041494C34005934004144584C33343500D4 +:10D1000048455836005936004F43544F583800416F +:10D110004343003344004641494C53414645004196 +:10D120004952504C414E45004D41470048454C49FD +:10D130005F39305F444547004759524F5F534D4F69 +:10D140004F5448494E47004C45445F52494E4700B2 +:10D15000464C59494E475F57494E47004249005493 +:10D1600052490047494D42414C00494E464C4947BF +:10D1700048545F4143435F43414C00534F4654532F +:10D18000455249414C00435553544F4D0048454C7E +:10D19000495F3132305F4343504D0050504D00568F +:10D1A0004152494F004241524F004759524F00519E +:10D1B00055414450004D4F544F525F53544F50000F +:10D1C0004F43544F464C41545000534F4E41520030 +:10D1D000504F5745524D4554455200475053005605 +:10D1E00042415400534552564F5F54494C540048F5 +:10D1F000455836580051554144580053455249410D +:10D200004C5258004F43544F464C415458005445DB +:10D210004C454D4554525900616C69676E5F6163BE +:10D2200063006D69647263006E65757472616C335E +:10D2300064006770735F706F73725F640067707310 +:10D240005F706F735F64006770735F6E61765F64B9 +:10D2500000736F667473657269616C5F696E766581 +:10D2600072746564007468725F6D6964006D6F72DA +:10D270006F6E5F7468726573686F6C640066616975 +:10D280006C736166655F6465746563745F7468720E +:10D290006573686F6C640061636378795F6465616E +:10D2A0006462616E64006163637A5F646561646295 +:10D2B000616E64007961776465616462616E6400C7 +:10D2C0006D696E636F6D6D616E6400766261746D21 +:10D2D000696E63656C6C766F6C746167650076620D +:10D2E00061746D617863656C6C766F6C7461676591 +:10D2F00000616C745F686F6C645F666173745F6318 +:10D3000068616E676500766261747363616C650065 +:10D3100070726F66696C65006465616462616E64F9 +:10D3200033645F7468726F74746C65006661696CF5 +:10D33000736166655F7468726F74746C65006D69A3 +:10D340006E7468726F74746C65006D617874687265 +:10D350006F74746C65006C6F6F7074696D65004EEE +:10D360006F6E65006770735F7479706500736572C6 +:10D3700069616C72785F74797065006163635F687E +:10D3800061726477617265006665617475726500CB +:10D3900072635F7261746500726F6C6C5F70697448 +:10D3A00063685F7261746500736572766F5F707732 +:10D3B0006D5F72617465006D6F746F725F70776D11 +:10D3C0005F72617465006E61765F736C65775F7222 +:10D3D00061746500736F667473657269616C5F6216 +:10D3E00061756472617465006770735F6261756412 +:10D3F000726174650079617772617465007361763A +:10D4000065006261726F5F7461625F73697A650063 +:10D410006261726F5F6E6F6973655F6C70660067E3 +:10D4200079726F5F6C706600616C69676E5F6D61C9 +:10D4300067006E61765F636F6E74726F6C735F68A6 +:10D44000656164696E6700616C69676E5F626F61D8 +:10D4500072645F706974636800695F70697463689F +:10D46000006163635F7472696D5F70697463680003 +:10D47000705F7069746368006465616462616E64A2 +:10D4800033645F68696768006770735F706F737299 +:10D490005F69006770735F706F735F6900677073B7 +:10D4A0005F6E61765F69006D696E636865636B00CE +:10D4B0006D6178636865636B006163635F756E615E +:10D4C000726D656463616C0074656C656D65747222 +:10D4D000795F736F667473657269616C00616C74F7 +:10D4E0005F686F6C645F7468726F74746C655F6E94 +:10D4F00065757472616C006C697374206F72202D95 +:10D5000076616C206F722076616C00706F77657247 +:10D510005F6164635F6368616E6E656C00727373F4 +:10D52000695F6175785F6368616E6E656C006261EA +:10D53000726F5F63665F76656C00645F6C657665CD +:10D540006C00695F6C6576656C00705F6C65766514 +:10D550006C00616C69676E5F626F6172645F726FAD +:10D560006C6C00695F726F6C6C006163635F7472F6 +:10D57000696D5F726F6C6C00705F726F6C6C0072C3 +:10D58000657461726465645F61726D007072696E6A +:10D590007420636F6E666967757261626C65207373 +:10D5A000657474696E677320696E206120706173A1 +:10D5B0007461626C6520666F726D006E61765F7378 +:10D5C000706565645F6D696E0076657273696F6E14 +:10D5D000006D61675F6465636C696E6174696F6E2D +:10D5E000007961775F636F6E74726F6C5F646972EC +:10D5F000656374696F6E007961775F6469726563F2 +:10D6000074696F6E007468726F74746C655F616EBC +:10D61000676C655F636F7272656374696F6E0072C9 +:10D62000635F6578706F007468725F6578706F0013 +:10D63000616C69676E5F6779726F007472695F759C +:10D640006E61726D65645F736572766F006770738B +:10D650005F706F73725F70006770735F706F735F7E +:10D6600070006770735F6E61765F70006D6170004F +:10D6700068656C700064756D70006D617070696EC6 +:10D6800067206F66207263206368616E6E656C2030 +:10D690006F72646572007069645F636F6E74726F3D +:10D6A0006C6C65720064657369676E206375737472 +:10D6B0006F6D206D69786572006163635F6C706681 +:10D6C0005F666163746F72006779726F5F636D701C +:10D6D000665F666163746F72006779726F5F636D16 +:10D6E00070666D5F666163746F720067696D626119 +:10D6F0006C5F666C6167730064656661756C7473FA +:10D70000006770735F77705F72616469757300732F +:10D71000686F772073797374656D207374617475A5 +:10D720007300736574006578697400645F616C747C +:10D73000006261726F5F63665F616C7400695F6154 +:10D740006C7400705F616C74007361766520616E4B +:10D7500064207265626F6F74007265736574207403 +:10D760006F2064656661756C747320616E642072ED +:10D7700065626F6F74006D69786572206E616D65AA +:10D78000206F72206C697374006E616D653D766107 +:10D790006C7565206F7220626C616E6B206F7220F9 +:10D7A0002A20666F72206C697374006665617475F7 +:10D7B00072655F6E616D6520617578666C6167206A +:10D7C0006F7220626C616E6B20666F72206C697381 +:10D7D0007400616C69676E5F626F6172645F79612A +:10D7E0007700695F79617700705F796177006465C0 +:10D7F000616462616E6433645F6C6F77004D4D41AC +:10D8000038343578006E61765F73706565645F6D7E +:10D81000617800636D697800617578006661696C94 +:10D82000736166655F64656C6179006661696C73DC +:10D830006166655F6F66665F64656C617900434130 +:10D840004D535441423B0043414C49423B004750F9 +:10D850005320484F4C443B004845414446524545BF +:10D860003B00414E474C453B0047505320484F4DED +:10D87000453B004D41473B0043414D545249473BD6 +:10D88000004845414441444A3B0041524D3B004819 +:10D890004F52495A4F4E3B00564152494F3B00426E +:10D8A00041524F3B004245455045523B00474F5681 +:10D8B00045524E4F523B004C4C49474854533B0055 +:10D8C00050415353544852553B004C45444C4F57DC +:10D8D0003B004F53442053573B004C45444D415867 +:10D8E0003B0024504D544B3235312C3139323030DD +:10D8F0002A32320D0A0024505542582C34312C3132 +:10D900002C303030332C303030312C313932303013 +:10D910002C302A32330D0A0024505542582C343111 +:10D920002C312C303030332C303030312C333834F3 +:10D9300030302C302A32360D0A0024504D544B32F0 +:10D9400035312C33383430302A32370D0A00245028 +:10D950004D544B3235312C35373630302A32430D69 +:10D960000A0024505542582C34312C312C303030A0 +:10D97000332C303030312C35373630302C302A32A1 +:10D98000440D0A0024505542582C34312C312C308F +:10D990003030332C303030312C3131353230302C86 +:10D9A000302A31450D0A0024504D544B3235312C6C +:10D9B0003131353230302A31460D0A00DCD90008C9 +:10D9C000000000203C0400001EAF0008CCDA000874 +:10D9D0003C0400202C25000040B100080196031EE5 +:10D9E0007A44CBDC0502A102370113DD30025C086A +:10D9F000021A030936B3914B8AD8BC29491A620C22 +:10DA0000290832021A8F0C2908297C1A9F0C290830 +:10DA100032041A980C290832051A730C29083206A8 +:10DA20001A580C290832071A810C290829591A3E5C +:10DA30000C290832091A780C2908320A1A690C29AB +:10DA400008320B1A4E0C2908320C1AC00C29083265 +:10DA50000D1AA50C2908320E1ADA0C2908320F1AF1 +:10DA6000CA0C290832101AB70C290832111A470CAF +:10DA7000290832121AAD0C290832131AD20C2908BF +:10DA8000721402A7FF021001E20452038B803F04CC +:10DA900001165A03494AD931E91D12010A1C0285AF +:10DAA000C208342C01401A408C1A40193A405B14C9 +:10DAB000A24A048B127A33380B02030406070809C2 +:0CDAC0000204063B2910691481000000DC :04000005080000ED02 :00000001FF diff --git a/src/imu.c b/src/imu.c index b70bbd160..d4a738006 100755 --- a/src/imu.c +++ b/src/imu.c @@ -67,12 +67,14 @@ void computeIMU(void) Smoothing[YAW] = (mcfg.gyro_smoothing_factor) & 0xff; } for (axis = 0; axis < 3; axis++) { - gyroData[axis] = (int16_t)(((int32_t)((int32_t)gyroSmooth[axis] * (Smoothing[axis] - 1)) + gyroData[axis] + 1) / Smoothing[axis]); + gyroData[axis] = (int16_t)(((int32_t)((int32_t)gyroSmooth[axis] * (Smoothing[axis] - 1)) + gyroADC[axis] + 1) / Smoothing[axis]); gyroSmooth[axis] = gyroData[axis]; } } else if (mcfg.mixerConfiguration == MULTITYPE_TRI) { - gyroData[YAW] = (gyroYawSmooth * 2 + gyroData[YAW]) / 3; + gyroData[YAW] = (gyroYawSmooth * 2 + gyroADC[YAW]) / 3; gyroYawSmooth = gyroData[YAW]; + gyroData[ROLL] = gyroADC[ROLL]; + gyroData[PITCH] = gyroADC[PITCH]; } else { for (axis = 0; axis < 3; axis++) gyroData[axis] = gyroADC[axis]; From 5107130ac03be99890f7390a695870abb1651a4a Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Fri, 1 Nov 2013 03:02:33 +0000 Subject: [PATCH 26/56] remove stm32_gpio.c from project and fix EXTI-using drivers w/local version of gpioExtiLineConfig. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@465 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- baseflight.uvproj | 15 --------------- src/drv_bmp085.c | 2 +- src/drv_gpio.c | 9 +++++++++ src/drv_gpio.h | 1 + src/drv_hcsr04.c | 2 +- 5 files changed, 12 insertions(+), 17 deletions(-) diff --git a/baseflight.uvproj b/baseflight.uvproj index a6d0cd2ce..67f38c295 100755 --- a/baseflight.uvproj +++ b/baseflight.uvproj @@ -797,11 +797,6 @@ 1 .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_usart.c - - stm32f10x_gpio.c - 1 - .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_gpio.c - stm32f10x_flash.c 1 @@ -1601,11 +1596,6 @@ 1 .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_usart.c - - stm32f10x_gpio.c - 1 - .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_gpio.c - stm32f10x_flash.c 1 @@ -2708,11 +2698,6 @@ 1 .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_usart.c - - stm32f10x_gpio.c - 1 - .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_gpio.c - stm32f10x_flash.c 1 diff --git a/src/drv_bmp085.c b/src/drv_bmp085.c index b2ff7b522..2fd7a45a2 100755 --- a/src/drv_bmp085.c +++ b/src/drv_bmp085.c @@ -115,7 +115,7 @@ bool bmp085Detect(baro_t *baro) #endif // EXTI interrupt for barometer EOC - GPIO_EXTILineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource14); + gpioExtiLineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource14); EXTI_InitStructure.EXTI_Line = EXTI_Line14; EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt; EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising; diff --git a/src/drv_gpio.c b/src/drv_gpio.c index 248c1663d..91021f2d7 100644 --- a/src/drv_gpio.c +++ b/src/drv_gpio.c @@ -31,3 +31,12 @@ void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config) } } } + +void gpioExtiLineConfig(uint8_t portsrc, uint8_t pinsrc) +{ + uint32_t tmp = 0x00; + + tmp = ((uint32_t)0x0F) << (0x04 * (pinsrc & (uint8_t)0x03)); + AFIO->EXTICR[pinsrc >> 0x02] &= ~tmp; + AFIO->EXTICR[pinsrc >> 0x02] |= (((uint32_t)portsrc) << (0x04 * (pinsrc & (uint8_t)0x03))); +} diff --git a/src/drv_gpio.h b/src/drv_gpio.h index ff695ae6a..ec0a9f5a1 100644 --- a/src/drv_gpio.h +++ b/src/drv_gpio.h @@ -53,3 +53,4 @@ typedef struct #define digitalIn(p, i) (p->IDR & i) void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config); +void gpioExtiLineConfig(uint8_t portsrc, uint8_t pinsrc); diff --git a/src/drv_hcsr04.c b/src/drv_hcsr04.c index 515f2cf56..1bc426f52 100644 --- a/src/drv_hcsr04.c +++ b/src/drv_hcsr04.c @@ -90,7 +90,7 @@ void hcsr04_init(sonar_config_t config) gpioInit(GPIOB, &gpio); // setup external interrupt on echo pin - GPIO_EXTILineConfig(GPIO_PortSourceGPIOB, exti_pin_source); + gpioExtiLineConfig(GPIO_PortSourceGPIOB, exti_pin_source); EXTI_ClearITPendingBit(exti_line); From 786d7277050be8b9a5b460d2155d6536f94f03e9 Mon Sep 17 00:00:00 2001 From: Davide Bertola Date: Fri, 1 Nov 2013 11:28:29 +0100 Subject: [PATCH 27/56] Add cli 'motor' command It allows to get and set single motor output value. --- src/cli.c | 43 +++++++++++++++++++++++++++++++++++++++++++ src/mixer.c | 11 +++++++++-- 2 files changed, 52 insertions(+), 2 deletions(-) diff --git a/src/cli.c b/src/cli.c index 002c46018..052b834a4 100644 --- a/src/cli.c +++ b/src/cli.c @@ -12,6 +12,7 @@ static void cliFeature(char *cmdline); static void cliHelp(char *cmdline); static void cliMap(char *cmdline); static void cliMixer(char *cmdline); +static void cliMotor(char *cmdline); static void cliProfile(char *cmdline); static void cliSave(char *cmdline); static void cliSet(char *cmdline); @@ -25,6 +26,9 @@ extern uint8_t accHardware; // from config.c RC Channel mapping extern const char rcChannelLetters[]; +// from mixer.c +extern int16_t motor_disarmed[MAX_MOTORS]; + // buffer static char cliBuffer[48]; static uint32_t bufferIndex = 0; @@ -74,6 +78,7 @@ const clicmd_t cmdTable[] = { { "help", "", cliHelp }, { "map", "mapping of rc channel order", cliMap }, { "mixer", "mixer name or list", cliMixer }, + { "motor", "get/set motor output value", cliMotor }, { "profile", "index (0 to 2)", cliProfile }, { "save", "save and reboot", cliSave }, { "set", "name=value or blank or * for list", cliSet }, @@ -725,6 +730,44 @@ static void cliMixer(char *cmdline) } } +static void cliMotor(char *cmdline) +{ + int motor_index; + int motor_value; + int len; + char *tmp = NULL; + char *sep = " "; + + len = strlen(cmdline); + + tmp = strtok(cmdline, sep); + if (tmp == NULL) { + printf("Usage:\r\n"); + printf("motor [index] shows the output value of one motor\r\n"); + printf("motor [index] [value] sets the output value of one motor\r\n"); + return; + } + motor_index = atoi(tmp); + + if (motor_index < 0 || motor_index >= MAX_MOTORS) { + printf("No such motor, use a number [0, %d]\r\n", MAX_MOTORS); + return; + } + + tmp = strtok(NULL, sep); + if (tmp == NULL) { + tmp = strtok(cmdline, sep); + motor_index = atoi(tmp); + printf("Motor %d is set at %d\r\n", motor_index, + motor_disarmed[motor_index]); + return; + } + motor_value = atoi(tmp); + + printf("Setting motor %d to %d\r\n", motor_index, motor_value); + motor_disarmed[motor_index] = motor_value; +} + static void cliProfile(char *cmdline) { uint8_t len; diff --git a/src/mixer.c b/src/mixer.c index 87d31aa72..a86f108a4 100755 --- a/src/mixer.c +++ b/src/mixer.c @@ -3,6 +3,7 @@ static uint8_t numberMotor = 0; int16_t motor[MAX_MOTORS]; +int16_t motor_disarmed[MAX_MOTORS]; int16_t servo[MAX_SERVOS] = { 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500 }; static motorMixer_t currentMixer[MAX_MOTORS]; @@ -192,6 +193,11 @@ void mixerInit(void) } } } + + // set disarmed motor values + for (i = 0; i < MAX_MOTORS; i++) { + motor_disarmed[i] = feature(FEATURE_3D) ? mcfg.neutral3d : mcfg.mincommand; + } } void mixerLoadMix(int index) @@ -436,7 +442,8 @@ void mixTable(void) motor[i] = mcfg.mincommand; } } - if (!f.ARMED) - motor[i] = feature(FEATURE_3D) ? mcfg.neutral3d : mcfg.mincommand; + if (!f.ARMED) { + motor[i] = motor_disarmed[i]; + } } } From 203e46daa62a680798f7ba6df76300a9c602b11e Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Fri, 1 Nov 2013 22:47:25 +0000 Subject: [PATCH 28/56] Enable automatic reset after (re)flashing, closes issue #19 git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@466 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- Makefile | 2 +- support/stmloader/stmbootloader.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Makefile b/Makefile index 380bff52a..14720dc8b 100644 --- a/Makefile +++ b/Makefile @@ -182,7 +182,7 @@ TARGET_MAP = $(OBJECT_DIR)/baseflight_$(TARGET).map # It would be nice to compute these lists, but that seems to be just beyond make. $(TARGET_HEX): $(TARGET_ELF) - $(OBJCOPY) -O ihex $< $@ + $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@ $(TARGET_ELF): $(TARGET_OBJS) $(CC) -o $@ $^ $(LDFLAGS) diff --git a/support/stmloader/stmbootloader.c b/support/stmloader/stmbootloader.c index d6312cd11..c159c7e9c 100644 --- a/support/stmloader/stmbootloader.c +++ b/support/stmloader/stmbootloader.c @@ -322,7 +322,7 @@ void stmLoader(serialStruct_t *s, FILE *fp, unsigned char overrideParity, unsign printf("Flashing device...\n"); jumpAddress = stmHexLoader(s, fp); if (jumpAddress) { - printf("\nFlash complete, cycle power\n"); + printf("\nFlash complete, executing.\n"); go: // send GO command From 7eec3aec9e24e76c5abe3bc912d6f12fa605e7ce Mon Sep 17 00:00:00 2001 From: dongie Date: Sat, 2 Nov 2013 08:17:31 +0900 Subject: [PATCH 29/56] add untested mixers - HEX6H, dual/single copter, to match mixer IDs with MultiWiiConf --- src/cli.c | 4 +++- src/mixer.c | 45 +++++++++++++++++++++++++++++++++++++++++++++ src/mw.h | 8 ++++++-- 3 files changed, 54 insertions(+), 3 deletions(-) diff --git a/src/cli.c b/src/cli.c index 002c46018..0d38a190d 100644 --- a/src/cli.c +++ b/src/cli.c @@ -37,7 +37,9 @@ static const char * const mixerNames[] = { "TRI", "QUADP", "QUADX", "BI", "GIMBAL", "Y6", "HEX6", "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX", - "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4", "CUSTOM", NULL + "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4", + "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER", + "CUSTOM", NULL }; // sync this with AvailableFeatures enum from board.h diff --git a/src/mixer.c b/src/mixer.c index 87d31aa72..badc81057 100755 --- a/src/mixer.c +++ b/src/mixer.c @@ -106,6 +106,20 @@ static const motorMixer_t mixerVtail4[] = { { 1.0f, 1.0f, -1.0f, -0.0f }, // FRONT_L }; +static const motorMixer_t mixerHex6H[] = { + { 1.0f, -1.0f, 1.0f, -1.0f }, // REAR_R + { 1.0f, -1.0f, -1.0f, 1.0f }, // FRONT_R + { 1.0f, 1.0f, 1.0f, 1.0f }, // REAR_L + { 1.0f, 1.0f, -1.0f, -1.0f }, // FRONT_L + { 1.0f, 0.0f, 0.0f, 0.0f }, // RIGHT + { 1.0f, 0.0f, 0.0f, 0.0f }, // LEFT +}; + +static const motorMixer_t mixerDualcopter[] = { + { 1.0f, 0.0f, 0.0f, -1.0f }, // LEFT + { 1.0f, 0.0f, 0.0f, 1.0f }, // RIGHT +}; + // Keep this synced with MultiType struct in mw.h! const mixer_t mixers[] = { // Mo Se Mixtable @@ -127,6 +141,10 @@ const mixer_t mixers[] = { { 0, 1, NULL }, // * MULTITYPE_HELI_120_CCPM { 0, 1, NULL }, // * MULTITYPE_HELI_90_DEG { 4, 0, mixerVtail4 }, // MULTITYPE_VTAIL4 + { 6, 0, mixerHex6H }, // MULTITYPE_HEX6H + { 0, 1, NULL }, // * MULTITYPE_PPM_TO_SERVO + { 2, 1, mixerDualcopter }, // MULTITYPE_DUALCOPTER + { 1, 1, NULL }, // MULTITYPE_SINGLECOPTER { 0, 0, NULL }, // MULTITYPE_CUSTOM }; @@ -249,6 +267,18 @@ void writeServos(void) pwmWriteServo(1, servo[1]); break; + case MULTITYPE_DUALCOPTER: + pwmWriteServo(0, servo[4]); + pwmWriteServo(1, servo[5]); + break; + + case MULTITYPE_SINGLECOPTER: + pwmWriteServo(0, servo[3]); + pwmWriteServo(1, servo[4]); + pwmWriteServo(2, servo[5]); + pwmWriteServo(3, servo[6]); + break; + default: // Two servos for SERVO_TILT, if enabled if (feature(FEATURE_SERVO_TILT)) { @@ -382,6 +412,21 @@ void mixTable(void) servo[3] += servoMiddle(3); servo[4] += servoMiddle(4); break; + + case MULTITYPE_DUALCOPTER: + for (i = 4; i < 6; i++ ) { + servo[i] = axisPID[5 - i] * servoDirection(i, 1); // mix and setup direction + servo[i] += servoMiddle(i); + } + break; + + case MULTITYPE_SINGLECOPTER: + for (i = 3; i < 7; i++) { + servo[i] = (axisPID[YAW] * servoDirection(i, 2)) + (axisPID[(6 - i) >> 1] * servoDirection(i, 1)); // mix and setup direction + servo[i] += servoMiddle(i); + } + motor[0] = rcCommand[THROTTLE]; + break; } // do camstab diff --git a/src/mw.h b/src/mw.h index 286f2e9e6..414b2e9fc 100755 --- a/src/mw.h +++ b/src/mw.h @@ -40,8 +40,12 @@ typedef enum MultiType MULTITYPE_HELI_120_CCPM = 15, MULTITYPE_HELI_90_DEG = 16, MULTITYPE_VTAIL4 = 17, - MULTITYPE_CUSTOM = 18, // no current GUI displays this - MULTITYPE_LAST = 19 + MULTITYPE_HEX6H = 18, + MULTITYPE_PPM_TO_SERVO = 19, // PPM -> servo relay + MULTITYPE_DUALCOPTER = 20, + MULTITYPE_SINGLECOPTER = 21, + MULTITYPE_CUSTOM = 22, // no current GUI displays this + MULTITYPE_LAST = 23 } MultiType; typedef enum GimbalFlags { From b65c45eb7ccdaea546002ead66d1ea20bcafc6a5 Mon Sep 17 00:00:00 2001 From: dongie Date: Sat, 2 Nov 2013 08:34:30 +0900 Subject: [PATCH 30/56] adding more stuff to ignore --- .gitignore | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.gitignore b/.gitignore index a70237a63..4fdcea4ba 100644 --- a/.gitignore +++ b/.gitignore @@ -1,2 +1,5 @@ *.o *~ +*.uvopt +*.dep +*.bak From 77d455f82b9ee0b2fd338604a67bd0db9792e36f Mon Sep 17 00:00:00 2001 From: dongie Date: Sat, 2 Nov 2013 08:55:27 +0900 Subject: [PATCH 31/56] more shit to ignore --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index 4fdcea4ba..bb41fd5b6 100644 --- a/.gitignore +++ b/.gitignore @@ -3,3 +3,4 @@ *.uvopt *.dep *.bak +*.uvgui.* From 567e7f7cc8eb511ff032f085111fa3ec44cd09e8 Mon Sep 17 00:00:00 2001 From: Kemal Hadimli Date: Thu, 31 Oct 2013 21:08:48 +0200 Subject: [PATCH 32/56] gps: keep state position use it to execute partial initialization code, get rid of delay() calls --- src/gps.c | 49 +++++++++++++++++++++++++++++-------------------- 1 file changed, 29 insertions(+), 20 deletions(-) diff --git a/src/gps.c b/src/gps.c index 51f265e5c..82e382483 100644 --- a/src/gps.c +++ b/src/gps.c @@ -69,7 +69,7 @@ typedef struct gpsData_t { uint32_t lastMessage; // last time valid GPS data was received (millis) uint32_t lastLastMessage; // last-last valid GPS message. Used to calculate delta. - + uint32_t state_position; // incremental variable for loops } gpsData_t; @@ -78,13 +78,18 @@ gpsData_t gpsData; static void gpsNewData(uint16_t c); static bool gpsNewFrameNMEA(char c); static bool gpsNewFrameUBLOX(uint8_t data); +static void gpsSetState(uint8_t state) +{ + gpsData.state = state; + gpsData.state_position = 0; +} void gpsInit(uint8_t baudrate) { portMode_t mode = MODE_RXTX; // init gpsData structure. if we're not actually enabled, don't bother doing anything else - gpsData.state = GPS_UNKNOWN; + gpsSetState(GPS_UNKNOWN); if (!feature(FEATURE_GPS)) return; @@ -98,42 +103,46 @@ void gpsInit(uint8_t baudrate) gpsSetPIDs(); core.gpsport = uartOpen(USART2, gpsNewData, gpsInitData[baudrate].baudrate, mode); // signal GPS "thread" to initialize when it gets to it - gpsData.state = GPS_INITIALIZING; + gpsSetState(GPS_INITIALIZING); } void gpsInitHardware(void) { - int i; - switch (mcfg.gps_type) { case GPS_NMEA: // nothing to do, just set baud rate and try receiving some stuff and see if it parses serialSetBaudRate(core.gpsport, gpsInitData[gpsData.baudrateIndex].baudrate); - gpsData.state = GPS_RECEIVINGDATA; + gpsSetState(GPS_RECEIVINGDATA); return; case GPS_UBLOX: // UBX will run at mcfg.baudrate, it shouldn't be "autodetected". So here we force it to that rate if (gpsData.state == GPS_INITIALIZING) { - for (i = 0; i < GPS_INIT_ENTRIES; i++) { + gpsData.state_position++; + if (gpsData.state_position <= GPS_INIT_ENTRIES) { // try different speed to INIT - serialSetBaudRate(core.gpsport, gpsInitData[i].baudrate); + serialSetBaudRate(core.gpsport, gpsInitData[gpsData.state_position - 1].baudrate); // but print our FIXED init string for the baudrate we want to be at serialPrint(core.gpsport, gpsInitData[mcfg.gps_baudrate].ubx); - delay(200); + } else { + // we're now (hopefully) at the correct rate, next state will switch to it + gpsData.baudrateIndex = mcfg.gps_baudrate; + gpsSetState(GPS_INITDONE); } - // we're now (hopefully) at the correct rate, next state will switch to it - gpsData.baudrateIndex = mcfg.gps_baudrate; - gpsData.state = GPS_INITDONE; } else { // GPS_INITDONE, set our real baud rate and push some ublox config strings - serialSetBaudRate(core.gpsport, gpsInitData[gpsData.baudrateIndex].baudrate); - for (i = 0; i < sizeof(ubloxInit); i++) { - serialWrite(core.gpsport, ubloxInit[i]); // send ubx init binary - delay(4); + + if (gpsData.state_position == 0) + serialSetBaudRate(core.gpsport, gpsInitData[gpsData.baudrateIndex].baudrate); + + gpsData.state_position++; + + if (gpsData.state_position <= sizeof(ubloxInit)) { + serialWrite(core.gpsport, ubloxInit[gpsData.state_position - 1]); // send ubx init binary + } else { + // ublox should be init'd, time to try receiving some junk + gpsSetState(GPS_RECEIVINGDATA); } - // ublox should be init'd, time to try receiving some junk - gpsData.state = GPS_RECEIVINGDATA; } break; case GPS_MTK_NMEA: @@ -166,7 +175,7 @@ void gpsThread(void) // TODO - move some / all of these into gpsData GPS_numSat = 0; f.GPS_FIX = 0; - gpsData.state = GPS_INITIALIZING; + gpsSetState(GPS_INITIALIZING); break; case GPS_RECEIVINGDATA: @@ -174,7 +183,7 @@ void gpsThread(void) if (millis() - gpsData.lastMessage > GPS_TIMEOUT) { // remove GPS from capability sensorsClear(SENSOR_GPS); - gpsData.state = GPS_LOSTCOMMS; + gpsSetState(GPS_LOSTCOMMS); } break; } From 091c77592ae6e30ade74da68a59717101e29b1e1 Mon Sep 17 00:00:00 2001 From: Kemal Hadimli Date: Fri, 1 Nov 2013 23:19:36 +0200 Subject: [PATCH 33/56] gps: wait for gps write buffer to empty before writing more --- src/gps.c | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/gps.c b/src/gps.c index 82e382483..4639385e1 100644 --- a/src/gps.c +++ b/src/gps.c @@ -117,6 +117,11 @@ void gpsInitHardware(void) case GPS_UBLOX: // UBX will run at mcfg.baudrate, it shouldn't be "autodetected". So here we force it to that rate + + // Wait until GPS transmit buffer is empty + if (!isSerialTransmitBufferEmpty(core.gpsport)) + break; + if (gpsData.state == GPS_INITIALIZING) { gpsData.state_position++; if (gpsData.state_position <= GPS_INIT_ENTRIES) { From c4dd556f3d49868ae29680d0b2387deeedc9dae5 Mon Sep 17 00:00:00 2001 From: Kemal Hadimli Date: Tue, 29 Oct 2013 19:35:13 +0200 Subject: [PATCH 34/56] gps passthrough cli command --- src/cli.c | 11 +++++++++++ src/gps.c | 26 ++++++++++++++++++++++++++ src/mw.h | 1 + 3 files changed, 38 insertions(+) diff --git a/src/cli.c b/src/cli.c index 0d38a190d..52ac92803 100644 --- a/src/cli.c +++ b/src/cli.c @@ -9,6 +9,7 @@ static void cliDefaults(char *cmdline); static void cliDump(char *cmdLine); static void cliExit(char *cmdline); static void cliFeature(char *cmdline); +static void cliGpsPassthrough(char *cmdline); static void cliHelp(char *cmdline); static void cliMap(char *cmdline); static void cliMixer(char *cmdline); @@ -73,6 +74,7 @@ const clicmd_t cmdTable[] = { { "dump", "print configurable settings in a pastable form", cliDump }, { "exit", "", cliExit }, { "feature", "list or -val or val", cliFeature }, + { "gpspassthrough", "passthrough gps to serial", cliGpsPassthrough }, { "help", "", cliHelp }, { "map", "mapping of rc channel order", cliMap }, { "mixer", "mixer name or list", cliMixer }, @@ -657,6 +659,15 @@ static void cliFeature(char *cmdline) } } +static void cliGpsPassthrough(char *cmdline) +{ + cliPrint("Enabling GPS passthrough..."); + + if (gpsSetPassthrough() == -1) { + cliPrint("Error: Enable and plug in GPS first\r\n"); + } +} + static void cliHelp(char *cmdline) { uint32_t i = 0; diff --git a/src/gps.c b/src/gps.c index 51f265e5c..9c44be192 100644 --- a/src/gps.c +++ b/src/gps.c @@ -521,6 +521,32 @@ void gpsSetPIDs(void) navPID_PARAM.Imax = POSHOLD_RATE_IMAX * 100; } +int8_t gpsSetPassthrough(void) +{ + if (gpsData.state != GPS_RECEIVINGDATA) + return -1; + +// get rid of callback + core.gpsport->callback = NULL; + + LED0_OFF; + LED1_OFF; + + while(1) { + if (serialTotalBytesWaiting(core.gpsport)) { + LED0_ON; + serialWrite(core.mainport, serialRead(core.gpsport)); + LED0_OFF; + } + if (serialTotalBytesWaiting(core.mainport)) { + LED1_ON; + serialWrite(core.gpsport, serialRead(core.mainport)); + LED1_OFF; + } + } +} + + // OK here is the onboard GPS code //////////////////////////////////////////////////////////////////////////////////// diff --git a/src/mw.h b/src/mw.h index 414b2e9fc..df32c7185 100755 --- a/src/mw.h +++ b/src/mw.h @@ -456,6 +456,7 @@ void cliProcess(void); void gpsInit(uint8_t baudrate); void gpsThread(void); void gpsSetPIDs(void); +int8_t gpsSetPassthrough(void); void GPS_reset_home_position(void); void GPS_reset_nav(void); void GPS_set_next_wp(int32_t* lat, int32_t* lon); From 1990c6a67e6efb358f96e4d06a1cd6ebbf28d5f1 Mon Sep 17 00:00:00 2001 From: dongie Date: Sat, 2 Nov 2013 11:14:25 +0900 Subject: [PATCH 35/56] add new gps type --- src/board.h | 2 ++ src/cli.c | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/src/board.h b/src/board.h index b3604eb40..47bc77d77 100755 --- a/src/board.h +++ b/src/board.h @@ -46,6 +46,7 @@ typedef enum { SENSOR_MAG = 1 << 3, SENSOR_SONAR = 1 << 4, SENSOR_GPS = 1 << 5, + SENSOR_GPSMAG = 1 << 6, } AvailableSensors; // Type of accelerometer used/detected @@ -88,6 +89,7 @@ typedef enum { GPS_UBLOX, GPS_MTK_NMEA, GPS_MTK_BINARY, + GPS_MAG_BINARY, } GPSHardware; typedef enum { diff --git a/src/cli.c b/src/cli.c index 0d38a190d..683bb2a2c 100644 --- a/src/cli.c +++ b/src/cli.c @@ -52,7 +52,7 @@ static const char * const featureNames[] = { // sync this with AvailableSensors enum from board.h static const char * const sensorNames[] = { - "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", NULL + "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL }; static const char * const accNames[] = { From e1087cf921416dc68e8f4669bcbf81614b252271 Mon Sep 17 00:00:00 2001 From: dongie Date: Sat, 2 Nov 2013 12:40:56 +0900 Subject: [PATCH 36/56] fix returned size in MSP_MISC, should correct CRC errors in other GUIs and correctly work with MSP_SET_MISC in MultiWiiConf --- obj/baseflight.hex | 6373 ++++++++++++++++++++++---------------------- src/serial.c | 2 +- 2 files changed, 3200 insertions(+), 3175 deletions(-) diff --git a/obj/baseflight.hex b/obj/baseflight.hex index 953d0d249..c187666dd 100644 --- a/obj/baseflight.hex +++ b/obj/baseflight.hex @@ -1,20 +1,20 @@ :020000040800F2 -:10000000682900208DA40008CDA400086F250008F1 -:10001000D1A40008D3A40008D5A400080000000063 -:10002000000000000000000000000000D7A400084D -:10003000D9A4000800000000DBA40008ED7C000843 -:10004000DFA40008DFA40008DFA40008DFA4000884 -:10005000DFA40008DFA40008DFA400083788000838 -:10006000DFA40008DFA40008DFA40008DFA4000864 -:10007000DFA40008DFA40008AD820008DFA40008A8 -:10008000DFA40008DFA40008DFA40008DFA4000844 -:10009000DFA40008DFA40008DFA4000839880008F6 -:1000A000DFA40008DFA40008DFA400089590000882 -:1000B000999000089F900008A39000085D760008C2 -:1000C0003B740008617600085F760008DFA4000832 -:1000D000DFA40008D98200080D830008DFA400080F -:1000E000796D0008DFA40008DFA40008DFF80CD059 -:1000F0000AF016FE00480047312300086829002056 +:10000000682900203DA500087DA500086F2500088F +:1000100081A5000883A5000885A500080000000050 +:1000200000000000000000000000000087A500089C +:1000300089A50008000000008BA500089D7D000830 +:100040008FA500088FA500088FA500088FA50008C0 +:100050008FA500088FA500088FA50008E788000875 +:100060008FA500088FA500088FA500088FA50008A0 +:100070008FA500088FA500085D8300088FA50008E4 +:100080008FA500088FA500088FA500088FA5000880 +:100090008FA500088FA500088FA50008E988000833 +:1000A0008FA500088FA500088FA500086D91000896 +:1000B00071910008779100087B9100080D77000886 +:1000C000EB740008117700080F7700088FA500086F +:1000D0008FA5000889830008BD8300088FA500084C +:1000E000296E00088FA500088FA50008DFF80CD046 +:1000F0000AF06EFE004800473123000868290020FE :1001000070B51546B0FBF5F40646A84203D3204669 :10011000FFF7F6FF014605FB1460FCA2105C0870B7 :10012000481C70BD70B50C46911E232900D30A22CD @@ -23,61 +23,61 @@ :10015000044600E0641C20782028FBD00928F9D050 :100160004FF07E58C1B247462D2902D02B2801D02E :1001700001E0F04F641C0026DFF8BC930CE000BFE8 -:100180000AF0AAFB0546494630460AF023FB2946F9 -:100190000AF0C8FA0646641C207830380928EFD9DE -:1001A00020782E2815D14D460EE000BF0AF094FBB2 -:1001B00029460AF045FB31460AF0B4FA064649469C -:1001C00028460AF007FB054614F8010F30380928C5 +:100180000AF002FC0546494630460AF07BFB294648 +:100190000AF020FB0646641C207830380928EFD985 +:1001A00020782E2815D14D460EE000BF0AF0ECFB5A +:1001B00029460AF09DFB31460AF00CFB06464946EB +:1001C00028460AF05FFB054614F8010F303809286D :1001D000ECD921784046652901D0452935D114F85C :1001E000011F4FF000082D2902D02B2902D002E078 :1001F0004FF00108641C00256FF02F0206E000BFDD :1002000005EB850302EB4303CD18641C2178A1F1B3 :100210003003092BF4D94FF49A718D4204D90D465D -:10022000C6490AF0D7FA083D082DF9D203E049463D -:100230000AF0D0FA6D1E002DF9D1B8F1000F04D0EC -:10024000014630460AF0FCFA03E0014630460AF067 -:10025000C1FA3946BDE8F0470AF0BCBAF0B587B03C +:10022000C6490AF02FFB083D082DF9D203E04946E4 +:100230000AF028FB6D1E002DF9D1B8F1000F04D093 +:10024000014630460AF054FB03E0014630460AF00E +:1002500019FB3946BDE8F0470AF014BBF0B587B08A :1002600000260D46B74900960196B5A70296B0F54F -:10027000000F02DB0AF056FA01E00AF0A5FAB249D3 -:100280000AF0A8FA0AF036FB041E00DC60420A22DB +:10027000000F02DB0AF0AEFA01E00AF0FDFAB24923 +:100280000AF000FB0AF08EFB041E00DC60420A222A :1002900003A9FFF747FF002C01DB202000E02D2001 -:1002A0008DF8000003A80AF010FA302401280AD0C3 -:1002B00003A80AF00AFA02280CD003A80AF005FAEB +:1002A0008DF8000003A80AF068FA302401280AD06B +:1002B00003A80AF062FA02280CD003A80AF05DFA3B :1002C00003280CD00DE08DF801408DF802408DF828 :1002D000034006E08DF801408DF8024001E08DF802 -:1002E000014003A968460AF0BCF968460AF0EDF936 -:1002F000C01EC4B22246694628460AF0D0F92E55DF -:10030000394628460AF0ADF90DEB040128460AF0FB -:10031000A8F907B02846F0BD70B505460C46086838 -:100320000AF0D3F9024621682868BDE870400AF057 -:10033000D3B970B506460AF0C8F9844D10F0FF0F26 -:100340000FD030460AF0E1F90446142815DA2021CE -:1003500030460AF0B0F90AF0D8F905EB4401C88735 +:1002E000014003A968460AF014FA68460AF045FA84 +:1002F000C01EC4B22246694628460AF028FA2E5586 +:10030000394628460AF005FA0DEB040128460AF0A2 +:1003100000FA07B02846F0BD70B505460C460868DF +:100320000AF02BFA024621682868BDE870400AF0FE +:100330002BBA70B506460AF020FA844D10F0FF0F74 +:100340000FD030460AF039FA0446142815DA202175 +:1003500030460AF008FA0AF030FA05EB4401C88783 :1003600070BD002405EB44002146C28F78A00AF03E -:1003700005FE641C142CF5DB70BDBDE87040142133 -:1003800076A00AF0FBBD2DE9F041002588B00746B4 -:100390002E460AF09AF97B4C10F0FF0FA84652D077 -:1003A000052279A138460AF097F900287ED0042268 -:1003B00077A138460AF090F9002878D038460AF03C -:1003C000A4F9461E0C2E73DA202138460AF073F980 +:100370005DFE641C142CF5DB70BDBDE870401421DB +:1003800076A00AF053BE2DE9F041002588B007465B +:100390002E460AF0F2F97B4C10F0FF0FA84652D01F +:1003A000052279A138460AF0EFF900287ED0042210 +:1003B00077A138460AF0E8F9002878D038460AF0E4 +:1003C000FCF9461E0C2E73DA202138460AF0CBF9D0 :1003D000070007D0781C0746FFF7B8FE04EB0611AC -:1003E00001250861202138460AF065F9070007D089 +:1003E00001250861202138460AF0BDF9070007D031 :1003F000471C3846FFF7AAFE04EB06116D1C486146 -:10040000202138460AF057F9070007D0471C384624 +:10040000202138460AF0AFF9070007D0471C3846CC :10041000FFF79CFE04EB06116D1C88612021384615 -:100420000AF049F930B1401CFFF790FE04EB0611C9 +:100420000AF0A1F930B1401CFFF790FE04EB061171 :100430006D1CC861042D67D057A000BF00F070FF8D :1004400008B0BDE8F08163A000F06AFF5FF000052E :1004500004EB0517386910F0FF4F2BD0761C691C90 -:1004600067A00AF08BFD03A93869FFF7F7FE014684 -:1004700065A00AF083FD03A97869FFF7EFFE014646 -:1004800061A00AF07BFD03A9B869FFF7E7FE01460A -:100490005DA00AF073FD03A9F869FFF7DFFE0146CE -:1004A0005AA00AF06BFD6D1C0C2D02E0C8E0D0E0F4 +:1004600067A00AF0E3FD03A93869FFF7F7FE01462C +:1004700065A00AF0DBFD03A97869FFF7EFFE0146EE +:1004800061A00AF0D3FD03A9B869FFF7E7FE0146B2 +:100490005DA00AF0CBFD03A9F869FFF7DFFE014676 +:1004A0005AA00AF0C3FD6D1C0C2D02E0C8E0D0E09C :1004B000F5E0CDDBCDF80880CDF804800025CDF83F -:1004C000008011E004EB0517009879690AF02AF919 -:1004D0000090B96901980AF025F90190F96902982C -:1004E0000AF020F96D1C0290B542EBDB49A000F048 +:1004C000008011E004EB0517009879690AF082F9C1 +:1004D0000090B96901980AF07DF90190F9690298D4 +:1004E0000AF078F96D1C0290B542EBDB49A000F0F0 :1004F00017FF4C4E00246D4655F8240020F00040B4 :10050000B04202DD48A092E0C4E08FE030313233E7 :100510003435363738394142434445464748494ADD @@ -100,68 +100,68 @@ :100620003A0900000AD7233C4E470900FDA000F01C :1006300077FE641C032CFFF65FAFAFF24000FDE6CF :100640000020414604EB0012401C11610C28F9DB2C -:10065000F6E6202138460AF02EF80028F8D0401C93 -:1006600006460AF032F8F04DC7B2002455F82410BF -:1006700031B13A4630460AF02FF818B1641CF5E75C +:10065000F6E6202138460AF086F80028F8D0401C3B +:1006600006460AF08AF8F04DC7B2002455F8241067 +:1006700031B13A4630460AF087F818B1641CF5E704 :10068000EAA0DBE6204602F015F855F82410EDA0AC -:100690000AF074FCAFF26810FFF775FED0E60C218B -:1006A000EDA00AF06BFCCBE610B5F5A000F038FE2B +:100690000AF0CCFCAFF26810FFF775FED0E60C2133 +:1006A000EDA00AF0C3FCCBE610B5F5A000F038FED3 :1006B000012001F0DAF8F9A000F032FE0A2007F07C -:1006C00043FBBDE81040002007F009BC7CB50446A0 +:1006C0009BFBBDE81040002007F061BC7CB50446F0 :1006D0000D4600790021062814D2DFE800F0030659 :1006E0000A0D111EA06801780CE0A06890F90010B6 :1006F00008E0A068018805E0A068B0F9001001E0FA -:10070000A0680168E9A00AF039FC002D04D0D4E902 -:100710000312E7A00AF032FC7CBDA06869460068BD -:10072000FFF79CFD0146E4A00AF028FC002DF3D061 -:10073000E0680AF0D1F86946FFF790FD0146DFA0B6 -:100740000AF01CFC20690AF0C7F86946FFF786FD2D -:100750000146DAA00AF012FC7CBD2DE9FF47D8A0C3 -:100760000AF00CFCD0A0FFF7E4FDE14DAE4968793A -:1007700001EB800050F8041CDEA00AF0FFFB2869A2 +:10070000A0680168E9A00AF091FC002D04D0D4E9AA +:100710000312E7A00AF08AFC7CBDA0686946006865 +:10072000FFF79CFD0146E4A00AF080FC002DF3D009 +:10073000E0680AF029F96946FFF790FD0146DFA05D +:100740000AF074FC20690AF01FF96946FFF786FD7C +:100750000146DAA00AF06AFC7CBD2DE9FF47D8A06B +:100760000AF064FCD0A0FFF7E4FDE14DAE496879E2 +:1007700001EB800050F8041CDEA00AF057FC286949 :1007800010F0FF4F4CD0DFF878A3002405EB0410E5 :10079000066916F0FF4F3FD0D0E90598C769611C84 -:1007A000D8A00AF0EBFB564502D3D8A00AF0E6FB2E -:1007B00069463046FFF752FD0146BFA00AF0DEFB56 -:1007C0005646B14502D3D1A00AF0D8FB6946484647 -:1007D000FFF744FD0146B8A00AF0D0FBB04502D3B4 -:1007E000CAA00AF0CBFB69464046FFF737FD014639 -:1007F000B1A00AF0C3FBB74202D3C4A00AF0BEFB0B +:1007A000D8A00AF043FC564502D3D8A00AF03EFC7C +:1007B00069463046FFF752FD0146BFA00AF036FCFD +:1007C0005646B14502D3D1A00AF030FC69464846EE +:1007D000FFF744FD0146B8A00AF028FCB04502D35B +:1007E000CAA00AF023FC69464046FFF737FD0146E0 +:1007F000B1A00AF01BFCB74202D3C4A00AF016FC59 :1008000069463846FFF72AFD0146AFF200200AF09C -:10081000B5FB641C0C2CB9DB611CBDA00AF0AEFB5F -:1008200001F054F8804E002407464C3656F8241048 -:1008300021B1BCA00AF0A2FB641CF7E700244FF032 +:100810000DFC641C0C2CB9DB611CBDA00AF006FCAD +:1008200001F054F8804E002407465C3656F8241038 +:1008300021B1BCA00AF0FAFB641CF7E700244FF0DA :10084000010800BF56F8241041B108FA04F03842FC -:1008500002D0B8A00AF092FB641CF3E7B94A00206A +:1008500002D0B8A00AF0EAFB641CF3E7B94A002012 :1008600069462C18135C94F80A41401C08280B5563 -:10087000F7DB00220A54B4A00AF080FBB54D002437 +:10087000F7DB00220A54B4A00AF0D8FBB54D0024DF :1008800004EB840005EB800655F82010B2A00AF0B6 -:1008900075FB00213046FFF719FF6EA000F040FD08 +:10089000CDFB00213046FFF719FF6EA000F040FDB0 :1008A000641C612CECD3BDE8FF8710B5ADA000F04F :1008B00037FD0121002000F022FEADA000F030FD48 -:1008C0000A2007F041FABDE81040002007F007BBFE +:1008C0000A2007F099FABDE81040002007F05FBB4E :1008D00010B50446AAA000F023FDAF480021017026 :1008E000AE480160AE4801702046BDE81040DCE72C -:1008F0002DE9F047064609F0E8FE054600F0E6FF60 -:10090000DFF8248107464FF0010908F14C0855B182 -:100910002A46A4A1304609F0DFFEC8B1307800278E +:1008F0002DE9F047064609F040FF054600F0E6FF07 +:10090000DFF8248107464FF0010908F15C0855B172 +:100910002A46A4A1304609F037FFC8B13078002735 :100920002D2824D026E0A1A000F0FAFC00244D469A :100930004FEA080656F8241041B105FA04F038428F -:1009400002D09FA00AF01AFB641CF3E741A01EE04E +:1009400002D09FA00AF072FB641CF3E741A01EE0F6 :100950009CA000F0E5FC00244FEA080555F824109F -:100960000029F3D096A00AF009FB641CF6E70127E2 +:100960000029F3D096A00AF061FB641CF6E701278A :10097000761C6D1E5FF0000458F8241031B12A4631 -:10098000304609F0A9FE30B1641CF5E793A0BDE83C +:10098000304609F001FF30B1641CF5E793A0BDE8E3 :10099000F04700F0C5BC09FA04F01FB100F091FF68 :1009A00095A002E000F00CFE96A000F0B9FC58F80B -:1009B0002410BDE8F04761A00AF0E0BA70B5002449 +:1009B0002410BDE8F04761A00AF038BB70B50024F0 :1009C00093A000F0ADFC634DB5F1A80504EB440025 -:1009D00005EB80014A6855F8201093A00AF0CEFA82 -:1009E000641C0E2CF2D370BD3EB5054609F06DFEB9 -:1009F000082815D10024285D09F0E6FD2855641C5F -:100A0000082CF8D300244F48295D09F054FE28B182 -:100A10002819295D401C09F04EFE00B108E10BE1E8 -:100A200011E100004F4B0900ECBE0008496E7661F1 +:1009D00005EB80014A6855F8201093A00AF026FB29 +:1009E000641C0E2CF2D370BD3EB5054609F0C5FE61 +:1009F000082815D10024285D09F03EFE2855641C06 +:100A0000082CF8D300244F48295D09F0ACFE28B12A +:100A10002819295D401C09F0A6FE00B108E10BE190 +:100A200011E100004F4B09009CBF0008496E766140 :100A30006C6964206D6978657220747970652E2EFA :100A40002E0D0A004C6F61646564202573206D696A :100A5000782E2E2E0D0A00004D6F746F72206E7569 @@ -179,8 +179,8 @@ :100B1000636D697820256420302030203020300D2E :100B20000A00000066656174757265202D25730DDD :100B30000A000000666561747572652025730D0AF0 -:100B400000000000F0C700086D61702025730D0AD9 -:100B5000000000005CC00008736574202573203D10 +:100B400000000000B4C800086D61702025730D0A14 +:100B50000000000020C10008736574202573203D4B :100B600020000000536176696E672E2E2E00000073 :100B70000D0A5265626F6F74696E672E2E2E00002B :100B80000D0A4C656176696E6720434C49206D6F94 @@ -197,57 +197,57 @@ :100C3000F7A000F075FB3EBD641C082CFFF4E3AE8A :100C4000284600F0A7FBFAA000F06AFBFE4BFF4A23 :100C50000020694615181C5C95F80A51401C0828AC -:100C60004C55F7D300220A54AFF230100AF086F93F -:100C70003EBD2DE9F041804609F027FDF34FF44DCC -:100C8000060011D00246AFF2E401404609F024FD0F +:100C60004C55F7D300220A54AFF230100AF0DEF9E7 +:100C70003EBD2DE9F041804609F07FFDF34FF44D74 +:100C8000060011D00246AFF2E401404609F07CFDB7 :100C900088B1002455F82410F1B13246404609F0DD -:100CA0001BFDF8B1641CF5E7787905EB800050F87E +:100CA00073FDF8B1641CF5E7787905EB800050F826 :100CB000041CE8A01BE0ECA000F032FB5FF0000495 -:100CC00055F8241029B1AFF208100AF057F9641C46 +:100CC00055F8241029B1AFF208100AF0AFF9641CEE :100CD000F6E7AFF2802001E0AFF2B020BDE8F041CE :100CE00000F01EBB601C787155F82410E3A0BDE82D -:100CF000F0410AF043B970B5054609F0E6FCD34C63 -:100D000010F0FF0F0CD0284609F0FFFC02280ED887 +:100CF000F0410AF09BB970B5054609F03EFDD34CB2 +:100D000010F0FF0F0CD0284609F057FD02280ED82E :100D100084F878030021084600F0F1FBC9A0EBE756 -:100D200094F87813BDE87040D9A00AF027B970BDD7 -:100D30002DE9F047814609F0C8FCDB4D060029D0BB +:100D200094F87813BDE87040D9A00AF07FB970BD7F +:100D30002DE9F047814609F020FDDB4D060029D062 :100D4000012E03D199F800002A2823D0D7A14846C4 -:100D500009F093FC00286ED0401C044609F0D5FC35 +:100D500009F0EBFC00286ED0401C044609F02DFD84 :100D600082462046FFF7F2F98046002606EB86070A -:100D700005EB870455F8270009F0A7FC024655F853 -:100D80002710484609F0A8FCF8B1761C612EEDD377 +:100D700005EB870455F8270009F0FFFC024655F8FB +:100D80002710484609F000FDF8B1761C612EEDD31E :100D9000C7A04CE0CEA000F0C3FA002404EB84000E -:100DA00005EB800755F82010AFF250200AF0E6F866 +:100DA00005EB800755F82010AFF250200AF03EF90D :100DB00031463846FFF78AFCAFF2683000F0B0FAEF :100DC000641C612CEAD3BDE8F08706EB860605EBD0 -:100DD0008607F86809F080FD414609F0B9FD25D87D -:100DE000386909F079FD414609F0BCFD1ED8397912 +:100DD0008607F86809F0D8FD414609F011FE25D8CC +:100DE000386909F0D1FD414609F014FE1ED8397961 :100DF000052907D0504606290ED2DFE801F0050587 :100E000008080B0B4046F6E7A168087004E0A168EB :100E1000088001E0A168086055F82610B2A00AF029 -:100E2000ADF82046BDE8F04700214FE4B1A0BDE891 +:100E200005F92046BDE8F04700214FE4B1A0BDE838 :100E3000F04700F075BA002404EB8406494655F8E3 -:100E4000260009F01AFC78B155F8261005EB860744 -:100E5000AFF2F8200AF092F800213846FFF736FC8E -:100E6000AFF210400AF08AF8641C612CE4D3AAE7C0 -:100E70002DE9F04106F059FF4FF47A71B0FBF1F122 -:100E8000A6480378A6480278A6A00AF077F800F0F2 +:100E4000260009F072FC78B155F8261005EB8607EC +:100E5000AFF2F8200AF0EAF800213846FFF736FC36 +:100E6000AFF210400AF0E2F8641C612CE4D3AAE768 +:100E70002DE9F04106F0B1FF4FF47A71B0FBF1F1CA +:100E8000A6480378A6480278A6A00AF0CFF800F09A :100E90000DFD0646B348B4490068B0FBF1F1B3A0BC -:100EA0000AF06CF86A4F00240125903757F8241097 +:100EA0000AF0C4F86A4F00240125A03757F824102F :100EB00051B105FA04F0304203D0AFF2FC200AF041 -:100EC0005DF8641CE4B2F1E7022000F0DDFCA0B1A3 -:100ED000AE4C5F482178AC3050F82110ACA00AF03D -:100EE0004DF82078022808D1AC48007C08B16F2169 -:100EF00000E06E21AAA00AF041F8AFF2A84000F08D -:100F00000FFA06F026FC0246A6484FF45F730188EC -:100F1000BDE8F041A4A00AF031B8B0A000F000BADA +:100EC000B5F8641CE4B2F1E7022000F0DDFCA0B14B +:100ED000AE4C5F482178C03050F82110ACA00AF029 +:100EE000A5F82078022808D1AC48007C08B16F2111 +:100EF00000E06E21AAA00AF099F8AFF2A84000F035 +:100F00000FFA06F07EFC0246A6484FF45F73018894 +:100F1000BDE8F041A4A00AF089B8B0A000F000BA82 :100F20002DE9FF5FDFF8E49299F8000038B901215C :100F300089F80010B6A000F0F3F900F0FDF9DFF831 -:100F400008B3DFF858A25446DAF8000008F0D2FAE5 -:100F500000285AD0206808F0D0FA092807D03F2886 +:100F400008B3DFF858A25446DAF8000008F03EFB78 +:100F500000285AD0206808F03CFB092807D03F2819 :100F600005D0DBF800105C4600294FD076E1002464 :100F70004D4F2546A83FDFF83081DBF800600BE0DD -:100F8000DBF8002022B1B148396809F0A5FB10B99F +:100F8000DBF8002022B1B148396809F0FDFB10B947 :100F900004B93C463D460C374745F1D394B1AB4FBD :100FA0005946226808682B68125C1B5C9A4209D17A :100FB00092B92E2810D220223A54401C0021CBF89E @@ -259,13 +259,13 @@ :101010004D75737420626520616E79206F7264650E :1010200072206F662041455452313233340D0A002C :1010300043757272656E742061737369676E6D6556 -:101040006E743A2000000000F0C700086C04002015 -:10105000ECBE000843757272656E74206D69786528 +:101040006E743A2000000000B4C800086C04002050 +:101050009CBF000843757272656E74206D69786577 :10106000723A2025730D0A00417661696C61626CE9 :1010700065206D69786572733A2000004D69786566 :10108000722073657420746F2025730D0A000000B0 :1010900043757272656E742070726F66696C653A22 -:1010A0002025640D0A0000005CC000083D0000001F +:1010A0002025640D0A00000020C100083D0000005A :1010B0004552523A20556E6B6E6F776E2076617294 :1010C0006961626C65206E616D650D0A000000004B :1010D00043757272656E742073657474696E67739C @@ -286,8 +286,8 @@ :1011C00072733A2025642C20636F6E666967207302 :1011D000697A653A2025640D0A0000004166726F45 :1011E000333220434C492076657273696F6E20322A -:1011F0002E32204E6F762020312032303133202F96 -:101200002030393A30343A3031000000B501002046 +:1011F0002E32204E6F762020322032303133202F95 +:101200002031323A33393A3236000000B50100203D :101210000D0A456E746572696E6720434C49204D16 :101220006F64652C20747970652027657869742750 :1012300020746F2072657475726E2C206F72202777 @@ -298,31 +298,31 @@ :10128000A9B343E004B03048BDE8F05FFFF720BBEE :101290002EA000F045F827E0AFF6480000F040F837 :1012A000294E206800250C2335542B48CDE9000633 -:1012B0000E222A49029501A809F08CF9070007D0EF -:1012C000386809F002FA3044B968401C884702E0E7 -:1012D00023A000F025F830211B4809F0B7F925605C +:1012B0000E222A49029501A809F0E4F9070007D097 +:1012C000386809F05AFA3044B968401C884702E08F +:1012D00023A000F025F830211B4809F00FFA256003 :1012E00099F80000002819D000F026F82BE60BE052 :1012F0000029FBD0144A491E0020CBF8001050549E :1013000020A000F00DF81EE62028EFD00E4A505421 :10131000491CCBF8001000F011F814E6BDE8FF9F5F -:1013200070B50446184D03E0641C286806F0A6FF5B +:1013200070B50446184D03E0641C286806F0FEFF03 :1013300021780029F8D170BD14A0F1E701461248C8 -:10134000006806F09BBF00003C0400201B5B324A93 -:101350001B5B313B3148000019030008B4BF000893 +:10134000006806F0F3BF00003C0400201B5B324A3B +:101350001B5B313B314800001903000878C00008CE :101360004552523A20556E6B6E6F776E20636F6DEB :101370006D616E642C20747279202768656C70270B :101380000000000008200800DC0800200D0A2320CF :10139000000000002DE9F04105460446FD4EFE4FD9 -:1013A00009E0FC4809F087F920B1611B801B384433 +:1013A00009E0FC4809F0DFF920B1611B801B3844DB :1013B00080F80A11641C21780029F2D1BDE8F0817F :1013C000F64800210278372A12D14288B2F55F7FB1 :1013D0000ED10279BE2A0BD190F87923EF2A07D1DA :1013E00000F55F7210F8013B59409042FAD309B101 :1013F00000207047012070472DE9F05FFFF7E0FF04 -:1014000010B90A2006F04AFD4FF45F72E349E24842 -:1014100009F003F9E04C94F87803022802D900207F +:1014000010B90A2006F0A2FD4FF45F72E349E248EA +:1014100009F05BF9E04C94F87803022802D9002027 :1014200084F87803C0B200EB001101EB401004EB2C -:10143000800101F59671C422D94809F0EEF8D84A26 +:10143000800101F59671C422D94809F046F9D84ACD :10144000D84F002092F8201092F81F5040F6C41692 :1014500000FB00F3193B4B4303F6C41343436B43B8 :1014600093FBF6F327F81030401CC0B20628EFD3E8 @@ -334,22 +334,22 @@ :1014C00002F29CFBF2F23A4402FB03F292FBFEF2C0 :1014D00002EB460212B204FB02F292FBFBF2424420 :1014E0002AF8102000F10100C0B20B28D6D399F8D9 -:1014F000000001F08BFFBDE8F05F04F09BBB2DE91D +:1014F000000001F0E3FFBDE8F05F04F0F3BB2DE96D :10150000F047A54D8146372028704FF45F740027BF :101510006C80BE202871EF2085F879033E4685F85F :101520007A7369B195F87803C42200EB001101EBDE -:10153000401005EB800000F59670994909F06DF8B0 +:10153000401005EB800000F59670994909F0C5F858 :101540009548974903E000BF10F8012B57408842A7 -:10155000FAD385F87A73914F4FEA040808F01EFF1A -:10156000342008F089FF384608F046FF04280FD1E0 -:101570000024E019295908F05BFF042805D008F081 -:1015800013FF761C032EE9DB02E0241D4445F0D353 -:1015900008F00AFF032E02D0FFF712FF10B90A204D -:1015A00006F07CFCFFF728FFB9F1000F06D0BDE87C -:1015B000F047012214210F2001F020BBBDE8F08785 +:10155000FAD385F87A73914F4FEA040808F076FFC2 +:10156000342008F0E1FF384608F09EFF04280FD130 +:101570000024E019295908F0B3FF042805D008F029 +:101580006BFF761C032EE9DB02E0241D4445F0D3FB +:1015900008F062FF032E02D0FFF712FF10B90A20F5 +:1015A00006F0D4FCFFF728FFB9F1000F06D0BDE824 +:1015B000F047012214210F2001F078BBBDE8F0872D :1015C00075498A6802438A6070472DE9FC5F77A1FC :1015D000D1E90001CDE900014FF45F716E4809F0D7 -:1015E00035F8C4216E4809F031F86B4B37200025DF +:1015E0008DF8C4216E4809F089F86B4B372000252F :1015F00018700320587102209D60FFF7E1FF83F807 :1016000078534FF41670A3F8F000FA20A3F8F20014 :10161000D0332A20D8835D859D85DD859D74DD745A @@ -376,7 +376,7 @@ :10176000164860631648A063012084F83C0015A069 :10177000FFF710FE84F8665084F8675084F86860BC :10178000012084F8690084F86A5004F8AC8FC823FB -:1017900063701DE0F0C700086C04002000FC010825 +:1017900063701DE0B4C800086C04002000FC010860 :1017A000E8070020A40A0020B00A00201E1E64647E :1017B00064646464031414009A99193F52B87E3F1C :1017C0003333733F4145545231323334000000000B @@ -388,7 +388,7 @@ :1018200006B0C77180F80890A0F80AA08181C6812F :101830000020294D014600BF05EB0012401C11613C :101840000C28F9DB5FF0000404EB041000EB4410FB -:1018500005EB800000F59670C4221E4908F0DDFEFD +:1018500005EB800000F59670C4221E4908F035FFA4 :10186000641C032CF0DBBDE8FC9F10B50446FFF7B9 :10187000A7FD641E204206D1FFF7A7FE0021BDE8A8 :10188000104008463BE610BD14490968014201D0EA @@ -397,112 +397,112 @@ :1018B000704709498968014201D001207047002022 :1018C000704705498A6882438A6070470248806889 :1018D00070470000E80700206C040020040000208E -:1018E00070B5FE4809F040FE0446FD48008808F047 -:1018F000FCFF0546214608F06DFF08F0FBFFF94CA0 -:1019000029462080F84808F09BFFF84908F098FF26 +:1018E00070B5FE4809F098FE0446FD48008809F0EE +:1018F00054F80546214608F0C5FF09F053F8F94CA5 +:1019000029462080F84808F0F3FFF84908F0F0FF76 :10191000E0650820FFF7B8FF002803D0BDE870405D -:1019200002F002BD70BD002801DD024600E0424227 +:1019200002F05ABD70BD002801DD024600E04242CF :101930008A4201DA00207047002802DDA0EB010096 :101940007047FDDA084470472DE9F04F91B0D0E9B7 -:101950000045814686688846086809F005FE0490BF -:10196000D8F800000AF0E6F90590D8F8040009F06C -:10197000FBFD0190D8F804000AF0DCF90746D8F81E -:10198000080009F0F1FD8246D8F808000AF0D2F903 -:1019900083465046049908F01DFF07905046019970 -:1019A00008F018FF80465846049908F013FF069087 -:1019B0005146059808F00EFF08905946059808F022 -:1019C00009FF03900198594680F0004008F002FF9B -:1019D00082463946089808F0FDFE069908F0A2FEF6 -:1019E00010903946039808F0F5FE079908F0EFFECD -:1019F0000E900598019980F0004008F0EBFE0590EC -:101A00003946079808F0E6FE039908F0E0FE0290D8 -:101A10003946069808F0DEFE089908F083FE8346F2 -:101A20000499019808F0D6FE04903046029908F017 -:101A3000D1FE01902846109908F0CCFE0090414656 -:101A4000204608F0C7FE009908F06CFE019908F0E6 -:101A500069FEC9F800005946304608F0BBFE8346CF -:101A600028460E9908F0B6FE80465146204608F0FA -:101A7000B1FE414608F056FE594608F053FEC9F83B -:101A800004003046049908F0A5FE0646284605994C -:101A900008F0A0FE05463946204608F09BFE294680 -:101AA00008F040FE314608F03DFEC9F8080011B0CC +:101950000045814686688846086809F05DFE049067 +:10196000D8F800000AF03EFA0590D8F8040009F013 +:1019700053FE0190D8F804000AF034FA0746D8F86C +:10198000080009F049FE8246D8F808000AF02AFA51 +:1019900083465046049908F075FF07905046019918 +:1019A00008F070FF80465846049908F06BFF0690D7 +:1019B0005146059808F066FF08905946059808F0CA +:1019C00061FF03900198594680F0004008F05AFFEB +:1019D00082463946089808F055FF069908F0FAFE45 +:1019E00010903946039808F04DFF079908F047FF1B +:1019F0000E900598019980F0004008F043FF059093 +:101A00003946079808F03EFF039908F038FF029026 +:101A10003946069808F036FF089908F0DBFE834641 +:101A20000499019808F02EFF04903046029908F0BE +:101A300029FF01902846109908F024FF00904146A4 +:101A4000204608F01FFF009908F0C4FE019908F035 +:101A5000C1FEC9F800005946304608F013FF83461E +:101A600028460E9908F00EFF80465146204608F0A1 +:101A700009FF414608F0AEFE594608F0ABFEC9F832 +:101A800004003046049908F0FDFE064628460599F4 +:101A900008F0F8FE05463946204608F0F3FE2946D0 +:101AA00008F098FE314608F095FEC9F8080011B01C :101AB000BDE8F08F2DE9F04380468A4887B0843036 :101AC000016881F000410391406880F0004004907B -:101AD0008748B0F9000008F0FFFE864908F07AFE5A -:101AE000804C05907834B4F9000008F0F5FE0090C1 -:101AF000B4F9020008F0F0FE0190B4F9040008F017 -:101B0000EBFE029003A96846FFF71EFF7A4D783C72 -:101B100095F83C00012804D07148008808F0E5FEE3 +:101AD0008748B0F9000008F057FF864908F0D2FEA9 +:101AE000804C05907834B4F9000008F04DFF009068 +:101AF000B4F9020008F048FF0190B4F9040008F0BE +:101B000043FF029003A96846FFF71EFF7A4D783C19 +:101B100095F83C00012804D07148008808F03DFF8A :101B200017E0764840780028206B0CD1C11700EBF5 -:101B30009161A0EBA11008F0CFFE029908F0F2FD30 -:101B400008F0D8FE2063C11700EB9160801108F007 -:101B5000C3FE029908F03BFE0290616B894608F0D3 -:101B600033FE0746404608F0C0FE0646644908F0CA -:101B7000D9FD0146304608F063FE394608F02AFEDA -:101B8000494608F0CFFD606309F0AEFD15F82D1F42 -:101B9000FFF7C9FE08F0A0FE0290009809F0A4FD2E -:101BA0006978FFF7C0FE08F097FE0090019809F0F1 -:101BB0009BFD6978FFF7B7FE08F08EFE0190E168A3 +:101B30009161A0EBA11008F027FF029908F04AFE7E +:101B400008F030FF2063C11700EB9160801108F0AE +:101B50001BFF029908F093FE0290616B894608F022 +:101B60008BFE0746404608F018FF0646644908F019 +:101B700031FE0146304608F0BBFE394608F082FED1 +:101B8000494608F027FE606309F006FE15F82D1F90 +:101B9000FFF7C9FE08F0F8FE0290009809F0FCFD7E +:101BA0006978FFF7C0FE08F0EFFE0090019809F099 +:101BB000F3FD6978FFF7B7FE08F0E6FE0190E168F3 :101BC00001EB0800E0602069401C2061009809F0EA -:101BD0008BFD4C4C216808442060019809F084FD7D -:101BE000616808446060029809F07EFDA1680844BD +:101BD000E3FD4C4C216808442060019809F0DCFDCD +:101BE000616808446060029809F0D6FDA168084465 :101BF000A06007B0BDE8F0832DE9F05F394D0446E1 -:101C00008435286809F0B0FC834628680AF092F809 -:101C10008246686809F0A8FC814668680AF08AF87C -:101C20000546D4F808802946404608F0D3FD5946B9 -:101C300008F0D0FD676806465146384608F0CAFDF0 -:101C4000294608F0C7FD05464946206808F0C2FD50 -:101C5000294608F067FD314608F064FD0446514608 -:101C6000404608F0B7FD05465946384608F0B2FD33 -:101C7000294608F0A9FD214609F04CFB224908F04D -:101C8000A9FD224908F0DCFD1649896A08F04AFDE1 -:101C90001F4908F0D5FD09F027FD00B2002802DA3F +:101C00008435286809F008FD834628680AF0EAF858 +:101C10008246686809F000FD814668680AF0E2F8CB +:101C20000546D4F808802946404608F02BFE594660 +:101C300008F028FE676806465146384608F022FE3E +:101C4000294608F01FFE05464946206808F01AFE9E +:101C5000294608F0BFFD314608F0BCFD0446514658 +:101C6000404608F00FFE05465946384608F00AFE81 +:101C7000294608F001FE214609F0A4FB224908F09C +:101C800001FE224908F034FE1649896A08F0A2FDD7 +:101C90001F4908F02DFE09F07FFD00B2002802DA8E :101CA00000F5B47000B2BDE8F09F2DE9F04F8DB0A3 -:101CB000002606F020F8DFF82CB005465C46DBF87D -:101CC0003800281A099008F010FE1249C96808F077 -:101CD00081FD0490A56300241EE00000F366DF3E52 +:101CB000002606F078F8DFF82CB005465C46DBF825 +:101CC0003800281A099008F068FE1249C96808F01F +:101CD000D9FD0490A56300241EE00000F366DF3EFA :101CE00082010020080000200AE81C4100401C4638 :101CF000B001002035FA8EBCE8070020700A0020F1 :101D00003661023CC40800200000E144DB0F49407A :101D1000000020414C0C00200BF1720A0AF106056C :101D20004FF07E58FE4890F82C70FE4830F91400B1 -:101D300008F0D2FD049908F04DFD06A941F82400F1 -:101D400017B3384608F0D1FD0146404608F078FD4B -:101D500081460B903AF9140008F0BEFD494608F0A0 -:101D600039FD814641460B9808F031FDEE4951F8A6 -:101D7000241008F02FFD494608F0D4FCEA4941F848 -:101D8000240008F0B7FD01E03AF8140025F814002B +:101D300008F02AFE049908F0A5FD06A941F8240040 +:101D400017B3384608F029FE0146404608F0D0FD9A +:101D500081460B903AF9140008F016FE494608F047 +:101D600091FD814641460B9808F089FDEE4951F8F6 +:101D7000241008F087FD494608F02CFDEA4941F897 +:101D8000240008F00FFE01E03AF8140025F81400D2 :101D900035F91400641C00FB0066032CC5D3DFF882 :101DA0008CA364204643BAF8000006A9404396FB82 :101DB000F0F4DD481830FFF7C7FD0820FFF764FD99 :101DC00006A910B1D8480C3801E0D6482030FFF7FA :101DD000BBFDA0B24938DFF858933C2827D2002435 -:101DE000B9F8F00008F081FD45464146059008F03D -:101DF00099FC0146284608F023FDCB4E05461836CF -:101E0000C8480C3030F9140008F066FD074656F853 -:101E10002410059808F0DEFC394608F083FC2946BA -:101E200008F0D8FC46F82400641C032CE8D30820F2 +:101DE000B9F8F00008F0D9FD45464146059008F0E5 +:101DF000F1FC0146284608F07BFDCB4E054618361F +:101E0000C8480C3030F9140008F0BEFD074656F8FB +:101E10002410059808F036FD394608F0DBFC294609 +:101E200008F030FD46F82400641C032CE8D3082099 :101E3000FFF72AFD48B34546BB4EDFF8E882002491 -:101E40000C3E08F11208B9F8F20008F04EFD814688 -:101E5000294608F067FC0146284608F0F1FC0546D3 -:101E600038F9140008F038FD0746484656F82410A3 -:101E700008F0B0FC394608F055FC294608F0AAFCE9 +:101E40000C3E08F11208B9F8F20008F0A6FD814630 +:101E5000294608F0BFFC0146284608F049FD054622 +:101E600038F9140008F090FD0746484656F824104B +:101E700008F008FD394608F0ADFC294608F002FDDF :101E800046F82400641C032CEAD35E46BBF900002C -:101E900008F022FDA44C1834A16808F059FD01D2C5 +:101E900008F07AFDA44C1834A16808F0B1FD01D215 :101EA000012100E00021A3484173D4E9010109F0B8 -:101EB00031FA9C4D18352860A068014608F08AFC6C -:101EC00007466068014608F085FC394608F02AFCA0 -:101ED00009F0F6FF0146206880F0004009F01AFA88 -:101EE000DFF8548268604146286808F073FC09F006 -:101EF000FBFBA5F1580741463880686808F06AFC8A -:101F000009F0F2FB78800820FFF7BEFC8B4D10B182 +:101EB00089FA9C4D18352860A068014608F0E2FCBC +:101EC00007466068014608F0DDFC394608F082FCF0 +:101ED0000AF04EF80146206880F0004009F072FADE +:101EE000DFF8548268604146286808F0CBFC09F0AE +:101EF00053FCA5F1580741463880686808F0C2FCD9 +:101F000009F04AFC78800820FFF7BEFC8B4D10B129 :101F100085480C3801E083482030FFF76DFE2880AB :101F20000998FFF7C7FD7E4D95F86A0000281BD081 -:101F3000BAF8000008F0D9FC0146A06808F080FC5F -:101F40007F4908F047FC08F0D5FCC0F1640064222A -:101F5000002104F0A3FB95F86A104843C11700EB79 +:101F3000BAF8000008F031FD0146A06808F0D8FCAE +:101F40007F4908F09FFC08F02DFDC0F16400642279 +:101F5000002104F0FBFB95F86A104843C11700EB21 :101F6000517040F3CF0070800DB0A1E52DE9F04134 -:101F700002F0D1F90220FFF787FC20B102F0CEF881 +:101F700002F029FA0220FFF787FC20B102F026F9CF :101F8000FFF793FE05E067480021801D0180418036 :101F900081804020FFF78DFC624B654CA3F10C0162 :101FA00018B3A1F15A02107830B9D4F8F400040C37 @@ -515,57 +515,57 @@ :1020100000EB4400032490FBF4F088809080188843 :10202000088058884880DEE73F4900200C3108606E :10203000486088603B496C390861C86070472DE989 -:10204000F84F05F058FE374C46F2A8126C3CE16B95 +:10204000F84F05F0B0FE374C46F2A8126C3CE16B3D :10205000A0EB0108904502D20020BDE8F88F394F6F :10206000E0632F4D3888DFF8E090DFF8E0A0DFF87C :10207000E0B04FF07E5640B3206D6269C11700EBAF :102080005171A0EBE10095F82F10491EB2FBF1F160 -:102090000844C117206500EB5170C01008F01CFC0B -:1020A000494608F0CDFB514609F036FB314608F0B1 -:1020B0008EFB594608F08EFB08F01CFCE064002003 +:102090000844C117206500EB5170C01008F074FCB3 +:1020A000494608F025FC514609F08EFB314608F000 +:1020B000E6FB594608F0E6FB08F074FCE0640020FB :1020C000206460643888401E388095F82F0061696C -:1020D000401EB1FBF0F008F008FC494608F0B0FBE8 -:1020E000514609F019FB4FF07E5108F070FB59463C -:1020F00008F070FB09F0F8FAE16C2F6B461A3946CC -:102100004FF07E5008F060FB8146304608F0E4FB5B -:10211000494608F05FFB0646A06908F0DDFB19E0C0 +:1020D000401EB1FBF0F008F060FC494608F008FC37 +:1020E000514609F071FB4FF07E5108F0C8FB59468C +:1020F00008F0C8FB09F050FBE16C2F6B461A39461B +:102100004FF07E5008F0B8FB8146304608F03CFCAA +:10211000494608F0B7FB0646A06908F035FC19E00F :10212000E807002074000020B80800208201002089 :102130006C040020700A00204C3D0F44B0010020C8 :102140000000C842AE01002080E6C547B1DC423E37 -:10215000D048874A394608F03DFB314608F0E2FA9C -:1021600009F0C2FA8346A061E06808F0BEFB0746AA -:10217000654908F02FFB0646206908F0ADFB814653 -:102180006248806808F0A8FBE16D08F023FB39463F -:1021900008F020FB494608F053FB0746206C314607 -:1021A000009008F017FB81464FF0FF31384608F0E9 -:1021B00087FB314608F00EFB494608F0B3FA616C24 -:1021C00008F0B0FAD5F83890824649464FF07E5074 -:1021D00008F0FAFA0646584608F07EFB314608F049 -:1021E000F9FA06464946504608F0F4FA314608F036 -:1021F00099FA606408F07EFB60653946009808F043 -:1022000091FA2064FFF710FFD4E915104FF4967788 -:10221000401AC7F100093A46494604F03FFA0A213C +:10215000D048874A394608F095FB314608F03AFBEB +:1021600009F01AFB8346A061E06808F016FC0746F8 +:10217000654908F087FB0646206908F005FC8146A2 +:102180006248806808F000FCE16D08F07BFB39468E +:1021900008F078FB494608F0ABFB0746206C314657 +:1021A000009008F06FFB81464FF0FF31384608F091 +:1021B000DFFB314608F066FB494608F00BFB616C1B +:1021C00008F008FBD5F83890824649464FF07E501B +:1021D00008F052FB0646584608F0D6FB314608F098 +:1021E00051FB06464946504608F04CFB314608F084 +:1021F000F1FA606408F0D6FB60653946009808F093 +:10220000E9FA2064FFF710FFD4E915104FF4967730 +:10221000401AC7F100093A46494604F097FA0A21E4 :10222000FFF781FB297906467143C81701EB50601F -:10223000C822C011514204F031FAE061A97B4CF28E +:10223000C822C011514204F089FAE061A97B4CF236 :1022400050327143C81701EB9060216A01EBA01076 -:102250005142206204F022FAC117206200EBD150F3 -:10226000E16901EB6020E061404608F03EFB8046FA -:10227000A669A06C301A08F02FFB254908F0AAFACD -:10228000414608F0DDFA08F035FB3A464946A664B7 -:1022900004F004FA0A21FFF746FB6F6B80463946CB -:1022A0004FF07E5008F090FA0646404608F014FBC6 -:1022B000314608F08FFA06463946206C08F08AFA53 -:1022C000314608F02FFA206408F014FB4FF47A72BC -:1022D000514204F0E3F908F0FFFA206409F004FA2F +:102250005142206204F07AFAC117206200EBD1509B +:10226000E16901EB6020E061404608F096FB8046A2 +:10227000A669A06C301A08F087FB254908F002FB1C +:10228000414608F035FB08F08DFB3A464946A66406 +:1022900004F05CFA0A21FFF746FB6F6B8046394673 +:1022A0004FF07E5008F0E8FA0646404608F06CFB16 +:1022B000314608F0E7FA06463946206C08F0E2FAA3 +:1022C000314608F087FA206408F06CFB4FF47A720C +:1022D000514204F03BFA08F057FB206409F05CFA25 :1022E0000521FFF720FB6062297E96224143C81733 -:1022F00001EB107000116FF0950104F0CFF9E16966 +:1022F00001EB107000116FF0950104F027FAE1690D :10230000081AE0610120A8E6BD378635C408002020 -:102310000024744970B5994D0446286807F0F3F815 -:102320000028FAD0E1B2286807F0D4F8204670BD42 -:1023300086B005F029FD0020FFF797FAFFF75CF85B +:102310000024744970B5994D0446286807F05FF9A8 +:102320000028FAD0E1B2286807F040F9204670BDD5 +:1023300086B005F081FD0020FFF797FAFFF75CF803 :102340008F4C002594F8090118B101281ED00928E6 -:102350001CD08DF8105084F8095104A804F0CAFB71 -:1023600004F0A4F90E20FFF797FA00F039F960792C +:102350001CD08DF8105084F8095104A804F022FC18 +:1023600004F0FCF90E20FFF797FA00F039F96079D4 :1023700001260E280DD008280BD08DF8065000BF7E :102380004FF48070FFF795FA50B905E08DF8100012 :10239000E3E78DF80660F3E70820FFF78AFA00B15B @@ -577,37 +577,37 @@ :1023F000E000ADF80A004FF48040FFF75AFA08B148 :10240000B4F8DA00ADF80C00B7F8B000ADF80E0083 :1024100094F80901012823D0092824D08DF8075009 -:10242000684605F063FB5849002040F2DE5200BFC9 +:10242000684605F0BBFB5849002040F2DE5200BF71 :1024300021F81020401CC0B21228F9D35449534847 :102440000827086088F811703846FFF732FAB0B1F3 :1024500094F8120158B1012809D002281CD10AE0D1 :102460008DF80760DCE707208DF80700D8E74848BB -:1024700003F008FE10E0464804F0D3FA0CE094F8AC +:1024700003F060FE10E0464804F02BFB0CE094F8FB :102480001C0128B194F91D01002801DA84F81D51BE -:1024900094F81D0103F017FC0120FFF70AFA30B190 -:1024A0004FF48060FFF705FA08B101F0C1FF394928 +:1024900094F81D0103F06FFC0120FFF70AFA30B138 +:1024A0004FF48060FFF705FA08B102F019F83949D6 :1024B0004FF0100AC1F800A0A1F10409B846C9F80C :1024C00000700025A9F10407386880F0100038601A -:1024D000386880F008003860192005F035FC0120CC -:1024E00005F03DFC192005F02FFC002005F037FC1D +:1024D000386880F008003860192005F08DFC012074 +:1024E00005F095FC192005F087FC002005F08FFC15 :1024F0006D1CEDB20A2DE7D3C9F80080C9F800A021 -:1025000001F04EFCFFF7ECF90220FFF7D2F908B119 -:1025100001F012FDD4F8200102F0BBF85846FFF795 -:10252000C8F928B194F82811D4F8240106F0F0FE77 -:102530004FF40060FFF7BDF908B103F051FF05F05B -:10254000DAFB154908606079052803D113494FF477 +:1025000001F0A6FCFFF7ECF90220FFF7D2F908B1C1 +:1025100001F06AFDD4F8200102F013F95846FFF7E4 +:10252000C8F928B194F82811D4F8240106F05CFF0A +:102530004FF40060FFF7BDF908B103F0A9FF05F003 +:1025400032FC154908606079052803D113494FF41E :10255000C870088012494FF47A7008801149C82069 -:102560000880114880F80D6000F058FFFCE704482F -:10257000B0F9D40000F015F9FEE70000DC080020F7 -:102580006C040020E8070020800A0020CF2F0008FC +:102560000880114880F80D6000F0B0FFFCE70448D7 +:10257000B0F9D40000F029F9FEE70000DC080020E3 +:102580006C040020E8070020800A00207F3000084B :1025900004010020140C0140000100207E010020F5 -:1025A00080010020AE010020700A00200146FE4894 +:1025A00080010020AE010020700A00200146F6489C :1025B00000EBC100B0F97000122804DA082902DA31 -:1025C000FA4931F910007047F74A02EBC00090F960 +:1025C000F24931F910007047EF4A02EBC00090F970 :1025D0007200084202D04FF0FF3070470120704770 -:1025E0002DE9F041F24EF34F707907EBC0004078CF -:1025F00000B10120F04CA0742020FFF75AF908B177 -:102600000120A0747079ED4CED4D122808D017F818 +:1025E0002DE9F041EA4EEB4F707907EBC0004078DF +:1025F00000B10120E84CA0742020FFF75AF908B17F +:102600000120A0747079E54CE54D162808D017F824 :10261000301007EBC0002170426842B3002024E074 :102620005FF0000006EB00110A6912F0FF4F1ED0A8 :10263000D1E9057C05EB0013C969401CC3E902C15F @@ -616,2889 +616,2914 @@ :10266000C6E90283C6E9007C401C8842F0DB4FF4D7 :102670008040FFF71EF900281AD02778012F17D9BC :10268000002613E005EB06144FF0FF384146A06822 -:1026900008F016F9A0604146606808F011F9606022 -:1026A0004146E06808F00CF9761CE060BE42E9DBC8 -:1026B000BDE8F081F0B5401C0021BD4A0B4600BFCB -:1026C00002EB0114491C23610C29F9DBB94B03EB24 +:1026900008F06EF9A0604146606808F069F9606072 +:1026A0004146E06808F064F9761CE060BE42E9DB70 +:1026B000BDE8F081F0B5401C0021B54A0B4600BFD3 +:1026C00002EB0114491C23610C29F9DBB14B03EB2C :1026D000C0014C68002C11D0002113F830000BE031 :1026E00004EB011302EB011593E8C010DB68491CF1 -:1026F000C5E906C3C5E904678842F1DCF0BDAE4810 -:1027000010B5807C002839D0A948AC4C4079A41C75 -:1027100005280ED004DC01281BD0042804D112E0C7 -:10272000082825D00E2829D02020FFF7C2F800283D -:1027300024D02188002005F069FA61880120BDE8D5 -:10274000104005F063BA2189002005F05FFA618925 -:10275000F4E79A499448891C90F8B300498908B174 -:102760000020ECE7974840780028F9D10021F7E7EE -:10277000E188002005F04AFA2189DFE710BD70B535 -:102780008F4E0024183E8D4D07E000BF36F8141020 -:10279000204605F030FA641CE4B228788442F5D370 -:1027A00070BD864A864B00211278183B04E000BFBA -:1027B00023F81100491CC9B29142F9D3DFE72DE992 -:1027C000FC5F7E4C804EDFF804922078032814D9F9 -:1027D000B9F904004142002801DD024600E00A4642 -:1027E00002F1640200DC08466FF06301A1EB000116 -:1027F000B6F9040003F052FFB0807048DFF8C0A1C2 -:10280000DFF8A4810778AAF1180A012F38D900242B -:1028100034E000BF98F9B200B6F9041040424843D2 -:1028200008F05AF8664901EB0415E96807F0D2FF91 -:102830000190B6F9000008F04FF8696807F0CAFF88 -:102840000090B6F9020008F047F8A96807F0C2FF47 -:102850008346B9F9060008F03FF8296807F0BAFF87 -:10286000594607F05FFF009907F05CFF019907F0F8 -:1028700059FF08F03FF82AF81400641CBC42C9D381 -:102880004B4D4E4CDFF848B16879A41C052842D066 -:1028900004DC012831D004283CD102E00828FBD117 -:1028A00056E00420FFF782FE034602210420FFF7D2 -:1028B0008BFEB6F9041000FB01F701210420FFF79D -:1028C00083FEB6F9021000FB017018442081052038 -:1028D000FFF76CFE034602210520FFF775FEB6F9EF -:1028E000041000FB01F701210520FFF76DFEB6F98A -:1028F000021000FB017018440BE00520FFF756FEA4 -:10290000034601210520FFF75FFEB6F9041000FB26 -:102910000130608199E098F97200BBF9021032260B -:10292000484390FBF6F708F172025B460020FFF780 -:102930003DFE3844208092F90800B3F90010484366 -:1029400090FBF6F20120FFF731FE104460807CE03E -:102950001C4F7878F0B3B5F8D220B5F8D010B9F99B -:10296000060003F09BFEE081AAF80000B87A4FF061 -:10297000010100284FF003003BD0FFF725FEB9F915 -:1029800002104B4600FB01F602210320FFF71CFE5C -:10299000B3F9001000FB0160E08001210420FFF783 -:1029A00013FEB3F9021016E0E8070020800A0020A9 -:1029B0006C040020ECCB0008DC080020B4000020F0 -:1029C00008090020700A0020360100204401002080 -:1029D000340000200AE000FB01F602210420FFF78A -:1029E000F3FDB3F9001000FB016021E0B5F8D4005D -:1029F000B9E7FFF7E9FDB6F9021000FB01F3022188 -:102A00000320FFF7E1FDB6F9001000FB0130E08084 -:102A100001210420FFF7D8FDB6F9021000FB01F3F5 -:102A200002210420FFF7D0FDB6F9001000FB0130B1 -:102A300020810320FFF7BAFDE1880844E0800420EC -:102A4000FFF7B4FD2189084420812020FEF731FFE3 -:102A5000C0B30020FFF7AAFD20800120FFF7A6FDEC -:102A600062496080097A69B398F8B42041469207B8 -:102A700015D591F97220BBF9023056425E433223DC -:102A800098F97A10BBF9002096FBF3F6514391FBBD -:102A9000F3F1721A238831449A1A228010E098F9CF -:102AA0007230BBF90210278803FB01F6322196FB36 -:102AB000F1F63E442680BBF90020534393FBF1F12D -:102AC000084460800026474607EBC6006C30B0F92A -:102AD0000220B0F9001034F9160003F0DFFD24F8ED -:102AE0001600761C082EEFD397F8B400DFF800919B -:102AF000400711D500262020FEF7DBFE00B102269C -:102B000000244F4607EB44000189A019C0B205F02C -:102B10007DF8641C042CF5D336495646BAF900708A -:102B200001200B7806E000BF36F91020BA4200DD24 -:102B30001746401C9842F7D300244FF4804A884639 -:102B40004DE000BFB5F8D200B84205DA36F81410EF -:102B5000381A081A26F814005046FEF7AAFE98B153 -:102B6000B9F9060040F2DC51884204DDB5F8D22004 -:102B7000B5F8D81003E0B5F8D620B5F8D41036F97A -:102B8000140003F08BFD15E0B5F8D220B5F8D01095 -:102B900036F9140003F082FD26F81400B9F9060096 -:102BA000B5F81611884207DA1020FEF782FE38B118 -:102BB000B5F8D40026F814000F48407818B10DE09D -:102BC000B5F8D000F6E75046FEF773FE10B1B5F841 -:102BD000DA0001E0B5F8D40026F81400641C98F877 -:102BE00000008442AED3BDE8FC9F0000C60A00206E -:102BF000800A0020B4000020700A00202DE9F04770 -:102C00001746894606460025DFF83C841AE0002472 -:102C100011E000BFD8F8001081F00801C8F80010DA -:102C2000012005F09CF8484605F08EF8002005F0DC -:102C300096F8641CE4B2B442ECD33C2005F084F86E -:102C40006D1CEDB2BD42E2D3BDE8F0872DE9FC5F1B -:102C5000FE4C002540F2DC51B4F90600FC4E4FF466 -:102C6000FA73884201DA64210CE0F949B0F5FA6F91 -:102C700091F8251004DAA0F2DC52514391FBF3F1F4 -:102C8000C1F164018946F34996F866E096F867B0A9 -:102C9000B1F814410022B246EC49EE4B40F2E63C5A -:102CA00031F91260311B01F2F317674503D800298F -:102CB00003DCA11B01E04FF4FA71022A34D0BEF10B -:102CC000000F05D08E4502DAA1EB0E0100E00021D5 -:102CD000642391FBF3F3DD4F6FF01808243707EB03 -:102CE000430C37F91370BCF902C003FB08F3ACEBDB -:102CF000070C01EB83030CFB03FC64239CFBF3F345 -:102D00003B44D54F27F812309AF823304B434FF409 -:102D1000FA7193FBF1F1C1F1640189B201FB09F190 -:102D2000642391FBF3F11CE0BBF1000F05D08B4550 -:102D300002DAA1EB0B0100E0002193F9EC30DFF89F -:102D400018C35B424B43ACF804309AF82430002996 -:102D500000DC49424B434FF4FA7193FBF1F1C1F1AE -:102D600064010AEB0207642397F801C0DFF8E882E8 -:102D70000CFB01FC9CFBF3FCA8F1540808F802C012 -:102D800097F80BC008F103080CFB01FC9CFBF3FC5B -:102D900008F802C07F7D4F4397FBF3F108F103036E -:102DA000A642995405DAAC4931F812305B4221F859 -:102DB0001230521C032AFFF66FAFDFF898A24FF4CF -:102DC000FA625446BAF8161103F068FCB4F816110A -:102DD0004FF47A72401A5043C1F5FA61B0FBF1F139 -:102DE000642291FBF2F0994B6FF01806303303EB3D -:102DF000400433F910307043B4F9024001EB800015 -:102E0000E41A444394FBF2F0DFF84C828F4E1844EE -:102E1000103EA8F80600707AA8F17C04E8B38F4849 -:102E2000B4F91E10B0F90000401A07F055FD8C49A6 -:102E300007F0D0FC8B4907F003FD074608F094FB30 -:102E40000190384608F076FF00904746B8F9000038 -:102E500007F042FD8346009907F0BCFC8046B7F9B5 -:102E6000020007F039FD8146019907F0B3FC4146A5 -:102E700007F058FC07F03EFD80464846009907F0F1 -:102E8000A9FC81465846019907F0A4FC494607F081 -:102E90009BFC07F02FFD388000E001E0A7F80280DE -:102EA0000220FEF706FD002750B3E078401CC0B2B8 -:102EB0000621B0FBF1F2E07001FB1200B8B900206E -:102EC00003F08AFE2179614A01F00703AC3A491CFC -:102ED00022F813002171002032F81010401C294400 -:102EE0008DB20828F8DBE80801F00EF8A072A07A8D -:102EF000E18C884203D89AF80811814201D9A77061 -:102F000001E00420A070A07803F05FF956484E4D10 -:102F1000008818B10220FEF7B7FC10B953480088AA -:102F200020B1286880F00800286011E0B1780820FE -:102F300011B14549091D0860717811B14249083144 -:102F400008604FF40060FEF7B4FC08B103F05DFACE -:102F50008020FEF7AEFC48B1E16C606B411A05D4ED -:102F60004CF250310844E06405F010FAA16C606B3B -:102F7000411A03D4717BF9B10120B07002F011F84D -:102F80002020FEF781FC68B1216D606B411A09D4E5 -:102F9000E17A052906D3364908442065286880F07F -:102FA000100028603348816800290ED002B02A48FA -:102FB000BDE8F05F5C380847B770296881F0080108 -:102FC00029602D490844A064D8E7BDE8FC9F10B5EE -:102FD000204C204490F80A0104F022FEA0F2EE21D9 -:102FE00040F2DD52914201D3B4F8140110BD2DE935 -:102FF000F047194EDFF854807C3EA8F19C087079A8 -:10300000124F401C00247071A14608F14005F16B7D -:1030100020468847727908EBC40102F0030221F8C8 -:10302000120025F81490002035F8143031F81020E3 -:10303000401C1A44C0B225F814200428F4D335F9F2 -:103040001400801CC11719E00C0C0140800A0020FC -:10305000E80700206C04002044010020B00100209B -:10306000DB0F4940000034437E0100208001002036 -:10307000F04902004C0C002020A1070000EB9170E9 -:10308000801025F8140037F91410C91E884202DA9E -:10309000811C27F8141037F91410C91C884202DD6E -:1030A000801E27F81400641CE4B2082CAFD3CBE5D3 -:1030B000FE480288FE48417852B9827842B1002920 -:1030C00005D101214170FB48FB490088C883704746 -:1030D0000029FCD10122FF2102208FE52DE9FC5FB0 -:1030E0000020F54982467C31054607460190B1F93A -:1030F00002004342002801DD044600E01C468B46E6 -:10310000B1F900104A42002901DD0E4600E01646E2 -:10311000B44203DD002806DC184604E0002901DD86 -:10312000084600E01046DFF8949300240090E04E3B -:10313000F07808B93079E8B3022C3FDADE484FF472 -:10314000FA72443030F914103BF9140001EB4000DE -:10315000514203F0A3FADA49DFF868A331F91410F9 -:10316000411A0AEB4400B0F9280001EB00089AF874 -:103170000810642001FB08F191FBF0F09AF81C1094 -:1031800001EB8102494201EB810103F087FA0190D2 -:10319000C94842F21072743050F8241001EB080054 -:1031A000514203F07BFAC449743141F824009AF883 -:1031B000121000E008E048434FEA203AF07818B1D6 -:1031C000307908B9022C48D13BF91450B84F05EBBF -:1031D00085000101BB48A83F00EB04084FF47A5278 -:1031E00098F8010091FBF0F039F91410401A57F8E3 -:1031F00024100844514203F051FA47F8240039F9E9 -:10320000140000F52070B0F5A06F02D857F8240024 -:1032100002E0002047F824007D2190FBF1F098F8AF -:103220000B10484387113079A8B1022C13DA0098AB -:10323000009AC0F5FA710198009B484305FB020013 -:103240004FF4FA7201FB0AF107FB031190FBF2F055 -:1032500091FBF2F608E0F07820B1022C02DA564633 -:10326000019801E028463E46934A39F91410283265 -:103270005023125DDFF838824A4392FBF3F28E4B03 -:10328000821A6833A8F13C0833F9140023F81410AB -:10329000081A08F10C0158F8243051F824C041F8FC -:1032A00024309C44844448F8240083482E30005D38 -:1032B00000FB0CF0C11700EBD1609119A1EB60107D -:1032C0007D496E3121F81400641C032CFFF62FAFEA -:1032D0007BE62DE9F05F764E4FF0000BDFF8E4A1BE -:1032E000DFF8D4915C46A83E714DE87808B928799A -:1032F000D0B1022C18DA70484FF4FA72443030F929 -:103300001410383030F9140001EB4000514203F042 -:10331000C5F96B4931F91410411A0AEB4400B0F9B0 -:10332000280001EB000B01E0022C52D0E878E0B35A -:103330009AF8080000FB0BF0001160490AEB040743 -:1033400031F91410FA7A451A787856F8241068433F -:103350004FEAE018B9F80C006843C01200FB0210F5 -:103360004FF4001246F82400514203F097F946F852 -:10337000240043134E480C3850F8241040F82450D1 -:10338000B9F80C00691A02094FF6FF70B0FBF2F0B1 -:10339000484347498011243901F10C0251F824C0F7 -:1033A00052F824506544054400E01CE042F824C073 -:1033B00041F82400787D6843011208EB03000844BB -:1033C0003D496E3121F81400641C032C8CDBBDE8F0 -:1033D000F09F9AF8240038491B307C31B1F9041071 -:1033E00048434011A9E7344A9AF823007C321B3045 -:1033F00032F9142050432A790011002A9DD09AF8FE -:10340000121001FB0BF100EB212096E72A4901285D -:1034100001D02D4800E02D48086470472DE9F84F91 -:103420000027B946B8460820FEF743FADFF8A0B0F7 -:1034300068B19BF8120120B1012802D0022806D100 -:1034400002E002F042FE01E003F00AFB8046DFF8F2 -:1034500068A0174C4FF00005DAF83410DAF8540081 -:103460004FF00106081A02D5B8F1000F7DD044F6DE -:1034700020621144CAF85410FFF7B9FD4FF48040A0 -:10348000FEF717FA28B10A485630007808B900F05C -:103490007DFC9BF81B0168B305494FF47A7210312B -:1034A00001EB40000021B0F9060013E0800100208C -:1034B000700A0020B0010020C80000206800002031 -:1034C00034000020E8070020DD300008D332000877 -:1034D0006C040020A0F57A7003F0E0F807F0FCF926 -:1034E000FE4907F0ADF9FE4907F074F907F01BFA41 -:1034F000AAF822004FF40070FEF7DBF9B0B3DFF852 -:10350000E483BAF90E2098F8ACC00CEB8C01914220 -:103510001DDA6078D8B1BBF91431F349002000BF3F -:1035200021F81030401C0328FADBB8F8AE30CB800D -:1035300098F8AD00604400EB8000904202DA00F0A1 -:1035400025FC2570BAF81010491CAAF8101098F83C -:10355000AC0000EB8001BAF90E00814204DA607819 -:1035600010B900F013FC257001E068E204E0BAF83D -:103570000E10491CAAF80E10BBF816C1BBF8182192 -:10358000DFF864830020BF0838F91030634501DD9F -:1035900047F08007934201DA47F04007401C0428B7 -:1035A000F1DB9AF8071050468F4205D18179FA294C -:1035B00003D2491C817100E085718AF807704FF4CD -:1035C00080473846FEF775F958B1BBF81411BBF8BF -:1035D000DC00B8F906200B1A934202DA0844904244 -:1035E00009DC3846FEF765F9E8B9B8F90610BBF80A -:1035F0001601814217DABC48B8380560456085601D -:10360000BA4805604560B748C08F60B1B6484630DB -:10361000007820B1207810B1FFF74AFD03E0607810 -:1036200008B100F0B3FB9AF80600142817D16078AF -:10363000B0B1AC4FF88F28B99AF807005F2801D1D4 -:1036400000F0A4FB9BF81A01002808D0F88F00288E -:1036500005D19AF807007D2801D100F097FB8FE093 -:103660009AF80700572809D00420FEF722F9E8B19C -:103670009AF8071050465A2921D017E09C494FF478 -:103680007A7008804FF48070FEF713F908B101F0EA -:1036900068FF0420FEF7F8F810B196490A20088068 -:1036A0000820FEF7F1F808B9934805809AF807005A -:1036B0005D2817D05B2817D05E2817D023E0818AB9 -:1036C00019B18582AAF816601DE0818C21B1002114 -:1036D000818419B1022102E00121F9E703218AF86E -:1036E000001010E0012702E0022700E00327781E07 -:1036F0008BF8780300210846FDF701FF3A462821A0 -:103700000220FFF77BFA774FF88F18B99AF8071065 -:103710006F290ED09BF81A1121B118B99AF8070039 -:103720007E2806D09AF80700972805D0A72808D049 -:1037300008E0FFF7BDFC05E070494FF4C870088051 -:1037400000E0A6739AF80700BB2806D0B72807D078 -:10375000BE2809D0BD280AD012E0788D801C01E077 -:10376000788D801E788505E0388D801C01E0388DCD -:10377000801E388501210846FDF7C1FE8AF80650F3 -:103780000420FEF796F820B3BAF8242050463221E0 -:103790006AB162785AB1B8F90630BBF81621934283 -:1037A00005DD514A463212780AB9418285844E4A73 -:1037B0004632527C32B1028B838A1A4309D1AAF86D -:1037C000121006E0818A21B1617811B98582AAF8C8 -:1037D00016600020C64640F2A46700BF0EEB400111 -:1037E000B1F9082040F214518A4201DA012300E0C5 -:1037F000002300EB40018B40A2F2155CBCF5C77FB3 -:1038000002D84FF0010C01E04FF0000C01F101086B -:103810000CFA08FC43EA0C03BA4201DD012200E085 -:103820000022891C8A40134343EA0903401C1FFA03 -:1038300083F90428D2DB2C4F00204637294901EBBD -:103840004001C98F11EA090100D001213954401CFF -:103850001428F3DB787840B9224890F8AC0000EBEC -:103860008001BAF90E0081420ADA0220FEF70CF854 -:1038700030B1E07828B91D4805604560E67000E089 -:10388000E570B87838B1E570207928B91748056037 -:103890004560267100E025713878B84600B9267079 -:1038A000E178102009B9217909B1154901E01449DD -:1038B000091F08600420FDF7E7FF70B198F80300C6 -:1038C000474650B3A07938BB0E48A67101680E4830 -:1038D000016006480830C18818E02BE000007A44F7 -:1038E00000C07F44E8070020800A00203C0100203F -:1038F00080010020AE010020B00100207E010020E8 -:10390000140C01405C00002060000020FF48AAF871 -:103910001A100560FE48056000E0A5714FF40050E4 -:10392000FDF7C7FF30B1387918B1E07B10B9E67305 -:1039300000E0E5730220FDF7A7FF18B90820FDF7A6 -:10394000A3FFD0B198F80510404639B1617931B97B -:10395000F04966710A88F0490A8000E06571817952 -:1039600019B1617A11B9667200E0657298F80700C2 -:1039700018B1E8480188AAF81E102020FDF784FF3E -:10398000F0B3E07AE8B39AF80B005746052844D321 -:1039900098F80A1059B1E07990BBE671DF492572B9 -:1039A0003D72081F02F09BFA0220787039E0E57141 -:1039B00098F80B0030B3D94A143AB2F90000002845 -:1039C00000DC4042D649B1F8C01088421DDAB2F995 -:1039D0000200002800DC4042884216DA207A78B9DA -:1039E000CE4826720C383D7200F1100102680A6060 -:1039F000406841F8040FC948001D02F070FA02E067 -:103A00000FE00AE001E07E700BE02572387A40B9E1 -:103A10008AF8086002F038FA03E0E57125728AF846 -:103A2000015098F80C0008B1A67200E0A5729BF84E -:103A30000500082801D00E2843D1657241E0DAF86C -:103A40005C005746042801DD401FF865052838D280 -:103A5000DFE800F0030B151F2A000820FE65FDF7C4 -:103A600013FF10B100F06DFC58BBF86D401CF865F9 -:103A70000420FDF709FF10B100F073FB08BBF86DDF -:103A8000401CF8650420FDF7FFFE10B1FEF7D7FAE1 -:103A9000B8B9F86D401CF8654FF48070FDF709FF68 -:103AA00010B102F0C0F90CE0F86D401CF865102070 -:103AB000FDF7EAFE08B100F0C6FC4FF40050FDF738 -:103AC000F8FE04F018F9CAF83400BBF80C20574689 -:103AD00012B1BB6DC31A71D41044D946B865FEF754 -:103AE00045FAFFF7B3F804F006F97863398F411A05 -:103AF000B981B8630820FDF7C7FE48B38749143978 -:103B0000B1F9042002F145008A2822D8607900B377 -:103B10008048038880480088181A00B210F1B40F5A -:103B200002DC00F5B47000B2B42802DBA0F5B4707A -:103B300000B299F9EC305B42434318B2637B3BB16E -:103B4000774B5B7A43431E2093FBF0F0101A88807A -:103B500003E070480188704801800420FDF794FE5E -:103B600058B3A07948B36E4991F8690038B36B48EF -:103B7000B7F91A201438B0F90630A3EB020CBCF1E7 -:103B8000000F01DCA2EB030C91F868108C4509DDF5 -:103B9000DFF878C19342CCF800507E7200DD4942D4 -:103BA000194409E0797A21B15E490B685E490B60DE -:103BB0007D72574909881144C1803AE0E4E0FFE78B -:103BC000DFF85881B7F91A00A8F11408B8F90630DF -:103BD0001A1A002A01DD134600E0C31A91F8681092 -:103BE0008B420FDDB98B4FF4FA6C114409B291FB93 -:103BF000FCF34D4A0CFB131115681D441560B98385 -:103C00007E7207E0797A29B146490A6846490A6016 -:103C1000BD837D723E490988084400B2A8F80600B9 -:103C2000B9F8D010B9F8D220963102F037FDA8F8D3 -:103C300006003B4D95F86A0050B1E07808B920794C -:103C400030B13648394A1438C18812881144C180CD -:103C50002020FDF719FEE8B3E07908B9207AC8B34F -:103C6000207BB8B32B4CB4F9000006F035FE304E83 -:103C7000314606F0AFFD08F05DF80090B4F90000A1 -:103C800006F02AFE314606F0A5FD07F06DFC234C38 -:103C9000064695F8B900303CDFF898A0A4F11C085E -:103CA00010B3A146B4F90200241DB4F90210401A61 -:103CB00001F008FA15F8B92F514202F0EFFC6188C3 -:103CC00008446080B9F90000B4F90010401A01F00E -:103CD000F9F900E04EE02A78514202F0DFFC218839 -:103CE000084400B2208001E0B4F9000006F0F4FDC1 -:103CF0008346009906F06EFD0546B4F9020006F011 -:103D0000EBFD8146314606F065FD15E028000020F8 -:103D100024000020B0010020B20100205801002042 -:103D2000E80700205C000020600000200A0000205E -:103D300035FA8E3C00002041294606F045FD5546E7 -:103D4000514606F07DFD06F0D5FDA8F8000044467A -:103D50005846314606F03EFD06464846009906F0B4 -:103D600039FD314606F0DEFC294606F069FD06F015 -:103D7000C1FD6080386C8047FEF721FDFEF7BFFC77 -:103D8000BDE8F84FFEF7FBBCBDE8F88F034841786B -:103D9000002901D00021417070470000700A002006 -:103DA0002DE9F843FE4CFF4BFF490026B4F8EE2006 -:103DB0009846A1F1100004F0EAFB08B101260EE0DC -:103DC000B4F8EE10F84804F0F1FD40B9B4F8EE1084 -:103DD000F54803F082FD10B9032004F05FF8F34DBD -:103DE0005FF0000794F8ED0006283CD2DFE800F011 -:103DF0000707192833030220FDF753FD33E08DF840 -:103E000000704FF44870E849ADF802001039684678 -:103E100002F085FF08B10120287094F8ED00012818 -:103E200021D06EB1E049B4F8EE204346A1F1100074 -:103E300004F0ADFB0220287094F8ED0002281DD09C -:103E4000D948103804F0ACFC28B10320287094F84D -:103E5000ED00032812D0D448103805F01AFB10B139 -:103E6000042028700AE0287840B994F8ED0010B1D9 -:103E700084F8ED70B6E70220FDF713FDCA48103054 -:103E800004F097FE38B9C848103002F0EFFF10B9BF -:103E90000420FDF706FD0220FDF7F6FC28B1C2491B -:103EA00094F8E300103909688847BF4914F8E20F15 -:103EB00009688847A07803F0F3F810B90820FDF7E7 -:103EC000F0FCBB486421B0F9262092FBF1F001FB25 -:103ED000102406B20820FDF7D7FCB64D90B120465D -:103EE00006F0FAFCB44906F075FC0446304606F0CC -:103EF000F3FC214606F016FCB04906F06BFC286086 -:103F0000BDE8F8832F60FBE770B50546A44890F83C -:103F1000060106F0EAFC0446284606F0E6FCA8493D -:103F200006F058FCA74906F08BFC214606F052FC2F -:103F300006F0F9FC80B270BD70B500252C4600205B -:103F400002F04AFE05440A2003F0FEFE641C202C09 -:103F5000F5D3C5F34F10FFF7D7FF914A022192F82E -:103F6000073100BF03FB01F4844202D8491C062933 -:103F7000F8D39548017092F80801484393490880A6 -:103F800070BD2DE9F05FDFF82492914E884FB9F8AB -:103F90000220834C0025C2B38E4900204FF4C8781C -:103FA000424501D141F8205051F8203036F910C077 -:103FB000634441F8203026F8105004EB4003401CC5 -:103FC000A3F8FA500328EBDB012A19D10868C8309E -:103FD00090FBF8F024F8FA0F4868C83090FBF8F02E -:103FE00060808868C83090FBF8F1B9F80600081ABC -:103FF000A0803D850121FA3C7D850846FDF77FFACA -:10400000B9F80210491EA9F802100420FDF751FC6E -:10401000002874D0704BDFF894816E491A8808F13B -:1040200020080C31A8F1180A322A05D0F2B300207A -:104030009B46322A14D015E034F8FA0FA8F8000095 -:104040006088A8F80200A088A8F80400B7F828C083 -:10405000AAF800C0B7F82AC0FA3CAAF802C0E6E7FE -:1040600041F8205051F8203036F910C0634441F82F -:10407000203026F8105004EB4003401CA3F8FA50FF -:104080000328D6DB012A1AD15448554B058001205C -:104090001880544B02201870B8F8000024F8FA0F6A -:1040A000B8F802006080B8F8040000E00AE0A080E0 -:1040B000BAF800303B85BAF80200FA3C7885521E07 -:1040C000ABF8002048480288012A18D105800A6808 -:1040D000322092FBF0F224F8FA2F4A6892FBF0F2B9 -:1040E0006280896891FBF0F1B9F80600081AA08097 -:1040F0003D850121FA3C7D850846FDF700FA3088B0 -:1041000034F8FA1F401A308070886188401A708035 -:10411000B088A188401AB080BDE8F09F224810B551 -:10412000103841682A488847BDE8104029E730B573 -:104130001E4C1F4AE06892F82F200146401C824224 -:1041400000D10020294A1368224A183242F821304F -:10415000274952F820200D682B449A1A0A60E06023 -:1041600030BD70B52348114C00682169411A01D552 -:10417000002070BD20610C4D6069103578B1286950 -:1041800080476868804728882169084420616A69F7 -:1041900019491648904700206061022070BD2DE04B -:1041A0006C040020EC0800204C0C00207C01002056 -:1041B000E8070020300000208988883C000020416A -:1041C0003333534000F07F4568010020EE000020AB -:1041D0007A0000201C0B0020DA000020E000002004 -:1041E000DC000020C8000020DE000020A00000202D -:1041F0001C000020FC000020A4000020A8688047CC -:10420000E8688047FFF793FF0120606168882169B3 -:1042100008442061012070BD2DE9F05FA24DA888FF -:1042200000286AD0DFF884820024A3464FF47A790C -:10423000A8F10C06A888484507D104EB840208EBD6 -:10424000820146F824B0C1F810B0994F56F82410F6 -:1042500037F91400014446F8241006F03DFB0146EE -:1042600004EB840208EB8200824600F0EFF827F8A6 -:1042700014B0904F27F814B0A888012837D1DAF885 -:104280001000012808DD401E06F026FB0146DAF882 -:104290000C0006F0D5FA00E0002007F011FE82467F -:1042A000854890F8F800A8B106F01FFB514606F0CB -:1042B0004FFB0FD27D49A5F80490C8F810B0C1F8A3 -:1042C00024B0C1F838B0C6F808B0C6F804B0C6F8D3 -:1042D00000B00CE056F82400012200F5FA7090FBC3 -:1042E000F9F027F814000F210A20FEF787FC641C60 -:1042F000032C9FDBA888401EA8806D496D4A0020D2 -:1043000031F8103032F810401B1B21F81030401CDF -:104310000328F5DB00E7654810B54C304168644878 -:104320008847BDE8104077E710B564481024046062 -:1043300002F005FF6148001F04605B4901204870DE -:1043400010BD2DE9F0415E48574C0068A169411A43 -:1043500002D50020BDE8F0815A490844A0615A48BE -:1043600002F0B5FEDFF864C14F4B00269CF80E004A -:104370005549514A26339D1D88B1A069E06100204E -:1043800002EB4007A7F8006131F8107023F81070B5 -:1043900025F81070401C0328F2D38CF80E6060786A -:1043A00070B10888B2F80071C01B08804888B2F864 -:1043B0000271C01B48808888B2F80471C01B8880D5 -:1043C000E06998B3A769381A414FB84218D23B4800 -:1043D0000838026882F008020260002031F91020DB -:1043E00033F91040A24201DA23F8102035F91040C9 -:1043F000A24201DD25F81020401C0328EED315E071 -:104400000020E66133F9101035F91040214402EB29 -:10441000400401EBD17141F34F01401CA4F800119D -:104420000328EFD301210846FDF769F8012091E741 -:1044300010B5012004F001FA1020FDF72DFA2549EE -:104440000020086010BD234804F04BBA2DE9F0416C -:10445000044600690E46401C206101281FD006F06A -:104460003BFA256880462946304606F0ADF90746F6 -:10447000414606F0E5F9294606F054F90546606024 -:104480002946304606F0A0F90146384606F0A2F962 -:10449000A16806F047F92560E060A0605AE7666011 -:1044A00000202660F9E700007C010020000C0020BD -:1044B00074000020A80000206C040020140C0140AF -:1044C000FC000020A086010086000020700A002069 -:1044D00080C3C901B000002070B5FB4CFB4EC1B2D7 -:1044E0000546A170306804F0F5FFE079A1784840F6 -:1044F000E071C5F30721A170306804F0EBFFE079AB -:10450000A1784840E071C5F30741A170306804F01C -:10451000E1FFE079A1784840E071290EA170306890 -:1045200004F0D8FFE079A1784840E07170BD70B523 -:10453000E54CE64EC1B20546E170306804F0CAFFB2 -:10454000E079E1784840E071C5F30721E170306817 -:1045500004F0C0FFE079E1784840E07170BD10B52B -:104560000446DA482146006804F0B4FFD648C17911 -:104570006140C17110BDD44AD548117A405C491CD4 -:104580001172704700B5FFF7F6FF0346FFF7F3FF20 -:1045900003EB002080B200BD10B5FFF7F3FF044627 -:1045A000FFF7F0FF04EB004010BD70B504460D4668 -:1045B0002420FFF7D4FF4D20FFF7D1FF0CB12120BD -:1045C00000E03E20FFF7CBFFBF4C0020E071284603 -:1045D000FFF7C5FF607ABDE87040C0E701460020E4 -:1045E000E3E701460120E0E7B748C079B7E770B5D7 -:1045F00004460D460846FFF7F1FF03E014F8010BEF -:10460000FFF7ADFF2800A5F10105EDB2F6D170BDB1 -:1046100010B5044603E000BFFFF7A1FF641C20783B -:104620000028F9D110BD2DE9F05FDFF89CB2DFF86A -:10463000989201274FF0000A0BF10C0B00251AE0AD -:10464000A3481438405D00EB40010BEB8108D8F81B -:10465000040006F03AF806460FB1B2440AE000241E -:1046600006E000BFD8F80400005DFFF778FF641C87 -:10467000B442F7DB6D1C99F800008542E0DB002FA7 -:1046800005D00AF0FF00FFF7A9FF0027D6E7BDE835 -:10469000F09F70B50246032300218E4803F0D4FC3E -:1046A0008A49FF2208608A481421143805F0C7FFA0 -:1046B000874D0020143D012428700220FDF7E4F806 -:1046C00020B1012068700220A87003240420FDF7A7 -:1046D000DBF850B103202855641C4FF40050FDF75F -:1046E000E8F810B104202855641C0220FDF7CCF82E -:1046F00018B90820FDF7C8F840B105202855641CFA -:1047000006202855641C07202855641C2020FDF72E -:10471000D0F810B108202855641C4FF48070FDF7C4 -:10472000C8F828B10A202855641C0B202855641CA1 -:1047300069484079082801D00E2802D10C2028555C -:10474000641C0D202855641C0420FDF7B2F810B13C -:1047500011202855641C132028555B48641C0470E4 -:1047600070BD2DE9F05F584EDFF864B14FF00008DE -:10477000717A594D594C5A4FC1464FF0010AABF16D -:10478000140B782978D011DC3046A1F1640100784F -:1047900014293BD2DFE801F0FCFBFAF9F8F7F6F553 -:1047A000F4F3F2F1F0EFEEEDECEBEAE94C48CF294F -:1047B000407871D014DCCA295FD008DCA0296CD005 -:1047C000A4296BD0C82927D0C9291FD138E0CB290B -:1047D00065D0CC2971D0CD2970D0CE2916D17BE3FC -:1047E000D4296CD00ADCD0296AD04FF00008D12936 -:1047F00067D0D22966D0D32908D1DFE0EF2918D0BD -:10480000F02960D0FA2979D0FE2978D00020FFF76E -:10481000E8FEBDE8F05FE7E60024324DFFF7B2FEA8 -:1048200025F81400641C082CF8D30020FFF7D6FEEE -:10483000EFE7FFF7A7FE6085FFF7A4FE2085F4E70A -:10484000FFF799FEF872FFF796FE27490870FFF709 -:10485000A3FE264C2060FFF79FFE6060FFF792FEEC -:1048600023490880FFF78EFE2249088022480178FC -:1048700041F002010170D8E761E10023FFF77BFE00 -:10488000E5186870FFF777FEE872FFF774FE5B1CAF -:1048900068750A2BF2D3C8E749E04BE35CE30025D7 -:1048A0005F4606E0FFF76EFE795D6D1C04EB41018B -:1048B000C88730788542F5D3B7E721E005E358E1B2 -:1048C000FDE2C9E26BE02BE3B4010020DC0800202C -:1048D000880C0020003801406C040020E80700200C -:1048E000700A0020800A0020D30000204C01002024 -:1048F000760100207801002064010020F1E2F2E25C -:10490000FFF739FE04F81F0FFFF735FE6070FFF761 -:1049100032FE2071FFF72FFE6071FFF72CFEA071B1 -:10492000FFF729FEA070FFF726FEE0707DE7FFF796 -:1049300029FEFFF727FEE93525F8190CFFF72CFEB5 -:10494000FFF720FEA4F8AE00FFF71CFEFFF724FEE1 -:10495000FFF718FE00EB80004000E084FFF70BFE3D -:104960006877FFF708FEE87713E0D2E150E2B3E1A1 -:10497000CCE10CE2DAE1B6E19CE183E174E16AE1C9 -:1049800051E13EE120E111E10BE1D5E0A1E028E0B9 -:1049900018E0FFF7F0FDA877FFF7EDFD45E70028E9 -:1049A0008AD1FFF7E8FD85F87803022801D985F858 -:1049B000788300210020FCF7A2FD36E7FFF7E2FD37 -:1049C000F94987E20720FFF709FEE620FFF7C7FD58 -:1049D0006879FFF7C4FD0020FFF7C1FD4FF00040EC -:1049E000B7E20B20FFF7FAFDF048008800B2FFF7AE -:1049F0009EFD02F0AEFE00B2FFF799FD0220FCF72B -:104A000043FF04460420FCF73FFF44EA400408202B -:104A1000FCF73AFF44EA80042020FCF735FF44EA23 -:104A2000C0041020FCF730FF44EA0010FFF77FFDC0 -:104A3000F9783A79490041EA8201BA79002041EADD -:104A4000C2017A79367841EA42117A7AD44641EA4B -:104A50008211D74AD37941EAC311137A41EA03217B -:104A6000537A41EA4321FB7941EA83213B7A41EAC7 -:104A7000C321BB7A41EA0331537B41EA4331937B43 -:104A800041EA8331137C41EA0341137941EA03117E -:104A9000537C41EA4341937CD27C41EA834141EA21 -:104AA000C24479785F460C43002208E0BB5C0CFAF4 -:104AB00003F3234202D00CFA02F10843521CB24223 -:104AC000F4D3FFF709FD95F8780300BFFFF747FD22 -:104AD0009FE61220FFF782FDB648B74D4FF0000465 -:104AE0000088B0F5806F0BD935F91400C11700EBC1 -:104AF0005170C010FFF71BFD641C032CF4D306E0BB -:104B000035F91400FFF713FD641C032CF8D3AB4DEB -:104B1000002400BF35F91400FFF709FD641C032CC5 -:104B2000F8D3A74D002400BF35F91400FFF7FFFCB0 -:104B3000641C032CF8D36CE61021A24833E0382023 -:104B4000FFF74CFD5FF0000504EBC50636F96C0F6E -:104B5000FFF7EDFCB6F90200FFF7E9FCB6F9040037 -:104B6000FFF7E5FCB079FFF7FAFC6D1C082DEBD3DD -:104B70004FE60020FFF732FD5FF00005FFF702FD72 -:104B800004EBC50626F86C0FFFF7FCFC7080FFF7FE -:104B9000F9FCB080FFF7EFFC6D1CB071082DEDD370 -:104BA00037E610218848FFF722FD32E61020FFF794 -:104BB00015FD864D002400BF35F91400FFF7B7FC42 -:104BC000641C082CF8D324E61020FFF707FDF87AC0 -:104BD000FFF7C5FC7E480078FFF7C1FC7D4C2068DC -:104BE000FFF77AFC6068FFF777FC7B48008800B22B -:104BF000FFF79DFC7948008800B2FFF798FC7848E1 -:104C00003DE00520FFF7EAFC7648008800B2FFF798 -:104C10008EFC7548B0F90000FFF789FC73480078F6 -:104C200000F0010052E70820FFF7D8FC704D002487 -:104C300035F91400FFF77BFC641C022CF8D36D4897 -:104C4000B0F90000FFF773FC6B48B0F9000000BF3B -:104C5000FFF76DFCDDE50620FFF7C0FC6748006844 -:104C6000FFF73AFC66480AE00520FFF7B7FC654805 -:104C70000078FFF774FC0020FFF759FC62480088B9 -:104C800000B2E5E70720FFF7A9FC14F81F0FFFF7B4 -:104C900066FC6078FFF763FC2079FFF760FC6079C1 -:104CA000FFF75DFCA079FFF75AFCA078FFF757FCEF -:104CB000E0780BE71E20FFF791FC0025661970785D -:104CC000FFF74DFCF07AFFF74AFC707DFFF747FCD9 -:104CD0006D1C0A2DF2D39CE52F20FFF77FFC4B487B -:104CE000FFF796FC95E54006000EFFF777FC0025E0 -:104CF0005F4607E0785D04EB4000B0F93E00FFF747 -:104D000016FC6D1C30788542F4D382E5FFF78BFCEE -:104D10007FE5FFF763FC00245D4603E0285DFFF7B5 -:104D20001EFC641C30788442F8D372E53220FFF711 -:104D300055FC0020FFF7FBFB35F9D00FFFF7F7FB21 -:104D4000B5F90200FFF7F3FBB5F90400FFF7EFFB3D -:104D5000B4F9AE00FFF7EBFB0020FFF7E8FB002003 -:104D6000FFF7BAFBB4F926000A2190FBF1F000B27C -:104D7000FFF7DDFB95F83600FFF7F1FB95F83800FB -:104D8000FFF7EDFB95F83700FFF7E9FB62E008203D -:104D9000FFF724FC0024601CC0B2FFF7E0FB641C9A -:104DA000082CF8D335E50000B2010020D400002023 -:104DB000C60A002082010020800000206800002038 -:104DC00086000020B6000020F0080020800A0020A5 -:104DD000D30000204C010020760100207801002043 -:104DE000660100207201002074010020640100208F -:104DF00034000020B0010020E60000205C0000200C -:104E00002C000020D2000020EA00002084CC000802 -:104E1000FFF7B1FB04461220FFF7E0FB14B1102CA2 -:104E200002D004E0954800E09548D0E9008920468A -:104E3000FFF795FB4046FFF74FFB4846FFF74CFB5B -:104E400090480068FFF748FB0020FFF770FB002048 -:104E5000FFF76DFB002039E6FFF78DFB8446FFF777 -:104E60009BFB0546FFF798FB0646FFF795FB0446BC -:104E7000FFF788FBFFF786FBFFF77DFBBCF1000F18 -:104E800011D0BCF1100F7FF4DAAC7D49C1E90056B6 -:104E90000CB17C4804607C4A0220091D10707848DF -:104EA00001F01DF8C1E47548002CC0E9005687F8F0 -:104EB000078087F80CA0F5D072480460B5E400289C -:104EC000F0D10120FCF7D1FCAFE40028EAD16F4912 -:104ED0004FF4C8700880A8E40028E3D187F80EA03A -:104EE000A3E4012166E50820FFF778FB68486A4AD9 -:104EF0006A4D016867481268B1FBF0F1B2FBF0F04F -:104F000000EB4002C2EBC01001EBC000E8800024BF -:104F100035F91400FFF70BFB641C042CF8D378E47C -:104F20000420FFF75BFBB4F92A00FFF700FBB4F99C -:104F300028008DE60C20FFF751FB59480068FFF769 -:104F4000CBFA5748001D0068FFF7C6FA54480830EE -:104F50000068FFF7C1FA5CE4524D29780AEB810042 -:104F6000C0B2FFF73BFB2878FFF7F9FA00244E4E5A -:104F70004E4FDFF83C81DFF83C910EE0305DFFF7EB -:104F8000EEFA385DFFF7EBFA18F80400FFF7E7FADE -:104F900019F80400FFF7E3FA641C28788442EDD383 -:104FA00037E470B5444C454E0025607810B3BDE839 -:104FB0007040FBF7B5BF306804F09FFAA17951B19A -:104FC00001291CD002291FD0032923D0042929D06C -:104FD00005293FD12CE0242803D00021A17149B933 -:104FE00001E00121FAE7232802D0522832D102E061 -:104FF000FBF796FF2EE0012002F071FF2AE04D281A -:1050000004D10220A07125E03C2801D00020F9E75E -:105010000320F7E740281CD8607125712572E071E4 -:105020000420EFE76072E1794140E1710520E9E792 -:1050300021796279914207D2E2794240E271204AB5 -:105040005054491C217105E0E179814201D1FFF7FB -:1050500088FBA571306804F04DFA0028ABD1607868 -:10506000002809D14FF40060FCF723FC002803D08E -:10507000BDE8704001F0E3B970BD000054010020AC -:105080005C01002060000020C90000207E0100209B -:105090000804002040420F000C0400206A01002098 -:1050A000E8F7FF1F7A010020DA0A0020EA0A002050 -:1050B000FA0A00200A0B0020B4010020DC080020BE -:1050C000880C002044F25061884201DDA0EB4100D1 -:1050D000FE49884202DA48F6A041084470472DE9AB -:1050E000F04706465068994614460D46301A05F0BA -:1050F000F3FB296805F0A4FB2061A768394605F099 -:1051000063FB8046F24890F8B80005F0EEFBF149E9 -:1051100005F060FB01464FF07E5005F091FB2D68D5 -:10512000294605F0FFFA0146284605F089FB41466D -:1051300005F050FB394605F0F5FA2061C4E901603D -:105140000146D9F8080005F045FBBDE8F04705F039 -:10515000D1BB2DE9F0411D4614460E4605F0BCFBBF -:10516000696805F037FB316805F034FB216805F00C -:10517000D9FA2060ED680746284605F0BBFB0646D5 -:1051800085F0004005F0B6FB0546384605F0B2FB59 -:105190003246294601F082FA05F09EFB2060BDE808 -:1051A000F04105F0A7BB70B5CB4CD4E90D01401A16 -:1051B000FFF788FF0028D4E90D01A0EB010002DD14 -:1051C000FFF780FF02E0FFF77DFF404241F29411BC -:1051D000884228DAD4E90D01401A05F07DFBBF4969 -:1051E00005F0F8FA0646E06B05F07FFB0546304611 -:1051F00006F0A0FD294605F0EDFA05F07BFB00B2B4 -:1052000040F6B8322082514201F048FA616B0844FE -:1052100048F6A0416064884200DD401A002800DAA8 -:105220000844606470BD606BFBE72DE9FE4F0546E6 -:10523000FFF7B9FFA84842F22831406C081A05F080 -:105240004BFBA64905F0C6FA044606F08DF901901D -:10525000204606F06FFD00900024284605F03CFB38 -:10526000DFF874A2DFF87892DFF878B20AF1300A3A -:10527000029099481A3030F9140005F02DFB0546CC -:105280005DF82410029805F0A5FA294605F09CFA6D -:1052900005F030FB00B24FF47A7255462AF814003C -:1052A000514201F0FBF98E4900B225F81400603933 -:1052B00000F03CFE04EB8406894B8749074609EB66 -:1052C0008602904635F91400603B2831FFF741FF14 -:1052D000834B81490744424635F91400603B28312D -:1052E000FFF7FDFE384400B240F6B8325D462BF8B9 -:1052F0001400514201F0D2F925F81400784859F809 -:1053000026102838641C40F82610022CB1DBBDE8BA -:10531000FE8F2DE9F05F704E0024DFF8C491503607 -:10532000DFF8C0B1A6F1360AA9F128096C4956F890 -:105330002400803900F0FAFD3AF81410664F401A44 -:105340003037674900B227F81400703900F0EEFDDD -:10535000054637F9140056F8241004EB8407084476 -:105360005F4B5D4909EB87029046703B2831FFF7A0 -:10537000F0FE28445A4B58492BF814005D4642462B -:1053800056F82400703B2831FFF7A9FE4FF4FA626B -:10539000514201F083F93AF914103131622900D8F1 -:1053A000002035F8141040F6B832084400B225F851 -:1053B0001400514201F072F925F81400484859F8D8 -:1053C0002710641C40F82710022CAFDBBDE8F09FCB -:1053D00070B50546086819681446401A05F07CFA4D -:1053E0003D49C96A05F0F6F905F084FA01463A48E4 -:1053F0005030416029682268891A016070BD2DE92A -:10540000F0410F46DDE90685116800681E46081A5E -:1054100005F062FA044630683968401A05F05CFA13 -:105420002D49C96A05F0D6F90646014605F0D2F9BC -:1054300007462146084605F0CDF9394605F072F9D0 -:1054400006F03EFD284905F0C5F905F06CFAC8F8EC -:10545000000084F00040314605F05CFF234905F070 -:10546000B9F9234905F05EF905F044FA28600028EF -:1054700003DA48F6A04108442860BDE8F0812DE930 -:10548000F0471C48144CD0E90056617804F14809F3 -:1054900091B34FF07E50A16A05F0D2F98246D9F857 -:1054A0000400301A05F018FAE16A05F093F9514644 -:1054B00005F090F905F01EFA07B2D9F8000004F1E2 -:1054C0001A08281A05F008FA514616E0B0B9FFFF8D -:1054D000E8070020DB0FC940BC020020D3023739A7 -:1054E000680D0020280100202C7D8E3FA00CB345C4 -:1054F00000A00C464C0100201AE005F06BF905F005 -:10550000F9F901B204F12400B0F902203A4402EBA7 -:10551000D27242F34F02A8F80220B0F900301944C9 -:1055200001EBD17141F34F01A8F8001042800180D6 -:1055300001206070C9E90056BDE8F08710B5044647 -:1055400005F0CAF9002C01DC80F00040F74905F0B5 -:1055500077F9F74905F03EF906F006F8F549C86213 -:1055600010BD10B5F44CE07A002811D0F348007853 -:1055700005280DD3F249F34A086810604968516064 -:10558000FFF7DCFFF048EB49008888820120207398 -:1055900010BD2DE9F043E749EC48E74B8E7A012531 -:1055A00002790024062E29D004DC022E09D0032E15 -:1055B00004D116E0122E33D0302E3DD00020BDE8AD -:1055C000F083DF4A466856608668166000694FF4CB -:1055D0007A7290FBF2F0DE4A1080C87AD8724D736E -:1055E00051E04079C00701D0032A03D00020C872DF -:1055F00010B148E00120FAE7DC7244E0C27AD20739 -:1056000002D0827A032A03D00022CA7212B102E0C9 -:105610000122FAE7DC72C94A90F82F00107032E0DC -:10562000CC4B828A1A80806942F2107290FBF2F0B1 -:10563000C94A10808D7326E0C84B102A1A7001D910 -:1056400010221A700022C64EC64FDFF81CC3DFF8C6 -:105650001C931D7815E000BF02EB420300EB8303AF -:1056600093F8088006F8028093F8098007F8028012 -:1056700093F80B800CF8028093F80C8009F80280F4 -:10568000521CAA42E8DB487B8A7B104097D04C73BF -:105690008C73012093E72DE9F041A64900240A46C6 -:1056A00091F809E092F807C0157A0CEB0003D78A4D -:1056B000DEB22246BEF1090F51D2DFE80EF0080536 -:1056C0000F151C2333434900622803D04A72B528C2 -:1056D00002D044E0022033E0012031E003224A728C -:1056E0000873C87108723AE004224A72CE717219C6 -:1056F0000A72887233E005224A72CE7172190A72F8 -:10570000C8822CE006234B72731907EB0020CE7180 -:1057100080B20B72C882B0F5007F01D9CA824A728A -:105720000A831CE0CE7172190A720A8BC82A01D250 -:10573000864B9854521C90B20883B8420FD1072070 -:1057400048720CE008234B72844508D04A7206E088 -:105750004A72854203D1FFF71CFF00B101242046A5 -:105760008BE670B5034600200246054611E02E2C5C -:1057700004D1521C00290FD054181D559C5C00EB1D -:1057800080004000A4F13006092E01D830382044B2 -:10579000521C9C5C002CEAD170BD2DE9F041002622 -:1057A000804635463746044604F00AFF016800E0AB -:1057B000641C2078085C2028FAD0404609E01EB11D -:1057C00006EB86025206160E10F8012B303E3244CC -:1057D000D6B2221A022AF2DC09E01DB105EB8502DD -:1057E0005206150E10F8012B303D2A44D5B28442E2 -:1057F000F3D820782E280ED1641C002007EB8702F6 -:10580000570022788B5C202B02D1303F1744641C58 -:10581000401C0428F2DB56480621454307EBC7002D -:1058200000EB071005EB8000B0FBF1F051494E434F -:1058300000EBC61021E62DE9F04700273D4C054658 -:10584000242815D0414E2046F03EC0782C2D13D090 -:105850002A2D11D021460D2D497964D00A2D62D010 -:105860000F2802D23554401CE07000295CD0BAE009 -:10587000A770E7702771B6E03754A0784FF00109A0 -:1058800028B1A179012921D002294ED0A2E0A77127 -:105890003078472807D17078502804D1B07847284D -:1058A00002D0522809D095E0F078472804D1307909 -:1058B000412801D184F806908CE0F0784D2804D17D -:1058C0003079432801D10220A07183E0DFF8708095 -:1058D00002280CD003280FD0042816D0052819D090 -:1058E000062849D0072850D0092855D072E017481B -:1058F000F038FFF752FF05E0307853286AD1D8F826 -:1059000000004042C8F8000064E01048F038FFF79B -:1059100044FF05E0307857285CD1D8F804004042B5 -:10592000C8F8040056E063E05AE03BE08096184B6C -:1059300035FA8E3CBC020020700A0020D300002003 -:105940004C01002054010020B0010020B80D0020BF -:105950007601002078010020660100207A010020F5 -:10596000DA0A0020EA0A0020FA0A00200A0B0020C6 -:1059700040420F002D3101003078302801D901203C -:1059800000E00020FE49C87224E00021FD48FFF736 -:10599000E8FEFD4908701DE00021FA48FFF7E1FE2E -:1059A000FA4916E0072802D008280DD012E001219C -:1059B000F448FFF7D6FE41F2184148434FF47A719C -:1059C000B0FBF1F0F24904E00121EE48FFF7C9FE17 -:1059D000F0490880A078401CA070E7702A2D04D000 -:1059E0002079684020710020A6E584F80590FAE748 -:1059F0000029F8D0307800F0C7FA0501707800F07F -:105A0000C3FA28442179C0B288426771EBD1A079EA -:105A10000128E8D190E52DE9FF5FDF49C0B291F898 -:105A20001C1119B1012904D002297CD1FFF703FF11 -:105A300001E0FFF730FE002875D0D24C1034A0688A -:105A4000E06002F072F9A0602020FBF725FFD34848 -:105A50004FF0000B0178012910D001210170C848D6 -:105A6000C17A00295FD0C849097805295BD38246ED -:105A7000407830B19AF80C1031B108E080F800B0ED -:105A8000EDE78AF80CB002E008B1FFF76AFDC44800 -:105A900005218E460278C44C521CB2FBF1F301FB87 -:105AA0001322C0490270002091F90090BC4954F8BB -:105AB00020306831BA4D41F82030BC49783593FB2D -:105AC000F1F145F82010BA4D00EB80074D4303EB90 -:105AD000C51342F2107593FBF5F5AEB2B04D4035EB -:105AE00025F81060A74DC83505EB8707AC4D57F872 -:105AF00022C0603555F8208047F82230A8EB0C0C06 -:105B0000634445F8203093FBFEF3A94D6D42694391 -:105B100003EBC111A24B7033B9F1010F43F8201010 -:105B200007D1B61E00E080E0B6F5797F01D844F8D1 -:105B30002010401C0228B9DB02F0F7F8984D296AC2 -:105B4000401A04F0D2FE9B4904F07AFEA86202F0EB -:105B5000ECF82862A86A4FF07E51884200DB0846C4 -:105B6000A86203A902A8944BCDE900011A1F211DC8 -:105B70008D48FFF744FC02986426B0FBF6F08F498D -:105B80008F4A57460880039890FBF6F010809AF8E9 -:105B90000C0018B9A1F800B0A2F800B0FFF76FFC34 -:105BA000387A10B9F87900283FD07D49343101F1B5 -:105BB000080000F11C07CDE900013B1D3A46211DFC -:105BC0007948FFF71CFC231D774A391D3846FFF73B -:105BD000FFFB744C94F90000012828D0022824D13E -:105BE000784F0121B7F9BE0000F0ABF9FFF71DFBBC -:105BF00097F8BA00744A18B1686C90FBF6F0108000 -:105C0000B7F8B600E96B88420BD2D5E90D01401A0E -:105C1000FFF758FA002800DC404242F21071884237 -:105C200003DD01202070A88A1080BDE8FF9FFFF7E8 -:105C300070FBFAE72DE9F047624C607904F055FEFD -:105C4000DFF88891494604F0FBFD4E4D2035286071 -:105C5000E07B04F04AFE494604F0F2FD5C4EEE6043 -:105C60006860A07904F041FE5A4F394604F0E8FD1F -:105C700010352860207C04F038FE494604F0E0FD31 -:105C80006860A07E04F031FEDFF82881414604F010 -:105C9000D7FDC5E90206E07904F027FE394604F095 -:105CA000CFFD10352860607C04F01FFE494604F0EB -:105CB000C7FD6860E07E04F018FE414604F0C0FDB8 -:105CC000C5E9020638E42DE9F0412E4C06461034B1 -:105CD0000027032527704FF48070FBF7EAFD0028AA -:105CE00019D0667002F021F8C4E901702A4890F8D2 -:105CF0001C0100B90125FFF79DFF374906EB46005F -:105D00002B4651F820203549354802F09DF9354998 -:105D100048600120207023E52DE9F041194C03274C -:105D200010341D4A60782F4D00EB400192F81C3171 -:105D3000294E686813B1012B1ED105E056F82110D9 -:105D400003F0DEFB27700BE52378012B4CD056F8CF -:105D5000211003F0D5FBDFF88080002608F13C0815 -:105D6000686818F8061003F0B5FB042001F0ECFF9A -:105D7000761C8C2EF4D3277000206060F0E40000C5 -:105D8000700A0020C80C0020D300002076010020FB -:105D900078010020660100206C04002064010020CE -:105DA000BC020020C90000204C0100208096980011 -:105DB000D3CEFEFF00007A4458010020720100207B -:105DC00074010020E8070020B20100200000C84252 -:105DD0000000FA4400002041B4CC0008175A000823 -:105DE00000440040DC0800200027904607EB4700F5 -:105DF00056F82010686803F083FB98F91D0100EB4A -:105E0000400006EB80004168686803F066FBC8202C -:105E100001F09AFF7F1C052FE8DB98F81D016070E8 -:105E200002202070A8E710B55E4C207805282AD201 -:105E3000DFE800F02903031C0600BDE810406BE713 -:105E400060680521401C60606078401CC0B2B0FBF7 -:105E5000F1F201FB1200607001F067FF5249A0608F -:105E6000002008705149C87201200BE001F05DFF6D -:105E7000A168401A40F6C411884204D92020FBF7DB -:105E800010FD0420207010BD2DE9F05FDFF814A193 -:105E90000024474FDFF81C81DFF81C910AF1400A0B -:105EA00025460AF1280B00BF27F8145028F8145093 -:105EB00004EB840629F814500AEB860000F06DF814 -:105EC0000BEB860000F069F83648903000EB860056 -:105ED00000F063F8641C022CE6DBBDE8F09F7CB5A3 -:105EE000364C02682260096861600068FFF726FB93 -:105EF000A4F1240101F10800314ECDE90001231D78 -:105F00002246311D3046FFF77AFAA4F15805331DB9 -:105F1000686B68643246211D2046FFF759FA686BAA -:105F2000A8632848B0F8BC0068827CBD10B50C4658 -:105F300004F0D2FC216804F04DFCBDE8104004F0F0 -:105F4000D9BC70B51D4C583CE26B21B1B0EB520F7F -:105F50000BD3500809E0904200D31046194900B213 -:105F6000B1F8BC10814200DB0846B4F9125000B20F -:105F7000A84208DD1449A06A04F02CFC04F0BAFC25 -:105F8000284400B2608270BD3038C0B2092801D9FF -:105F9000C01FC0B200F00F007047002101604160D7 -:105FA00081607047D80C0020D3000020700A0020C8 -:105FB0000C0100202C0100202801002014030020E7 -:105FC0004C010020E80700200000C842F0B5404A1C -:105FD000404C1178E9B192F805C01779032104F11A -:105FE0001C035E1816F8015CFD4005F00F05072D37 -:105FF00009D213F801E016F8016C06EA0C060EEB64 -:10600000062644F82560891CC9B21029E9D300216D -:106010001170314907280ED2937863B151782E4A16 -:10602000104490F80A0149B154F820004FF47771F8 -:1060300001EB500006E0B1F81401F0BD34F8200087 -:1060400000F5777080B2F0BD70B5214C0126054691 -:10605000A67001F050FEA168421AC4E9020241F2A2 -:1060600088300021824200D9E1701A4AE0781C325F -:1060700015540F2802D0401CE07070BD17482670E0 -:10608000018070BD70B504461348114990F8122183 -:10609000032007252AB1012A08D108714D7101207A -:1060A00003E002220A7148710020487001234FF476 -:1060B000E1320B490B4801F0C7FF01460A48C160B5 -:1060C0000CB10A492160457470BD014800787047E1 -:1060D0003C030020800E00206C040020D60000202D -:1060E0004960000800440040DC080020CD5F000843 -:1060F00070B57C4C06460125207880B901F015FE6C -:10610000A1683231884207D32570012001F027FEB3 -:1061100001F00BFEA06070BD20780028FBD001F0DC -:1061200004FEA16831448842F5D30020207001F0BC -:1061300016FE01F0FAFD6C49A060087808B1401E17 -:106140000870657070BDF8B5664D8DF800008DF86B -:1061500001108DF802208DF80330A8791DF8001089 -:1061600044292DD04C2929D04D2925D04E292AD07B -:1061700032240026032806D274B12046FFF7B8FF68 -:10618000A879032808D301F0D0FDA968001B884234 -:1061900002D95548AE7106706878012801D0002CEC -:1061A00009D1A879032801D2401CA8716E702E7005 -:1061B000002001F0D4FDF8BD6424DAE7C824D8E754 -:1061C0004FF4FA64D5E70024D3E72DE9F047DFF870 -:1061D0001CA10546434C9AF80D004FF0010900261A -:1061E00010B184F8029000E0A6704FF40070FBF745 -:1061F00060FB3F4F18B33F493F484FF0020C91F806 -:10620000AC30B0F9000003EB830282420FDA97F85A -:106210000180B8F1000F0AD084F8049091F8AD1015 -:10622000194401EB8101814201DA84F804C0824201 -:1062300003DA797809B984F804C000B926712020FE -:10624000FBF722FB40B19AF80A1011B99AF80B003B -:1062500008B1F87AA8B1E6702079022814D0012894 -:1062600017D0E078012817D0A078012817D0042D86 -:1062700019D0022D1ED0012D1ED0607901281ED00C -:1062800022E084F80390E7E74E22442311464C2095 -:106290000DE04D234C2208E04D234E2201E04D231A -:1062A0005322532102E044234D224D215320BDE8C7 -:1062B000F04748E7442305E044234E22F5E7787889 -:1062C00010B14E234D22ECE70748007818B1BDE825 -:1062D000F04732200CE72670BDE8F047002001F0BF -:1062E0003EBD00004C030020C8000020C60A00206C -:1062F000700A0020E8070020D600002010B5D84C16 -:106300005E28A26807D05D280CD001461046BDE883 -:10631000104003F0DFB85D21104603F0DBF83E21AA -:10632000A068F4E75D21104603F0D4F83D21A06891 -:10633000EDE72DE9F041132000F04AF9C94C20683F -:10634000002800DC4042C84D90FBF5F000B200F0A0 -:1063500051F91B2000F03CF92068002800DC404285 -:106360000A2690FBF6F042F2107790FBF7F107FB5C -:10637000110000B200F03EF9232000F029F9206856 -:10638000002801DA532000E04E2000F033F91220FB -:1063900000F01EF96068002800DC404290FBF5F038 -:1063A00000B200F027F91A2000F012F96068002806 -:1063B00000DC404290FBF6F090FBF7F107FB110088 -:1063C00000B200F017F9222000F002F960680028FE -:1063D00001DA572000E04520BDE8F04100F00AB99D -:1063E00010B54FF40040FBF764FAA04A9C4920B175 -:1063F00092F82901012806D002E0002082F8290144 -:106400000868886010BD9A48FBE770B5974890F817 -:10641000291111B9974A52780AB1012400E00024E9 -:10642000954D2A78944209D039B914B14FF41650D9 -:1064300001E0D0F82001FEF72CF92C7070BD2DE999 -:10644000F0478A4890F8290118B98A48407800280E -:106450007ED08348806803F04DF8002878D101F0A1 -:1064600064FC854D6968401A7D2871D301F05DFC9C -:1064700068606878814F401CDFF80482DFF804927E -:106480006870002404F12400C0B200F0A1F838883C -:1064900004F02BFA064638F9140004F01DFA3146D0 -:1064A00004F0CEF9494604F095F904F023FA00B25D -:1064B00000F0A0F8641C032CE4DB00F096F8687888 -:1064C0004FF06404800724D1102000F081F86E4E54 -:1064D000306890FBF4F000B200F08CF8212000F05E -:1064E00077F8306890FBF4F104FB110000B200F083 -:1064F00081F8142000F06CF86448B0F9000000F056 -:1065000079F81C2000F064F8002000F073F800F027 -:106510006CF86878400735D1022000F059F85C48E3 -:106520004FF00A08B0F9001091FBF8F000B200F04B -:1065300061F80220FBF7BDF9E0B100F065F85548BD -:106540006E21007848431521B0FBF1F63A2000E0B7 -:106550003CE000F03DF8B6FBF4F738B200F04AF842 -:106560003B2000F035F804FB1760401DB0FBF8F04D -:1065700000F040F82020FBF787F908B1FFF7D9FEBB -:1065800000F033F86878282820D10020687001F0E6 -:10659000CCFB4FF47A71B0FBF1F43C25B4FBF5F67B -:1065A000B6FBF5F005FB1067172000F011F8380274 -:1065B00000B200F01FF8182000F00AF805FB1640A2 -:1065C00000F018F8BDE8F04700F00FB8BDE8F0871C -:1065D00070B5234C05465E21A06802F07BFF29467A -:1065E000A068BDE8704002F075BF1D485E2180685C -:1065F00002F070BF10B50446C0B2FFF77FFEC4F3CF -:106600000720BDE8104079E670B52248224E40F6DA -:10661000340200783178184DB0FBF1F050432A2253 -:10662000B0FBF2F06A88B2FBF1F301FB13214FF6E5 -:10663000FF7202EA011141EA0024C0F3032004437F -:106640000620FFF7C5FF20B2FFF7D4FF6888317836 -:10665000401C80B2B0FBF1F201FB1200688070BDFB -:10666000DC0800204C010020A08601006C04002002 -:10667000D8140020700A0020580300208201002056 -:106680008000002000007A4420000020B00100209B -:10669000E8000020D200002068010020884201DAD2 -:1066A000084670479042FCDD104670472DE9F047E0 -:1066B000BD49BD48E831B0F9E600B1F90050B1F983 -:1066C000024010B90DB9002C7ED0B84A00211170DB -:1066D00004F002F9B64F394604F07CF8DFF8D492A2 -:1066E000494604F0ADF88046284604F0F5F83946EE -:1066F00004F070F8494604F0A3F80646204604F07A -:10670000EBF8394604F066F8494604F099F8074674 -:10671000304604F029FF0446404604F025FF214698 -:1067200004F058F8A44C2060384604F01DFF0546DC -:10673000404605F0FFFA294604F04CF80546384675 -:1067400005F0F8FA8246304605F0F4FA81464046F4 -:1067500004F00AFF494604F03DF8514604F03AF8C7 -:10676000294604F031F86060384605F0E3FA054642 -:10677000404605F0DFFA294604F02CF80546384675 -:1067800004F0F2FE8246304605F0D4FA81464046D7 -:1067900004F0EAFE494604F01DF8514604F01AF8E8 -:1067A000294603F0BFFFA060304604F0DDFE054639 -:1067B000404605F0BFFA294604F00CF8E060384680 -:1067C00004F0D2FE054600E057E0404604F0CCFE5F -:1067D000294603F0FFFF0546384605F0ABFA82462E -:1067E000304605F0A7FA8146404605F0A3FA49462F -:1067F00003F0F0FF514603F0EDFF294603F092FF4E -:106800002061384605F096FA0546404604F0ACFE95 -:10681000294603F0DFFF0546384604F0A5FE824610 -:10682000304605F087FA8146404605F083FA49462E -:1068300003F0D0FF514603F0CDFF294603F0C4FF1B -:106840006061304605F076FA80F00040A06138467D -:1068500005F070FA0546304604F086FE294603F03E -:10686000B9FFE061384604F07FFE0546304604F08B -:106870007BFE294603F0AEFF2062BDE8F0872DE9DC -:10688000F0470546B0F90080B0F90260B0F90400A5 -:1068900004F022F8484C8246A16803F09BFF0746AB -:1068A000304604F019F88146616803F093FF06460C -:1068B000404604F011F88046216803F08BFF314612 -:1068C00003F030FF394603F02DFF04F013F8288061 -:1068D0005046616903F07EFF07464846216903F090 -:1068E00079FF06464046E16803F074FF314603F045 -:1068F00019FF394603F016FF03F0FCFF688050468D -:10690000216A03F067FF07464846E16903F062FF2A -:1069100006464046A16903F05DFF314603F002FFE1 -:10692000394603F0FFFE03F0E5FFA880A5E7092A3A -:1069300011D2DFE802F0100509161C21262A2E00CC -:1069400002880A80428803E042880A8002880CE0BC -:106950004A808088888015480078002822D108461F -:106960008DE7028852420A8042885242F0E742880C -:1069700052420A800288EBE7028852420A8042882B -:106980000CE042880A80028808E002880A80428877 -:1069900003E0428852420A80028852424A8080883C -:1069A0004042D7E7704700006C04002060030020DD -:1069B000DB0F494000003443AC0E0020444908443A -:1069C000444990F80A0151F820004FF4777101EB27 -:1069D000500080B2704710B5044601F08CF93E4972 -:1069E00002464868131A0020B3F57A6F00D9487040 -:1069F0004A604A780AB90F2C0AD1087032B1354B77 -:106A000020331344182A03F8014C02D0521C4A7058 -:106A100010BD304A2032D27D0AB901220A70487076 -:106A200010BD10B504462A4800212A4BB0F81401C5 -:106A30004200A2F5F76200BF43F82120491C082953 -:106A4000FADB0123254A2649264801F0FDFA0146D2 -:106A50002548C1600CB1254921600821417410BD51 -:106A60001D4B10B5187840B11A484FF00002203085 -:106A7000817DC908C90702D01A70002010BD1C49C9 -:106A8000401C0A8030F8011CC1F30A0411490C6053 -:106A90000488C4F3CA044C600468C4F38A348C606C -:106AA000B0F80340C4F34A04CC608488C4F30A14E9 -:106AB0000C614468C4F3CA344C61B0F80740C4F3B5 -:106AC0008A048C6100894009C8611A70012010BDD8 -:106AD0006C040020D00E002064030020A08601007A -:106AE000D769000800440040DC080020BD690008A8 -:106AF000D60000202DE9F0410646007890B008B19C -:106B0000012500E00025DFF8D880404602F0BCFEF9 -:106B10003448009000243448CDE90104012725B110 -:106B20000220CDE90304802002E0CDE903740020B7 -:106B300005904FF480700690800007902020089008 -:106B40000002CDE909046946404602F00AFF01212E -:106B5000404602F030FF8DF830500B948DF83170C4 -:106B60004FF46020CDE90D040DB1022000E00120BA -:106B70001C4C8DF83C004C3C0BA9204602F0F0FD6B -:106B8000032301220421204602F03FFE2DB131787B -:106B900003230222204602F038FE0121204602F0A3 -:106BA00008FE0121204602F0FAFD204602F00BFE0D -:106BB000204602F00DFE0028FAD1204602F00FFE1A -:106BC000204602F011FE0028FAD10121204602F0F1 -:106BD00012FE10B0BDE8F081034931F81000704793 -:106BE000080002404C2401406C0300202DE9FF47BF -:106BF000DFF86C81814698F80000D0B300273E464C -:106C00003D463C46641CE4B202AB082232215320CC -:106C100000F063FD9DF808009DF80910202C00EBA2 -:106C2000012000B207449DF80A009DF80B1000EB0C -:106C3000012000B206449DF80C009DF80D1000EBF9 -:106C4000012000B205449DF80F0000F07F0001D242 -:106C50000028D7D197FBF4F0ADF8000096FBF4F0D4 -:106C6000ADF8020095FBF4F0ADF8040088F802409E -:106C70001EE0FFE702AB06223221532000F02DFD7B -:106C80009DF808009DF8091000EB0120ADF8000008 -:106C90009DF80A009DF80B1000EB0120ADF80200F2 -:106CA0009DF80C009DF80D1000EB0120ADF80400DC -:106CB00098F8012049466846FFF739FEBDE8FF878E -:106CC00070B5274D04464FF0080228784FF02D018B -:106CD00000284FF053000ED000F0F9FC0A223121B9 -:106CE000532000F0F4FC0C222C21532000F0EFFC88 -:106CF0009022382108E000F0EAFC0A2231215320DA -:106D000000F0E5FC0A222C21532000F0E0FC15499C -:106D100040F20910002C088000D06C7070BD38B5AE -:106D2000054600208DF800000F480C460F4900680A -:106D300088420AD06B4601220021532000F0CDFC8E -:106D400018B19DF80000E52801D0002038BD0449A5 -:106D5000287808700648206006486060012038BD29 -:106D600070030020820100200C040020001BB700EB -:106D7000C16C0008ED6B000810B54FF4804420464C -:106D800002F076FE012805D1204602F07FFEB949C7 -:106D90000120087010BD70B50D46B649B64A0646CA -:106DA00088885389B2F91440C01A13895843B2F93C -:106DB0001230C013DB02044493FBF4F31844D06197 -:106DC00000EB8000082202EB40000411886800F00C -:106DD000D0F806B13060002D00D02C6070BD38B501 -:106DE000A44C207810B96088401C60806B46032258 -:106DF000F621772000F071FC9DF800009DF801104D -:106E0000000440EA01209DF8021008439A49B1F9B4 -:106E10002010C1F10801C840A06038BD9648342157 -:106E200090F8200001EB80109249C2B20020087057 -:106E3000F421772000F04BBC38B58E4C207810B987 -:106E40006088401C60806B460222F621772000F0AB -:106E500044FCBDF8000040BAA08038BD8549002040 -:106E60002E220870F421772000F031BC2DE9F04388 -:106E700004468248824985B00068884203D10020D8 -:106E800005B0BDE8F083DFF8EC9199F8010008B196 -:106E90000120F5E74FF40055ADF80C5002208DF8B5 -:106EA0000F001020774E8DF80E0003A9304601F038 -:106EB00039FF6F00ADF80C7004208DF80E0003A9A7 -:106EC000304601F02FFF35610E21022003F052FA07 -:106ED00000208DF8080008208DF809004FF0010807 -:106EE000019747468DF80A8001A802F08BFD282003 -:106EF0008DF810000F208DF811008DF812008DF81C -:106F0000137004A802F0F9FB142000F01DFF6B467B -:106F10000122D021772000F0E0FB574F9DF80000C0 -:106F20000321F8753984552801D07561A7E76B46B0 -:106F30000122D121772000F0D0FB9DF8000000F065 -:106F40000F0139760009787600F05CF889F8018045 -:106F500041F27070208046F6781060804A48606088 -:106F60004A48A0604A48E0604A4820614A48606157 -:106F70008EE770B54049CA69B1F90E40A2F57A6250 -:106F800002FB02F31D136C43E512B1F90240B1F9A3 -:106F90000460544305EBE424B1F9005004EB85058B -:106FA00091F82040A54056437213B1F90C601B13B1 -:106FB0005E4302EB2642921C9210C98802F5004201 -:106FC000AD1C5143C90B4CF25032A0EBA500E2407E -:106FD0005043B0F1004F03D24000B0FBF1F002E0AB -:106FE000B0FBF1F040000112494340F6DE3251435C -:106FF0002A4A0914424301EB224101F6CF6100EB1A -:10700000211070BD00B587B06B461622AA217720EB -:1070100000F063FBBDF8000041BA17480180BDF8DD -:10702000021049BA4180BDF8041049BA8180BDF808 -:10703000061049BAC180BDF8081049BA0181BDF8EF -:107040000A1049BA4181BDF80C1049BA8181BDF8D6 -:107050000E1049BAC181BDF8101049BA0182BDF8BD -:10706000121049BA4182BDF8141049BA818207B0A2 -:1070700000BD0000740300200C0F00200C04002051 -:10708000001BB700001001405D6E0008396E00085B -:107090001D6E0008DF6D0008976D000843E3FFFFD9 -:1070A00038B5044600208DF800006B4601220A2105 -:1070B0001E2000F012FB18B19DF80000482801D0F6 -:1070C000002038BD0CB18D480470012038BD7FB55B -:1070D000054602AB062203211E2000F0FEFABDF891 -:1070E000080040BA00B203F0F7FB844C241D21686D -:1070F00003F070FB03F0FEFBADF80000BDF80A00E2 -:1071000040BA00B203F0E8FBA16803F063FB03F0B0 -:10711000F1FBADF80400BDF80C0040BA00B203F07A -:10712000DBFB616803F056FB03F0E4FBADF8020003 -:10713000201F294602786846FFF7F9FB7FBD2DE93D -:10714000F0476F4800246F49006825468EB02E46F0 -:107150004FF0010888420CD14FF48050ADF8280060 -:1071600002208DF82B0004208DF82A000AA9664819 -:1071700008E06649884207D14FF48040ADF8280006 -:107180000AA9634801F0CEFD322000F0DDFD112296 -:1071900000211E2000F09BFA602201211E2000F039 -:1071A00096FA642000F0D0FD6846FFF790FFDFF804 -:1071B00058A1DFF8609100270AF10C0A0122022190 -:1071C0001E2000F084FA322000F0BEFD6846FFF772 -:1071D0007EFFBDF90210BDF90400BDF900200D4489 -:1071E00014440644814201DA0B4600E00346934210 -:1071F00001DD104602E0814200DA0846484502DC23 -:107200004FF0000808E0DAF8001081F01001CAF829 -:1072100000107F1C0A2FD1DB122200211E2000F05B -:1072200056FA0027012202211E2000F050FA3220D7 -:1072300000F08AFD6846FFF74AFFBDF90020BDF95E -:107240000210BDF90400A41A6D1A361A814201DA3F -:107250000B4600E00346934201DD104602E0814206 -:1072600000DA0846484502DC4FF0000808E0DAF88A -:10727000001081F01001CAF800107F1C0A2FD1DB2A -:10728000204603F029FB244F0146384603F0D8FA84 -:107290001A4C20F00040241D2060284603F01CFBFF -:1072A0000146384603F0CCFA20F0004060603046DA -:1072B00003F012FB0146194803F0C2FA20F0004027 -:1072C000A060702200211E2000F001FA202201217E -:1072D0001E2000F0FCF9002202211E2000F0F7F928 -:1072E000642000F031FDB8F1000F04D14FF07E5062 -:1072F00020606060A0600EB0BDE8F08780030020D1 -:107300000C04002000127A00000C0140001BB700A2 -:107310000010014000F0FFFF00406F4601C05E46D4 -:1073200030B587B005464FF44060ADF81400022038 -:107330008DF817001C208DF8160005A9FB4801F0F8 -:10734000F1FCFB4CE56000F007FAE06802F0A4FBFA -:10735000684602F00CFC00224FF44071E06802F035 -:107360003CFC0025ADF804504BF6FF70ADF806006C -:107370004FF48040ADF80C00EE4800900121E06829 -:1073800002F003FC6946E06802F099FB4FF4A0604C -:1073900002F0AEF922208DF810008DF811508DF812 -:1073A000125001208DF8130004A802F0A6F9212044 -:1073B0008DF810008DF8115004A802F09EF907B066 -:1073C00030BD38B5DA4CE068818A009111F4706FF5 -:1073D00001D001212170009911F4E06F25D0018BBB -:1073E00000224FF4806102F0F8FB009880051CD465 -:1073F000E0680188890518D40188C9050CD5018881 -:10740000C905FCD4012102F0D4FBE068018889059C -:10741000FCD4FFF785FF08E0012102F0CAFB00223F -:107420004FF44071E06802F0D8FBE068818A21F4F3 -:10743000706181820020207138BDC2E72DE9F041E2 -:10744000BB4CE068818A4FF00105C9B2CA074FF012 -:10745000000627D0018821F400610180012102F09B -:10746000B2FBE670607A20B1607860B9A079FF283D -:1074700009D061790022E06802F0BCFBA079FF2806 -:1074800048D0FF20C9E06570E079022804D1E068A7 -:10749000018841F40061018061790122E06802F015 -:1074A000A9FB37E08A074FF4806745D5BFF3508FBB -:1074B000E079012810D1607A70B1607860B1002164 -:1074C000E06802F080FBBFF3508FE068018B012180 -:1074D00002F06FFBA57018E0E068008BBFF3508FDF -:1074E000E079022808D1607A30B1607820B10021BB -:1074F000E06802F068FB06E0E079032805D1607AD5 -:1075000018B1607808B1002200E001223946E06835 -:1075100002F063FB94F90310E079401C814209D129 -:107520006670A07828B100224FF44071E06802F044 -:1075300054FB2671BDE8F0814A0753D5A570627AE5 -:107540007B494978CAB3C9B3E17902291FD900211F -:1075500002F039FBE06802F04AFB94F9031062691B -:107560005054491CE1700121E06802F022FBA57033 -:10757000E06802F03CFB94F9031062695054491C26 -:10758000E17001223946E06802F027FB25E0012185 -:1075900002F00FFBE06802F02AFB94F90310626925 -:1075A0005054491CE170E06802F021FB94F903108B -:1075B00062695054891CE1700FE000E000E009B9F5 -:1075C000217A31B1012102F0F4FAE078401CE07038 -:1075D00003E0012102F0E3FA6570E0680188C90563 -:1075E000FCD497E74A061AD502F001FB94F9031080 -:1075F00062695054491C48B2E070E179C01C814274 -:1076000004D100223946E06802F0E7FAE17994F902 -:1076100003008142E5D100F10100E0707AE709063C -:10762000DFD594F903104B1C5AB20BD02369595C77 -:10763000E27002F0DAFAE07994F9031088423FF43C -:107640005AAF67E7E270A17902F0CFFA607A0028BA -:107650007FF451AFE0790028F1D05BE7EEE6B0E6C9 -:10766000ECE670B5324C4FEA400047F2305560719D -:10767000A171012020720021617223616361E271B6 -:1076800020712170E068818889050ED40188C905C0 -:1076900005D401888905FCD4012102F080FA012279 -:1076A0004FF44071E06802F098FA207910B16D1E35 -:1076B000FBD104E01DB1207880F0010070BD60892D -:1076C000401C6081E068FFF72BFE002070BD07B50D -:1076D00002AB0122FFF7C5FF0EBD70B5144C4FEA97 -:1076E000400047F230556071A171002020720121E5 -:1076F000617263612361E27121712070E0688188A9 -:1077000089050ED40188C90505D401888905FCD4F2 -:10771000012102F044FA01224FF44071E06802F0C6 -:107720005CFA207940B16D1EFBD10AE0000C0140EB -:1077300090030020801A06001DB1207880F001001F -:1077400070BD6089401C6081E068FFF7E9FD0020A2 -:1077500070BD2A48408970472DE9F84F4FF44067C3 -:10776000ADF800704FF0020A8DF803A01420DFF886 -:1077700090B08DF802006946584601F0D3FA204DCA -:1077800010352F60DFF8789000262C1505F10408DD -:1077900009F1080902E00A2000F0CAFAD9F800004D -:1077A0004005F8D5C8F800400A2000F0C1FA2C6066 -:1077B0000A2000F0BDFA761CF6B2082EEED34FF484 -:1077C00000694646C8F800900A2000F0B1FA34601B -:1077D0000A2000F0ADFA2C600A2000F0A9FAC5F8E2 -:1077E0000090ADF800708DF803A01C208DF8020009 -:1077F0006946584601F096FABDE8F88F90030020DC -:10780000000C014038B504466B4602221B2168205B -:10781000FFF763FFBDF8000043F2903140BA08441F -:107820004FF48C71B0FBF1F02330208038BD1FB5D0 -:10783000044602AB06221D216820FFF74EFFBDF86B -:107840000800214640BA02B2D01702EB90708010B7 -:10785000ADF80000BDF80A0040BA02B2D01702EB42 -:1078600090708010ADF80200BDF80C0040BA02B272 -:10787000D01702EB90708010ADF804002F484278CA -:107880006846FFF754F81FBD70B50446192000F094 -:107890005BFA002215216820FFF719FF10B90320B9 -:1078A00000F0FCFA254D1621287840F018026820D7 -:1078B000FFF70DFF002217216820FFF708FF0122C4 -:1078C0003D216820FFF703FF01223E216820FFF7DA -:1078D000FEFE002C00D06C7070BD70B504460D46E5 -:1078E000192000F031FA002215216820FFF7EFFE81 -:1078F00000281CD012482060124860601248A06026 -:107900001248E0600D48622D12D004DC0A2D13D01D -:10791000142D05D10EE0BC2D06D0B5F5807F01D029 -:10792000032102E0002100E001210170012070BD6F -:107930000221FAE70421F8E70521F6E7A803002071 -:10794000897800082F7800080578000818449231DB -:10795000FEB5064614460D46684602F025FC012099 -:10796000ADF804000021ADF80050ADF80610ADF8F8 -:107970000810ADF802406946304602F065FBFEBDD6 -:1079800070B51646D04A02EB0015D04A02EB00143F -:107990000122206801F0EFFAD4E90101182200F079 -:1079A00087F9217B3246206800F03FF9A07B18B1AF -:1079B0000121206802F00AFC0121206802F0FCFB92 -:1079C000207B30B1042807D008280AD00C2806D123 -:1079D0000AE02068343001E020683830286028460A -:1079E00070BD20683C30F9E720684030F6E72DE9AB -:1079F000F0410546B4480F4600EB0516B348B27196 -:107A000000EB05142822D4E9010100F051F9217B93 -:107A100000222068FFF79CFF01224FF6FF712046ED -:107A200001F0C6FA3A462946204601F087FA304668 -:107A3000BDE8F08170B5A648002402894281018129 -:107A4000891A8BB240F68C218B4201D9C47070BD6B -:107A50009F49A3F2EF2540F2DB569E4AC978B54212 -:107A60001BD2082919D2984DE035042925F8113088 -:107A700007D2C588AB4204D9012305798B402B433B -:107A8000037103790F2B08D10471B2F90030142B64 -:107A900002DD143B138000E01480491CC170148087 -:107AA00070BD70B5884A894B02EB001203EB0013DE -:107AB000D47918681B7B8CB151811489824D091BC4 -:107AC00091819479E03525F814100024D471224670 -:107AD0001946FFF73DFF7F48048070BD11810121E9 -:107AE000D171BDE870400222194631E72DE9F04717 -:107AF0000446774DE1890020E980A17901B1022097 -:107B0000617801B1401C7449DFF8D081002651F83A -:107B100020704FF47A79BA5D02F00F0002F0F001A4 -:107B2000FF2A65D0A2781AB102285ED003285CD063 -:107B3000E2783AB1042858D0052856D0062854D007 -:107B4000072852D0E2790AB182424ED011F0300FAC -:107B500002D0227802B90021227932B1A27922B969 -:107B6000082801D0092800D1802162792AB1A279A0 -:107B70001AB9021F032A00D88021CA0605D500229F -:107B80005749FFF734FF082008E08A0608D5AA788D -:107B90005449FFF72CFFA87800F10100A87024E0F9 -:107BA0004A0612D52289B8FBF2F1A28989B202B93C -:107BB0004A46FFF7E5FE0146434A2878F03242F88C -:107BC000201000F1010028700FE009060DD5628930 -:107BD000B8FBF2F189B24A46FFF7D2FE0146424AAB -:107BE000687842F82010401C6870761C0E2E92DBDC -:107BF0000020BDE8F087364A1278904205D23A4A12 -:107C0000303A52F82000006801807047304A5278BC -:107C1000904204D2344A52F8200000680180704734 -:107C20003149403931F8100070477FB50646154696 -:107C30000C46684602F0AEFA7020ADF80000012054 -:107C4000ADF802000020ADF804000220ADF80800F5 -:107C5000C001ADF80650ADF80C0074B1042C15D07D -:107C6000082C1CD00C2C07D16946304602F038F99C -:107C70000821304602F0D3FA7FBD6946304602F053 -:107C800084F80821304602F0B4FA7FBD69463046D8 -:107C900002F0B0F80821304602F0B1FA7FBD694623 -:107CA000304602F0E3F80821304602F0B2FA7FBD18 -:107CB00008B5ADF800108DF8022002218DF80310F0 -:107CC000694601F02FF808BD300F0020F0CD000804 -:107CD000AA030020D6000020B4CD000840420F00C7 -:107CE000357A0008A37A00085010002080484168C7 -:107CF000491C4160704710B57D484FF0E023416852 -:107D00009A694468A142FAD10368006803EB43040E -:107D1000C4EBC313C2EBC302B2FBF0F001EB4102B0 -:107D2000C2EBC11100EBC10010BD71484068704743 -:107D300030B50546FFF7DFFF4FEA0004FFF7DBFF32 -:107D4000001BA842FAD330BD30B504464FF47A7513 -:107D500002E02846FFF7ECFF641EFAD230BD64490A -:107D6000896808474FF4805108B1624801E06148D2 -:107D7000001F016070474FF4805110B15D48001F33 -:107D800000E05C48016070472DE9F04F8DB018228B -:107D90005949684602F041FC032701F002FC012129 -:107DA000564801F08DFF012144F61D2001F07FFFB0 -:107DB0000121084601F072FF01F09DFF4FF6FF70B0 -:107DC000ADF818004B484FF0000A8DF81AA006A92C -:107DD000143800F0A7FF06A9494800F0A3FF06A940 -:107DE000484800F09FFF4848416841F000714160F9 -:107DF000464DDFF81C813E4E2968414501D145487A -:107E000000E04548B0600020FFF7A9FF3C4908208A -:107E10001031086010200860A946002483466D4692 -:107E2000D9F80010414506D105EBC4008179142929 -:107E300001D180F806B005EBC401091D55F83400E6 -:107E400000F070FF641CBC42EAD307A801F0E0FE1A -:107E500032490798B0FBF1F0306031484FF47A7145 -:107E60000068B0FBF1F0B0F1807F0CD220F07F41D0 -:107E70004FF0E020491E41612A4AF0211170C0F8FC -:107E800018A0072101612848FFF74AFA00F0B5FF62 -:107E90006420FFF759FF0DB0BDE8F08F184A10219C -:107EA000143211600821121F11600446151F40F2A0 -:107EB000DB104443286880F010002860286880F0B8 -:107EC00008002860A01EFFF73FFF0120FFF747FFD3 -:107ED0001920FFF739FF0020FFF741FFEAE710B153 -:107EE0001349124808600F49124817390860704753 -:107EF000B803002014080140C4CD0008070040006A -:107F0000000C014000100140000001400C04002062 -:107F1000001BB700777D0008657D000840420F0018 -:107F20000804002023ED00E000580040EFBEADDE65 -:107F3000F04F00200400FA057CB5FA4C0D46FA49D2 -:107F40002160A060A4F53070606100F58070A061D0 -:107F50004FF48070E0602061F4482063F348012111 -:107F600014386063880301F0A2FE02208DF803003C -:107F70000002ADF8000018208DF80200EC4EA807B2 -:107F800003D56946304600F0CDFE4FF48060ADF871 -:107F9000000048208DF80200E80703D0694630460B -:107FA00000F0C0FE0E208DF8040001208DF80500C1 -:107FB0008DF806008DF8070001A801F09EFB204611 -:107FC0007CBD2DE9FC41D74C0D464C34D64921608F -:107FD000A0608020E06040202061A4F58670606190 -:107FE0008030A061D3480121A064480401F068FEFC -:107FF00002268DF803600420ADF8000018208DF8EB -:108000000200CB4FA80703D56946384600F08AFE28 -:108010000820ADF8000048208DF80200E80703D0E2 -:108020006946384600F07EFE26208DF804000120C7 -:108030008DF805008DF806608DF8070001A801F0A5 -:108040005CFB2046BDE8FC812DE9F04389460646ED -:10805000B9490024B7488FB01D4617468E4204D157 -:1080600019461046FFF768FF05E0864204D119461D -:108070001046FFF7A6FF04464FF00008C4F8208022 -:10808000C4F81C80C4F82880C4F82C90C4F824805C -:10809000A6642571A760ADF83080ADF834800B97E9 -:1080A000ADF83280ADF83880ADF83680E80702D000 -:1080B0000420ADF83600A80705D5BDF8360040F01D -:1080C0000800ADF836000BA9304602F0CFF80121C8 -:1080D000304602F023F9684601F060FC301D009044 -:1080E0004FF48050CDE909088020CDF81080CDE90B -:1080F00005084746CDF81C80E80723D0206BD8B18F -:10810000E068CDE902702020089060690190206B42 -:1081100001F0BAFB6946206B01F023FC0121206BC2 -:1081200001F049FC01224021304602F019F9206B90 -:1081300001F056FC206405E0012240F22551304652 -:1081400002F0F6F8A80724D5606BE0B1206903902F -:10815000102008970290606B01F096FB6946606BF7 -:1081600001F0FFFB01220221606B01F02FFC0021D6 -:10817000606B01F033FC606B476001228021304668 -:1081800002F0EEF805E0012240F22771304602F0DD -:10819000CFF80FB02046BDE8F0837FB5044600203D -:1081A000ADF80400ADF808000091ADF80600ADF898 -:1081B0000C00ADF80A0020790D46C00702D004205B -:1081C000ADF80A002079800705D5BDF80A0040F017 -:1081D0000800ADF80A006946A06C02F047F8A560F7 -:1081E0007FBD826A81691144426BD160D0E9092167 -:1081F00000238A4205D9511A426B5160416A81625B -:1082000004E00269511A426B5160836280F8443085 -:10821000406B012101F0CFBB016B11B14968006CCB -:1082200001E01C3003C8814201D0012070470020CA -:108230007047416B11B190F844007047243003C877 -:10824000814201D1012070470020704710B50146DE -:10825000036BC268406943B10B6CD21A805C5B1E31 -:108260000B6401D1CA680A6410BD0B6AC05C5B1C58 -:10827000B3FBF2F402FB14320A6210BD436A826956 -:10828000D154416A0269491CB1FBF2F302FB13119C -:108290004162416B19B10968C90706D1A1E7806C39 -:1082A000012240F2277102F043B8704710B51D4C0F -:1082B0004FF4005001F097FB0021606B01F07BFB55 -:1082C000D4E90901884203D02046BDE8104088E780 -:1082D000012084F8440010BD1249886C02881206FF -:1082E0000ED5D1E909329A420BD08B699A5C828013 -:1082F000886A0A69401CB0FBF2F302FB1300886233 -:108300007047002240F2277102F012B870B5054C98 -:108310004C34A06C0588A9061CD58088E16A69B137 -:10832000884717E030130020DCCD000858000240D9 -:10833000000801400044004000380140E2696169E2 -:108340008854E069E16800F10100B0FBF1F201FB43 -:108350001200E06128060FD5D4E9091088420CD03C -:10836000A169085CA16C8880A06A2169401CB0FBEF -:10837000F1F201FB1200A06270BDA06CBDE870407C -:10838000002240F2277101F0D3BF0000FEB52C4C53 -:108390000125207878B1012823D0022820D164203B -:1083A0008DF8000027488DF8015000264078E0B392 -:1083B0008DF802503CE07A208DF8000022486B4690 -:1083C0000222B0F90000FF21C0F1B40000EBD07030 -:1083D000C0F347008DF801006D20FFF742F92570CA -:1083E000FEBD1A4E79208DF80000B6F900000A256E -:1083F00090FBF5F05A30B4220021FEF74FF98DF8CA -:108400000100B6F90200B42290FBF5F05A300021C9 -:10841000FEF744F98DF802006B460322FF216D2020 -:10842000FFF71FF902202070FEBDFFE78DF8026004 -:108430006B460322FF216D20FFF713F92670F3E747 -:10844000C4030020700A0020B00100203400002086 -:108450001FB5044602AB062243216820FFF73DF911 -:10846000BDF80800214640BA02B2D01702EB907066 -:108470008010ADF80000BDF80A0040BA02B2D01773 -:1084800002EB90708010ADF80200BDF80C0040BA0D -:1084900002B2D01702EB90708010ADF804007C4857 -:1084A00042786846FEF743FA1FBD38B504464FF4DC -:1084B0000050ADF8000002208DF8030004208DF874 -:1084C0000200744874490068884202D169467348C2 -:1084D00004E07349884203D16946724800F022FCE7 -:1084E00080226B216820FFF7F2F80520FFF72CFCB3 -:1084F000002219216820FFF7EAF803226B21682087 -:10850000FFF7E5F8022237216820FFF7E0F8604D19 -:108510001A2168202A78FFF7DAF818221B21682030 -:10852000FFF7D5F810221C216820FFF7D0F8002CA7 -:1085300000D06C7038BD1FB5044602AB06223B214B -:108540006820FFF7CAF8BDF80800214640BAADF828 -:108550000000BDF80A0040BAADF80200BDF80C00FA -:1085600040BAADF804004A4882786846FEF7DFF961 -:108570001FBD47494C4ACB7813B14FF4FF6301E06C -:108580004FF480531380002800D0887070472DE985 -:10859000FE4F8146984692460D462320FFF7D4FBB6 -:1085A0006B46012275216820FFF797F8002804D058 -:1085B0009DF80000682802D00020BDE8FE8F06224A -:1085C00001AB11466820FFF788F89DF809009DF877 -:1085D0000710C007400F01F0010140EA41009DF87B -:1085E00005102B4C01F0010108434FF001064FF03C -:1085F000000704D0012833D002280DD02CE06B46B0 -:1086000001220C216820FFF768F89DF8000010F0A7 -:108610000F0021D0042823D0E7702449C9F80010A6 -:1086200023492448C9F80410286023486860234877 -:10863000E860B8F1000F02D0E17888F800105046E9 -:10864000BAF1620F19D00DDC05281ED00A281AD005 -:10865000BAF1140F0BD114E00520FFF71FFCDCE783 -:10866000E670DAE7BC2806D0BAF5807F01D0032097 -:1086700004E0277003E0267001E002202070012052 -:108680009BE70420FAE70520F8E70620F6E700005C -:10869000C50300200C04002000127A00000C0140E9 -:1086A000001BB70000100140820100207385000804 -:1086B00037850008AB8400085184000819449231C2 -:1086C0001FB5044602AB062201211C20FFF705F866 -:1086D000BDF80800214640BA40F38D02D01702EBE6 -:1086E00090708010ADF80000BDF80A0040BA40F369 -:1086F0008D02D01702EB90708010ADF80200BDF82B -:108700000C0040BA40F38D02D01702EB907080103D -:10871000ADF80400334802786846FEF708F91FBD3B -:1087200038B504462020ADF8000002208DF8030083 -:1087300004208DF8020069462B4800F0F3FA00226D -:108740002A211C20FEF7C3FF02220E211C20FEF767 -:10875000BEFF03220F211C20FEF7B9FF12222B219E -:108760001C20FEF7B4FF02222C211C20FEF7AFFFD5 -:1087700001222D211C20FEF7AAFF00222E211C2001 -:10878000FEF7A5FF05222A211C20FEF7A0FF1749AE -:108790004FF48070002C088001D01248047038BD5E -:1087A00038B5044600208DF80000114811490068D2 -:1087B00088420CD06B4601220D211C20FEF78DFF54 -:1087C00028B19DF800002A2803D01A2801D00020E3 -:1087D00038BD09492160094961600249487001209A -:1087E00038BD0000C90300200008014082010020BC -:1087F0000C040020001BB70021870008C186000878 -:10880000434810B50068434CA188084203D0FFF7E5 -:1088100072FAA0600AE0FFF76EFAA168884205D9F3 -:10882000401A3B2190FBF1F061690860E068BDE807 -:10883000104001F02BB9E3E7E2E7FEB50125354C26 -:10884000022110B1012810D109E04FF4807060803E -:108850004000A080E06009202070172004E06580BF -:10886000A180E1602570072060706088ADF800008D -:108870001026274F8DF802608DF80310083F6946D7 -:10888000384600F04FFAA088ADF8000004208DF8BB -:1088900002006946384600F045FA2178012001F0CF -:1088A00069FDE06801F0F2F8E068019000208DF8C1 -:1088B00008008DF809608DF80A5001A801F0A2F8AF -:1088C00094F9010000F01F018D4040094FF0E021B4 -:1088D00001EB8000C0F80051FFF727FA3C38206117 -:1088E000FEBD70B50546FFF720FA0A4C21693C3100 -:1088F00088420CD3C4E90405054960880831086042 -:108900000B20FFF715FA024960880C31086070BD32 -:10891000080C0140CC0300201FB5044602AB062220 -:10892000A8216820FEF7D9FEBDF80800214640BA0C -:1089300002B2D01702EB90708010ADF80000BDF8C5 -:108940000A0040BA02B2D01702EB90708010ADF866 -:108950000200BDF80C0040BA02B2D01702EB9070D2 -:108960008010ADF80400264842786846FDF7DFFF26 -:108970001FBD70B504466420FFF7E6F9F0222321FD -:108980006820FEF7A4FE10B90320FFF787FA052040 -:10899000FFF7DAF91A4D2021287840F00F026820FD -:1089A000FEF795FE002C00D06C7070BD38B5044603 -:1089B0000D461920FFF7C8F96B4601220F216820E8 -:1089C000FEF78BFE9DF80000D32801D0002038BDB3 -:1089D0000C4820600C4860600C48E0600848362D68 -:1089E00005D04E2D07D05D2D07D0002100E040219D -:1089F0000170012038BD8021FAE7C021F8E70000AE -:108A0000E40300207389000819890008DDE9A73113 -:108A10002DE9F04FB74C83468E46608926890102C6 -:108A2000B5484FF0000A4068421AA6FB027CA088B5 -:108A30004FEAE2754FEA10414FEA00430AFB02C0D9 -:108A400006FB05064FEAD71040EA466013EB000923 -:108A500041EBE611E6886388A6FB02C84FEA534063 -:108A60004FEAC3370AFB028306FB05364FEA1C2395 -:108A700043EA0663FB1840EB2620A689A6FB027C8E -:108A80000AFB02C206FB05244FEAD75242EA4422FF -:108A90004FF4FA654FEAE454521944F10004A24637 -:108AA000551B74F1000448DA944D5519A5FB056770 -:108AB0004AF1FF3404FB057705FB047C0525A6FB82 -:108AC00005480CFB0585002706FB07556F104FEA8C -:108AD000340CB9EB0C0961EB0701A40844EA857476 -:108AE0001B1B60EBA500864D551B7AF1FF3424DA81 -:108AF00040F2DC555619A6FB06474AF1000505FB76 -:108B0000067706FB05750726A4FB06C805FB068647 -:108B1000002704FB0767B9EB0C0961EB07010B2782 -:108B2000A4FB07C805FB0785002604FB0654641058 -:108B30004FEA3C055B1B60EB04006F4CA56800240A -:108B4000A5FB036704FB037305FB0030740D44EAC7 -:108B5000C0244015B4EB090360EB0100410441EA75 -:108B6000D330BBF1000F01D0CBF80000BEF1000FF5 -:108B700001D0CEF80020BDE8F08F10B500F072F8FB -:108B80005D49886010BD5C48012200784030C1B268 -:108B90007720FEF79CBD10B500F064F85649486098 -:108BA00010BD5548012200785030C1B27720FEF741 -:108BB0008EBD2DE9FE430546524853490068884260 -:108BC0000FD04FF40054ADF8004002208DF80300A0 -:108BD00010204E4E8DF802006946304600F0A2F893 -:108BE00074610A20FFF7B0F801AB0122A0217720C1 -:108BF000FEF773FD002823D001221E217720FEF707 -:108C000066FD4FF42F60FFF793F80024DFF8E4804F -:108C10002646A02707EB4400C1B202AB0222772010 -:108C20000296FEF75AFDBDF8080040BA28F8140075 -:108C3000641C082CEEDB2F4800F026F810B1002051 -:108C4000BDE8FE8342F2107028806880304868607A -:108C50003048A8603048E860304828613048686192 -:108C60000120EDE708B56B46032200217720FEF7CF -:108C700034FD9DF800009DF80110000440EA012039 -:108C80009DF80210084308BDF0B5C289002102F426 -:108C90007F4502F00F040123C5810A4630F81260B7 -:108CA00006B10023521C082AF8DB4FF0FF36F3B957 -:108CB0000022D30722F0010302D0C35C594002E036 -:108CC000C35A81EA132108230F0401D581F4C0514E -:108CD00049005B1E002BF7DC521C102AE9DB254300 -:108CE000C581C1F30330844201D10020F0BD30467C -:108CF000F0BD0000C8130020E803002030F8FFFF9B -:108D000024FAFFFF0C040020001BB70000100140F4 -:108D1000A38B0008978B0008878B00087B8B0008CB -:108D2000118A0008F0B500234FF0010C0A880CFAF4 -:108D300003F52A4228D04FEAD30200EB82064FEA1D -:108D4000437491F802E04FEAD46734680EF00F02E2 -:108D50005FEACE6E03D591F803E04EEA02024FF0CF -:108D60000F0E0EFA07FE24EA0E04BA4022433260C8 -:108D70008A78282A02D0482A03D005E0C268AA438C -:108D800001E0C2682A43C2605B1C102BCED3F0BD49 -:108D90004FF4805108B14E4801E04D48001F01607A -:108DA00070472DE9F04104464A4817460D460088B1 -:108DB000484E0C3E1CE015B115F8010B00E0FF20F9 -:108DC00080460221304601F0EDFB0028F9D04146F3 -:108DD000304601F0E3FB0121304601F0E3FB0028BF -:108DE000F9D0304601F0DCFBC0B20CB104F8010B45 -:108DF0007F1EE0D20120BDE8F081F0B501218C0397 -:108E000089B0204600F05CFF0121204600F06AFF97 -:108E100018208DF816004FF42040ADF814002C4EA9 -:108E200003208DF81700143E05A93046FFF77AFF9E -:108E3000ADF8144004208DF8160005A93046FFF760 -:108E400071FFA010ADF8140010258DF8165005A97B -:108E50003046FFF767FF1F4E0C3E304601F054FBD3 -:108E60004FF48270ADF8020068010024ADF80A00EA -:108E70000720ADF81000ADF804400220ADF80E4018 -:108E8000ADF806000127ADF80040ADF80870ADF868 -:108E90000C506946304601F05BFB0121304601F081 -:108EA00073FB0DA0006806900120FFF771FF0422FC -:108EB00006A907A8FFF775FF0020FFF769FF9DF8D7 -:108EC0001D00EF2802D0204609B0F0BD3846FBE770 -:108ED000140C01400C3800409F0000002DE9F041C7 -:108EE00080461D4616460C46084600F0E7F8074641 -:108EF000404600F0D8F807EB8000C0B2102805D239 -:108F0000734901EB0010856004710673BDE8F081C0 -:108F100051B104290BD008290CD00C290DD1012204 -:108F20005FF0100101F05DB901220221FAE7012290 -:108F30000421F7E701220821F4E7704770B50D46D8 -:108F40000446017B134600682A46FFF7C7FF217BD2 -:108F50002068BDE87040DBE708B58DF80000002010 -:108F60008DF8010001208DF802008DF8030068469D -:108F700000F0C3FB08BDFEB5064614460D46684624 -:108F800001F0FFF853486D1E44435348ADF80450B8 -:108F900069460068B0FBF4F0401EADF80000002008 -:108FA000ADF80600ADF80200304600F0B5FEFEBD9B -:108FB00010B504460068FFF7DEFF0121206801F0CC -:108FC000FBF8607BBDE81040C6E770B50546084673 -:108FD00000F074F80446284600F065F804EB8000C1 -:108FE0003B49C0B201EB001070BD70B505460221CF -:108FF00001F028F9012825D00421284601F022F9A2 -:1090000001282CD00821284601F01CF9012833D072 -:109010001021284601F016F901283AD110212846DE -:1090200001F01CF90C212846FFF7CFFF0446284623 -:1090300001F005F9A2680146002A2AD0207BBDE88C -:10904000704010470221284601F008F90021284607 -:10905000FFF7BBFF0446284601F0EBF8EAE70421DE -:10906000284601F0FBF804212846FFF7AEFF04462E -:10907000284601F0E0F8DDE70821284601F0EEF887 -:1090800008212846FFF7A1FF0446284601F0D5F83D -:10909000D0E770BD1148A8E74FF08040A5E7104821 -:1090A000A3E71048A1E7014600200F4A01E0401C59 -:1090B000C0B252F820308B42F9D1704701460020EF -:1090C0000A4A01E0401CC0B2135C8B42FAD17047DF -:1090D000D813002040420F0008040020002C01405B -:1090E0000004004000080040F4030020D0CE000837 -:1090F000016B4A68926889680A4290F8441204D069 -:109100000020002900D10120704701200029FBD157 -:1091100000207047D0F8343101299A685B6801D08B -:1091200021B107E090F8440230B103E090F8440226 -:10913000012801D05A6170471A617047018940685F -:1091400089B2482200F052B970B5044601EB4100E3 -:10915000AC491646B1FBF0F081B21D460322204611 -:10916000FFF726FF2A4631462046BDE87040FFF74C -:10917000E5BE0189406889B2102200F037B900B518 -:109180000346032083F83C021846FFF7B1FF30B1D5 -:10919000B3F8400293F839120843A3F8400293F859 -:1091A0003902400083F8390293F83E02401E10F065 -:1091B000FF0083F83E0205D1012083F83802022027 -:1091C00083F83C0200BDC268016A521E914201D37D -:1091D000002100E0491C0162704710B501240346DC -:1091E00080F83C42FFF784FF01280FD1002083F86C -:1091F000380283F83A4293F84002A3F840021A6A10 -:1092000059698854BDE810401846DCE710BD00B528 -:109210000346FFF76DFF012101280BD003F23A232B -:1092200000201870D880042098700820187103F866 -:10923000011C00BD83F83C1200BD90F83C12491E91 -:1092400011F0FF0180F83C1208D190F83A1201B1F8 -:10925000DDE790F8381201B1BFE790E77047D0E939 -:109260000910814201D1012070470020704730B5BC -:10927000044690F83B020025F8B194F83D02401EE8 -:1092800010F0FF0084F83D0216D1B4F8420200F05D -:1092900001014008A4F842022046FFF73BFF0320EB -:1092A00084F83D0294F83F02401E10F0FF0084F85D -:1092B0003F0201D184F83B5230BD2046FFF7CFFF7B -:1092C0000028F9D1A16AA269481CA062515C2269F8 -:1092D000904200D3A5624FF4007004F23B2440EAB0 -:1092E0004100A4F807000A2020710120A07020701E -:1092F00030BD00EBC00101EB801010B5424901EB1D -:10930000C0042046FFF7B3FF2046BDE8104094E7B5 -:1093100070B53D4C06463D48206003202071A66094 -:1093200084F844123A4820631030C4F83401002510 -:1093300004F13401256261614FF48070E0602061C6 -:1093400004F59C71C4E90615A562656284F83B5278 -:10935000012084F83A0284F8385284F83C02206BE9 -:10936000FFF7ECFED4F83401FFF703FF012120469C -:10937000FFF7D0FE3220FEF7E7FCAFF289032A4662 -:109380003146206BBDE87040DEE6D0E9072191420E -:1093900002D14FF00000704702D9A1EB020003E0B8 -:1093A000C0680844A0EB0200C0B2704700B5034695 -:1093B000FFF7EBFF00280BD05969D869095CDA6820 -:1093C000521E904201D2401C00E00020D8610846A5 -:1093D00000BD436A8269D154416A0269491CB1FBEC -:1093E000F2F302FB131141627047704708B5ADF804 -:1093F00000108DF8022002218DF803106946FFF756 -:1094000091FC08BDC0C62D00D8140020D4CE0008A1 -:1094100030CE00081FB5044602AB062202211820F8 -:10942000FEF75BF99DF808009DF80910800800EB35 -:109430000120ADF800009DF80A009DF80B1080088F -:1094400000EB0120ADF802009DF80C009DF80D1016 -:10945000800800EB0120ADF804001A48214602788C -:109460006846FDF764FA1FBD10B5044608220F21B7 -:109470001820FEF72CF90E2210211820FEF727F9EC -:1094800011494FF48050002C088001D00D48047021 -:1094900010BD38B5044600208DF8000001466B462B -:1094A00001221820FEF719F918B19DF80000FB28D9 -:1094B00001D0002038BD05482060054860600120CB -:1094C00038BD0000040400208201002069940008D7 -:1094D0001594000802681268104770B50C460546DE -:1094E00003E02A6828461268904714F8011B0029F7 -:1094F000F7D170BD01684968084701688968084765 -:109500000268D26810470168096908476E48016817 -:1095100041F00101016041686C4A114041600168FD -:109520006B4A11400160016821F4802101604168AB -:1095300021F4FE0141604FF41F0181606549C003C1 -:1095400008607047604A10B55068634B10F00C011A -:10955000624803D0042903D0082903D0036016E031 -:10956000416813E05168536801F470114FF0020430 -:1095700013F4803F04EB914106D053689B0343688A -:1095800000D55B084B43E9E7554B594301605168EF -:10959000524AC1F303110832515C0268CA400260AA -:1095A00010BD3EB4002100914FF4E01301914648F4 -:1095B000CDE901314B4A046844F480340460846985 -:1095C00044F0100484614FF4A064056805F400358C -:1095D0000195009D6D1C0095019D15B9009DA5424A -:1095E000F3D10568AD0301D5022114E0056845F00B -:1095F000010505600091016801F0020101910099E7 -:10960000491C0091019911B90099A142F3D1016857 -:10961000890739D50121029133490C6844F01004BF -:109620000C600C6824F003040C600C6844F0020425 -:109630000C604168416041684160416841F480616B -:109640004160116821F070411160244C2249616031 -:10965000416821F47C114160116841F000411160C2 -:109660002049091FCA6822F40042CA6089680904B7 -:1096700003D51E494FF480136160029901930129BB -:1096800008D002290AD100E0FEE7416843F48032A5 -:10969000114302E0416841F460114160016841F00A -:1096A0008071016001688901FCD5416821F00301E6 -:1096B0004160416841F0020141604168C1F38101AC -:1096C0000229FAD13EBC3DE7001002400000FFF83D -:1096D000FFFFF6FE08ED00E000127A00080400200B -:1096E00000093D000410014000200240001BB700AB -:1096F00018490843184908607047F0B50F21C4782D -:10970000027801234FF0E026DCB1134C2468457841 -:1097100004F4E064C4F5E064240AC4F10407E14001 -:109720008478BD400C402C4321010C4C115500782D -:1097300000F01F018B40400906EB8000C0F80031AB -:10974000F0BD02F01F008340500906EB8000C0F816 -:109750008031F0BD0000FA050CED00E000E400E00F -:1097600010B54268464B0C791A400B6842EA042255 -:10977000134343608368434A1340D1E902422243C2 -:109780004C7943EA44031A438260C26A097C22F49A -:109790007002491EC9B242EA0151C16210BD0029DE -:1097A000816802D041F0010101E021F001018160F6 -:1097B00070470029816802D041F4807101E021F4F2 -:1097C000807181607047816841F008018160704755 -:1097D000014600208968090700D50120704781688B -:1097E00041F0040181607047014600208968490703 -:1097F00000D5012070470029816802D041F4A00102 -:1098000001E021F4A0018160704770B507240929A7 -:109810000AD9C568A1F10A0606EB4606B440A5437D -:10982000B3401D43C56007E0056901EB4106B44044 -:10983000A543B3401D4305611F23072A09D2446B8A -:10984000521E02EB820293409C4391400C434463BE -:1098500070BD0D2A09D2046BD21F02EB8202934025 -:109860009C4391400C43046370BDC46A0D3A02EB03 -:10987000820293409C4391400C43C46270BD00003F -:10988000FFFEF0FFFDF7F1FF01684FF6FE72114099 -:1098900001600021016041608160C1605749574A01 -:1098A0000839904203D1486840F00F0006E0534A5F -:1098B0001432904204D1486840F0F000486070478C -:1098C0004E4A2832904203D1486840F47060F5E770 -:1098D0004A4A3C32904203D1486840F47040EDE778 -:1098E000464A5032904203D1486840F47020E5E780 -:1098F000424A6432904203D1486840F47000DDE788 -:109900003E4A7832904203D1486840F07060D5E713 -:109910003B4A111F904203D1086840F00F0006E057 -:10992000374A1432904204D1086840F0F0000860D1 -:109930007047334A2832904203D1086840F470607F -:10994000F5E72F4A3C32904203D1086840F470405A -:10995000EDE72B4A50329042EAD1086840F470207B -:10996000E5E730B5036847F6F07293430C6A8A68FE -:109970002243D1E904452C4322438C692243CC691C -:1099800022434C6A22438C6A22431A430260CA680B -:1099900042600A6882604968C16030BD0021016090 -:1099A00041608160C160016141618161C1610162A9 -:1099B0004162816270470029016802D041F00101D3 -:1099C00002E04FF6FE72114001607047002A026803 -:1099D00001D00A4300E08A4302607047416070474B -:1099E000406880B27047C10003D50549091F08606F -:1099F000704702490839486070470000080002407B -:109A00000804024030B523498379026853B30B68D8 -:109A100093430B600A1D13680468A3431360027923 -:109A20000A4413680468234313601A4A083213680F -:109A30000468A3431360131D1C680568AC431C60D5 -:109A40004479102C05D021440A68006802430A605A -:109A500030BD116804682143116019680068014332 -:109A6000196030BD0079084401689143016030BD40 -:109A7000084A014600201268064B0A4014331B684E -:109A80000B4202D0002A00D0012070470149143156 -:109A900008607047000401405A4910B588424FF0F1 -:109AA000010101D14C0501E04FF48004204600F093 -:109AB00019F92046BDE81040002100F013B970B537 -:109AC0000446808886B00D4620F03F06684600F0C8 -:109AD0009FF84D490298B0FBF1F189B20E43A68080 -:109AE000228822F001022280484B2A689A421CD820 -:109AF0005200B0FBF2F080B2042800D20420491CCE -:109B00002184A083208840F00100208021884FF626 -:109B1000F5300140A8886A89104308432080A8894D -:109B200029890843208106B070BDEB88A3F53F4624 -:109B3000FF3E05D102EB4202B0FBF2F080B208E03A -:109B400002EBC20303EB0212B0FBF2F080B240F46E -:109B50008040020501D140F001004FF4967251435C -:109B60004FF47A72B1FBF2F140F40040C7E741F2E2 -:109B700088310160002181804BF6FF72C280018133 -:109B800041814FF48041818170470029018802D0D2 -:109B900041F0010101E021F001010180704700293D -:109BA000018802D041F4807101E021F480710180CC -:109BB00070470029018802D041F4007101E021F4CE -:109BC0000071018070470029018802D041F4806152 -:109BD00001E021F4806101807047002A828801D071 -:109BE0000A4300E08A438280704701827047008AFE -:109BF000C0B2704712B141F0010101E001F0FE0175 -:109C0000018270470054004040420F00A0860100CE -:109C100030B53C494A683C4B12F00C0405D03B4A35 -:109C2000042C126803D0082C24D0036000E00260EA -:109C30004A680F2303EA1212354B9C5C0268E2402B -:109C400042604C68072505EA14241C5D22FA04F4DE -:109C500084604C6805EAD4241B5DDA40C260496820 -:109C6000032303EA91312A4B1B1F595CB2FBF1F12C -:109C7000016130BD4B684C6803F470134FF002056E -:109C800014F4803F05EB934305D04C68A40300D542 -:109C900052085A43CBE71F4A5343C6E7194A0029E3 -:109CA000516901D0014300E0814351617047154A79 -:109CB0000029916901D0014300E08143916170471F -:109CC000104A0029D16901D0014300E08143D161EC -:109CD00070470C4A0029D16801D0014300E081435C -:109CE000D1607047074A0029116901D0014300E0A3 -:109CF0008143116170470348416A41F080714162BC -:109D0000704700000010024000127A000C0400208E -:109D10002404002000093D0030B50288FD4BFE4CB4 -:109D200098420DD0A0420BD0B0F1804F08D0FB4D2F -:109D3000A84205D0FA4DA84202D0FA4DA84203D15C -:109D400022F070054A882A43F74DA84206D0F74D05 -:109D5000A84203D022F44075CA882A4302808A8828 -:109D600082850A88028598420AD0A04208D0F04A2B -:109D7000904205D0EF4A904202D0EF4A904201D182 -:109D8000097A01860121818230BD30B5028C22F032 -:109D900001020284028C8388048B22F0020224F0E8 -:109DA00073050C882C430D8915434A882A43D94DE5 -:109DB000A8420BD0D84DA84208D0DD4DA84205D00E -:109DC000DC4DA84202D0DC4DA8420DD122F008059E -:109DD0004A8923F440732A4322F004058A882A43DF -:109DE0008D891D43CB892B4383800483C988818659 -:109DF000028430BD70B5028C22F010020284028C05 -:109E00008488038B0D8823F4E6464FF6FF7303EA3C -:109E1000052535430E8922F0200203EA0616164373 -:109E20004A8803EA02123243BA4EB04202D0BA4E16 -:109E3000B04215D122F080064A8924F4406403EA36 -:109E40000212324322F040068A8803EA02123243A9 -:109E50008E8903EA86062643CC8903EA84043443C8 -:109E600084800583C9880187028470BD70B5028C27 -:109E700022F480720284028C8488838B0D8823F004 -:109E800073031D4322F400730E894FF6FF7202EA3A -:109E900006261E434B8802EA032333439D4EB042FD -:109EA00002D09D4EB04215D123F400664B8924F4B4 -:109EB000405402EA0323334323F480668B8802EA8A -:109EC000032333438E8902EA06162643CC8902EA2D -:109ED0000414344384808583C9888187038470BDDA -:109EE00070B5028C22F480520284048C8288838BA9 -:109EF0000D8823F4E6464FF6FF7303EA0525354344 -:109F000024F400560C8903EA043434434E8803EAEF -:109F1000063626437F4CA04202D07F4CA04205D19A -:109F200022F480448A8903EA821222438280858354 -:109F3000C988A0F84010068470BD828B22F440626C -:109F40008283828B4FF6FF7303EA01210A438283E7 -:109F50007047828B22F00C028283828B0A438283B9 -:109F60007047028B22F440620283028B4FF6FF732C -:109F700003EA01210A4302837047F0B5048C24F000 -:109F800010040484078B048C4FF6FF7527F4734785 -:109F900005EA03333B4305EA02221A435D4B05EA17 -:109FA000011698420ED05C4B98420BD0B0F1804F16 -:109FB00008D05A4B984205D0594B984202D0594B81 -:109FC000984205D124F02001314341F0100104E012 -:109FD00024F0A0030B4343F0100102830184F0BD81 -:109FE000028B22F00C020283028B0A430283704729 -:109FF00070B5048C24F001040484058B048C4FF6A6 -:10A00000FF7606EA0313134325F0F305414A2B4379 -:10A0100090420ED0404A90420BD0B0F1804F08D011 -:10A020003E4A904205D03E4A904202D03D4A90427C -:10A0300002D124F0020201E024F00A020A4342F0B5 -:10A0400001010383018470BD2DE9F05F0D460446D4 -:10A050000888304FDFF8C0C0DFF8C0804988AA8880 -:10A060002B894FF0804960B3042832D04FF6FF7E31 -:10A07000082836D0208C9B4620F480502084A38B67 -:10A08000268C704600EA022223F473431A4300EA46 -:10A090000B3010430EEA013EBC420BD0644509D0A0 -:10A0A0004C4507D0444505D01D4A944202D01D4B73 -:10A0B0009C425AD126F4005141EA0E0141F48051EC -:10A0C00058E02046FFF794FFE9882046BDE8F05F9E -:10A0D00086E72046FFF751FFE9882046BDE8F05F9C -:10A0E0003FE7208C20F480702084B4F81CA0208CE2 -:10A0F0000EEA031313432AF0F30A0EEA012B43EA94 -:10A100000A03BC4220D064451ED04C451CD04445B7 -:10A110001AD013E0002C014000340140000400403C -:10A1200000080040000C00400010004000140040F7 -:10A13000004001400044014000480140494A944227 -:10A1400002D0494A944204D120F4007040EA0B0046 -:10A1500002E020F42060084340F48070A383208450 -:10A16000E9882046BDE8F05FF3E626F402420A43A0 -:10A1700042F48051A08320462184E988BDE8F05F45 -:10A18000DBE64FF6FF71818000210180C1804180B4 -:10A19000017270470021018041808180C18001816E -:10A1A00041818181C181704700210180418001226C -:10A1B0008280C180018170470029018802D041F06E -:10A1C000010101E021F0010101807047002930F810 -:10A1D000441F02D041F4004101E0C1F30E010180AF -:10A1E0007047002A828901D00A4300E08A438281B5 -:10A1F0007047028B22F008020A4302837047028BE9 -:10A200004FF6FF7322F4006203EA01211143018338 -:10A210007047828B22F008020A4382837047828B48 -:10A220004FF6FF7322F4006203EA01211143818398 -:10A230007047808E7047008F7047808F7047B0F8EE -:10A240004000704702460020138A92890B4202EABE -:10A25000010202D0002A00D001207047C9430182C8 -:10A260007047000000080040000C004030B5044674 -:10A27000008A85B00D464CF6FF710840E98801431D -:10A280002182A1894EF6F3100140A8882A89104343 -:10A290006A890A431043A081A08A4FF6FF41084013 -:10A2A000A9890143A1826846FFF7B2FC3048844285 -:10A2B00001D1039800E00298A1890904002900EB6C -:10A2C000C00101EB0010296802DA4FEA410101E008 -:10A2D0004FEA8101B0FBF1F06422B0FBF2F14FEAEA -:10A2E00001114FEA11136FF018056B4300EB830067 -:10A2F000A3891D044FF0320306D503EBC000B0FB69 -:10A30000F2F000F0070005E003EB0010B0FBF2F004 -:10A3100000F00F000843208105B030BD002981897D -:10A3200002D041F4005101E021F4005181817047D5 -:10A3300010B5C1F3421301F01F040121A140012B0C -:10A3400007D0022B07D01430002A026805D00A4338 -:10A3500004E00C30F8E71030F6E78A43026010BDE5 -:10A36000002A828A01D00A4300E08A438282704731 -:10A370000038014010B58A0721F003040649130F85 -:10A3800021440F228C689A4094438C608A689840DC -:10A3900002438A6010BD000000000140394838497E -:10A3A00041603949416070473648016941F0800198 -:10A3B0000161704733490420CA68D20701D00120E7 -:10A3C0007047CA68520701D502207047C968C9069C -:10A3D000FBD50320704700B50346FFF7EBFF02E013 -:10A3E000FFF7E8FF5B1E012803D0002B00D10520FA -:10A3F00000BD002BF4D1FAE770B505464FF43026C6 -:10A400003046FFF7E8FF042811D11E4C206940F0C8 -:10A41000020020616561206940F040002061304603 -:10A42000FFF7D9FF216941F6FD721140216170BD2E -:10A43000F8B5064600204FF4005C00900D466046DB -:10A44000FFF7C9FF042816D10E4C206940F0010027 -:10A45000206135806046FFF7BEFF41F6FE77042895 -:10A4600006D1B61C280C009630806046FFF7B3FF7B -:10A47000216939402161F8BD0249C8607047000078 -:10A480002301674500200240AB89EFCD14481549F0 -:10A49000026800608A4203D013488047134800478F -:10A4A000134E4FF0090030601248016821F07061CE -:10A4B000016041020160104C182020600F491048D3 -:10A4C00008601048D0F800D040680047FEE7FEE77B -:10A4D000FEE7FEE7FEE7FEE7FEE7FEE7FEE7FEE754 -:10A4E000F04F0020EFBEADDE0D950008ED00000836 -:10A4F0001810024004000140140C0140000C0140FF -:10A500004434434400F0FF1F2A4910B588420AD161 -:10A51000841401212046FFF7DCFB2046BDE81040F3 -:10A520000021FFF7D6BB2449884202D1012104143F -:10A5300004E0224988420AD10121C4132046FFF7D2 -:10A54000D1FB2046BDE810400021FFF7CBBB10BD7A -:10A5500030B502884C8802F441530A88CD882243E2 -:10A560008C882C4322430C8922434C8922438C89BA -:10A570002243CC8922431A430280828B22F4006258 -:10A580008283098A018230BD0029018802D041F00E -:10A59000400101E021F04001018070478181704756 -:10A5A000808970470246002012890A4200D00120AB -:10A5B000704700000030014000380040003C00407F -:10A5C00000487047ACD00008A0F16101192900D8FB -:10A5D000203870472DE9F05F994615460F468346AF -:10A5E0004FF0FF36DDF828A011E0A819441009FB50 -:10A5F000047080460146584652469047002802D0D3 -:10A6000004DA254603E04046BDE8F09F2646A5EB68 -:10A6100006000128E9DC0020F6E740EA01039B0779 -:10A6200003D009E008C9121F08C0042AFAD203E0C7 -:10A6300011F8013B00F8013B521EF9D27047D2B22B -:10A6400001E000F8012B491EFBD270470022F6E71B -:10A6500010B513460A4604461946FFF7F0FF204698 -:10A6600010BD421E12F8013F002BFBD111F8013B37 -:10A6700002F8013B002BF9D1704730B505462A4658 -:10A680000B4612F8010B13F8014B08B1A042F8D0A9 -:10A690001CB1002802D06D1CF1E7284630BD10B572 -:10A6A000044604E00B7800F8013B03B1491C521E3C -:10A6B000F8D2204610BDCAB2401E10F8011F8A42CF -:10A6C00002D00029F9D100207047421C10F8011B6C -:10A6D0000029FBD1801A70472DE9F0410546002082 -:10A6E00090460E46044600E0641C44450BD2285DAB -:10A6F00000F058F90746305D00F054F9381A02D1DD -:10A70000295D0029F0D1BDE8F08170B5064600F062 -:10A7100059FC046805460A220021304600F048F939 -:10A720002C6070BDF0B480EA0102D40F4200B2EB9D -:10A73000410F02D20246084611464A0042D0C30DDC -:10A74000DDB2C1F3C752AD1A202D35DAC1F31601BF -:10A7500041F4000204B15242C5F1200602FA06F1AA -:10A760002A411044B3EBD05F23D0C4B1012DA0EB3C -:10A77000C35009DCF0BC4FF0004202EAC35200F5BE -:10A780000000DBB200F055B9400000F1807000EB32 -:10A79000C350A0F1807040EAD170490009E0490837 -:10A7A00041EAC071A0EBC35000F50000400800EB87 -:10A7B000C350F0BC00F034B96142012202EB410108 -:10A7C000001BF6E7F0BC704781F00041AAE780F07B -:10A7D0000040A7E780EA010210B502F00043400004 -:10A7E00026D04A0023D04FEA106101EB1261C0F37A -:10A7F0005600C2F3560240F4000042F40002A0FBEF -:10A800000220A1F17F014FEA0040140401D000F1C1 -:10A81000010050EA124001D44000491EC2B20C06A9 -:10A8200004EBD010401C4008802A02D003E0002036 -:10A8300010BD20F00100002900DA0020184310BDEF -:10A8400030B480EA010202F0004530F0004221F00D -:10A85000004015D0A0B1C0F3C753C2F3C754C2F330 -:10A860001601C0F31600E41A41F4000140F400029E -:10A870007D34914201D3641C00E04900002C02DACF -:10A8800030BC002070474FF400000023914201D3F8 -:10A89000891A034340084FEA4101F7D151B191426F -:10A8A00002D14FF0004105E002D24FF0010101E07A -:10A8B0006FF0010103EBC450284430BC00F0B0B885 -:10A8C000420005D0C0F3C7525242914201DC002041 -:10A8D000704700EBC1507047C10F80EAE070084438 -:10A8E000CA079623002100F0A4B89623002211463F -:10A8F00000F09FB800F0004220F00040C10DC0F30E -:10A90000160040F400007F2901DA002070479629E4 -:10A9100003DCC1F19601C84001E096398840002A65 -:10A92000F4D04042704720F00040C10DC0F3160043 -:10A9300040F400007F2901DA00207047962903DCEB -:10A94000C1F19601C84070479639884070470000B1 -:10A95000002801DBC0F10040002901DBC1F100410A -:10A9600081427047002801DBC0F10040002901DB73 -:10A97000C1F100418842704730B50B4601460020C6 -:10A980002022012409E021FA02F59D4205D303FAB1 -:10A9900002F5491B04FA02F52844151EA2F1010232 -:10A9A000F1DC30BDA0F14101192900D820307047F9 -:10A9B0002DE9F04791460F4680460446002614F8DC -:10A9C000015B2DB1FFF7FCFD0068405DC007F6D1CB -:10A9D0002B2D02D02D2D18D0641E4A463946204614 -:10A9E00000F0E1F927B13968A14201D1C7F8008030 -:10A9F00071054FF002040BD54042002803DD00F042 -:10AA0000E1FA0460A007BDE8F08746F48066E4E759 -:10AA10000028F8DA00F0D6FA04606FF00040F2E7A0 -:10AA20000029A8BF7047401C490008BF20F0010062 -:10AA3000704710B4B0FA80FC00FA0CF050EA010440 -:10AA400004BF10BC704749B1CCF1200421FA04F4D2 -:10AA500011FA0CF118BF012121430843A3EB0C01AB -:10AA6000CB1D0106000A002BBEBF002010BC7047A2 -:10AA700000EBC35010440029A4BF10BC7047401C19 -:10AA8000490008BF20F0010010BC7047F0B4002856 -:10AA900002DCF0BC00207047C0F3C751C0F31600C1 -:10AAA00040F40000CA0701D14000491E3F2202EBDA -:10AAB0006105002211464FF4000626FA01F3134403 -:10AAC000D418844201D8001B1A464000491C17299B -:10AAD000F3DD5100814202D24FF0FF3100E000214E -:10AAE00002EBC550F0BCFFF79BBF10B541000CD086 -:10AAF000C0F3C751962908DC7E2909DC06DB410238 -:10AB000004D000F0004040F07E5010BD002010BD89 -:10AB1000C1F19604C4F1200100FA01F1E040FFF711 -:10AB20007FFFA04010BD2DE9FE4F804681EA030063 -:10AB3000C00F0C46009021F0004123F00045B8EB17 -:10AB40000200A94105D24046214690461C460B46CC -:10AB5000024623F00040104304D14046214603B092 -:10AB6000BDE8F08F270DC7F30A00C3F30A51029026 -:10AB7000401A0190402866DAC3F3130040F4801BAA -:10AB80000098924620B10023D2EB030A63EB0B0B33 -:10AB900001985946C0F14002504600F0D3F80646ED -:10ABA0000D4650465946019A00F0EBF810EB0800AC -:10ABB0006141002487EA115284EAE7731A433BD0CB -:10ABC000009A3AB3019A012A4FEA075210DC001B9F -:10ABD00061EB02014FF0004202EA0752CDE9004268 -:10ABE000001C41F5801132462B4600F038F9B6E7DB -:10ABF000001B61EB0201001C41F5801300185B4152 -:10AC00002018A2F5001747EB030140EAD570B619EA -:10AC10006D4111E06D084FEA360645EAC0754FEA0E -:10AC20000752001B61EB0201001C41F5801149082D -:10AC30004FEA30000019514132462B4603B0BDE8BF -:10AC4000F04F00F0FFB80098012240000023D0EB45 -:10AC5000020263EBE073009821464FEAE074B8EB20 -:10AC6000000061EB0401E9E783F000435BE781F05A -:10AC7000004158E710B500F0004420F00040C20D3C -:10AC8000C0F3160040F400007F2A07DA7D2A00DABC -:10AC90007D22763A00FA02F1002008E0962A09DCCB -:10ACA000A2F1760100FA01F1C2F19602D040FFF75D -:10ACB000B7FE01E0963A9040002C00D0404210BD13 -:10ACC00000F0004230F000400AD0C10D01F5607183 -:10ACD000C0F3160042EA0151C20840071143704711 -:10ACE00000200146704701F0004330B421F00041DC -:10ACF00050EA010206D00A0DA2F56072C1F31301F9 -:10AD0000002A02DC30BC00207047440F44EAC10432 -:10AD1000C100E01830BC00EBC250FFF781BE00005C -:10AD2000064C074D06E0E06840F0010394E8070098 -:10AD300098471034AC42F6D3F5F7DCF9BCD90008DB -:10AD4000DCD90008202A04DB203A00FA02F10020B6 -:10AD500070479140C2F1200320FA03F31943904059 -:10AD60007047202A04DB203A21FA02F000217047C4 -:10AD700021FA02F3D040C2F1200291400843194663 -:10AD80007047202A06DBCB17203A41FA02F043EA4B -:10AD9000E07306E041FA02F3D040C2F12002914094 -:10ADA0000843194670472DE9F05F82460078002776 -:10ADB00015468B460AF10104B946302801D09DB1F1 -:10ADC00013E014F8010B0127782803D0582801D08C -:10ADD00045B10AE00DB1102D07D10027102514F858 -:10ADE000010B02E0082500E00A250026B0460EE02F -:10ADF00005FB080005FB06F1012701EB10461FFAD1 -:10AE000080F8B6F5803F00D3B94614F8010B294607 -:10AE100000F077F80028EBDABBF1000F05D00FB196 -:10AE2000641E00E05446CBF80040B9F1000F06D094 -:10AE300000F0C8F802210160C81EBDE8F09F48EA92 -:10AE40000640FAE710B5002B08DA401C41F100017A -:10AE500092185B411A4301D120F0010010BD2DE989 -:10AE6000F04D92469B4611B1B1FA81F202E0B0FA80 -:10AE700080F220329046FFF765FF04460F4640EA15 -:10AE80000A0041EA0B0153465A46084303D12046C3 -:10AE90003946BDE8F08D114653EA010015D0C8F1DE -:10AEA00040025046FFF75DFF05460E4650465946A4 -:10AEB0004246FFF747FF084301D0012000E0002091 -:10AEC000054346EAE0762C4337430A984FEA445359 -:10AED000A0EB08004FEAD4240A304FF0000244EA05 -:10AEE00047544FEAD72502D500200146D1E7010596 -:10AEF00010196941DDE9084500196941BDE8F04DC7 -:10AF0000A0E73A2800D2303820F02002412A01D3AD -:10AF1000A2F13700884201D34FF0FF30704770B57F -:10AF200001EB020410F8015B15F0070301D110F8E2 -:10AF3000013B2A1106D110F8012B03E010F8016B38 -:10AF400001F8016B5B1EF9D12B0705D40023521EBB -:10AF50000FD401F8013BFAE710F8013B02F10202BD -:10AF6000A1EB030303E013F8015B01F8015B521E40 -:10AF7000F9D5A142D6D3002070BD00000FB4054B17 -:10AF800010B503A9044A029800F0E8F810BC5DF877 -:10AF900014FB0000152300083404002041000802BF -:10AFA00018BF04200A0E18BF40F001004FF07F4286 -:10AFB00032EA010108BF40F00200012808BF052065 -:10AFC0007047000000487047380400206FF05E01B1 -:10AFD0000807FFF775BC00002DE9F04D0E4614463A -:10AFE0004FF07F41B1EB440F9EBF4FF0FF31316016 -:10AFF000BDE8F08D4FF0004040EA0421C4F3C75093 -:10B000007838431100F01F00DFF814C1C0F12002AE -:10B01000FC445CF823500CEB83038540D3F804C058 -:10B020002CFA02F72F439D680CFA00FC25FA02F86F -:10B03000DB6805FA00F023FA02F240EA02054CEA66 -:10B04000080CA7FB0132ACFB01C0A5FB015101EBD1 -:10B050000C058D4234BF4FF0010C4FF0000CC118AD -:10B060006144BCF1000F02D0814202D903E0814269 -:10B0700001D2012000E00020104400F120024FEA3C -:10B0800092188006CA0C40EA42304F03C6F800808E -:10B09000FFF722FC82463846FFF727FC6FF01201CB -:10B0A000FFF70EFC07462846FFF71FFC6FF025014F -:10B0B000FFF706FC834639465046FFF733FB5946F7 -:10B0C000FFF730FB00F500656FF30B05514628468E -:10B0D000FFF77AFB3946FFF777FB5946FFF777FB17 -:10B0E0001049FFF777FB07460F492846FFF772FB29 -:10B0F0003946FFF717FB07460C492846FFF76AFB5E -:10B100003946FFF70FFB14F0004F08BFBDE8F08D84 -:10B11000C8F1805180F000403160BDE8F08D000042 -:10B120009C200000DB0FC92F22AAFD290000C92F97 -:10B1300002E008C8121F08C1002AFAD17047704700 -:10B14000002001E001C1121F002AFBD1704700005E -:10B150000149086070470000380400202DE9FF4FC6 -:10B160008BB09A460F4605460026C9E0252837D100 -:10B1700000246D1C6649A04601222B78203B02FA70 -:10B1800003F0084202D004436D1CF6E728782E280D -:10B1900017D115F8010F44F004042A280ED06FF0DF -:10B1A0002F022878A0F1300109290AD808EB88017C -:10B1B00002EB410100EB01086D1CF2E757F8048B2C -:10B1C0006D1C287869283FD006DC002871D06328E0 -:10B1D0000CD0642804D137E0732811D075284ED0E4 -:10B1E00052460D99904706F1010688E017F8040BC6 -:10B1F0008DF8000000208DF80100E946012003E0F1 -:10B2000057F8049B4FF0FF3061074FF0000401D462 -:10B210000AE0641C44450DDA8442FADB19F8041094 -:10B220000029F6D106E0641C8442FCDB19F8041006 -:10B230000029F8D1264404E019F8010B52460D9973 -:10B240009047641EF8D25AE001CF4FF00A0B002855 -:10B2500004DAC0F100004FF02D0102E0210504D511 -:10B260002B218DF82410012103E0E10705D02021D6 -:10B27000F7E70DF1200908910CE00021F9E701CF73 -:10B280004FF00A0BF9E75946FFF776FB01F1300260 -:10B2900009F8012D0028F6D1ADEB090000F1200BD3 -:10B2A000600701D44FF00108D84503DDA8EB0B007F -:10B2B00001E029E000208046002406E009A852466B -:10B2C000005D0D999047761C641C08988442F5DB5C -:10B2D00004E0302052460D999047761CB8F10001E9 -:10B2E000A8F10108F5DC05E019F8010B52460D99AB -:10B2F0009047761CBBF10001ABF1010BF4DC6D1C37 -:10B30000287800287FF432AF0FB03046BDE8F08FC8 -:10B31000092801002DE9F0474FF0684202EB400395 -:10B320000C460546B3F1654F3CBF02EB4102B2F15A -:10B33000654F3FD34FF07F42B2EB400F28BFB2EBD7 -:10B34000410F03D2BDE8F047FFF7ECB940EA010333 -:10B350005B0008BF44F0FF410AD0B2EB400F08BFCA -:10B36000B2EB410F06D125F0804024F08041054624 -:10B370000C461FE0B2EB400F12BF5FEA410245F0FE -:10B38000FF4004F0004115D04FEA410292EA400329 -:10B3900010D4002AB4BF4FF03E564FF09F463146BE -:10B3A000FFF718FA054631462046FFF713FA044620 -:10B3B00028462146C0F3C753C1F3C7529A1A1B2A25 -:10B3C00006DD10F0004F14BF54485548BDE8F08723 -:10B3D00012F11A0F17DA11F0004F06D010F0004FDB -:10B3E0000CBF50485048BDE8F08721462846FFF77B -:10B3F00027FA0446FFF7D2FD042808BFFFF7E6FD51 -:10B400002046BDE8F0874200B2EB410F25D910F08D -:10B41000004F19BF454F464E464F474E224685F0D6 -:10B42000004415460A4680F0004110460A1A5200B0 -:10B43000B2F1807F3ED248404049DFF804A110F0CD -:10B44000004F18D04FF03F483846FFF7BDF9074688 -:10B4500051463046FFF7B8F917E011F0004F04BF2E -:10B4600000263746E2D010F0004F19BF354F364E58 -:10B47000364F374EDAE74FF07C583846FFF752F92F -:10B48000074651463046FFF74DF9064641462846E5 -:10B49000FFF7A0F92146FFF745F9824621464046CD -:10B4A000FFF798F92946FFF792F95146FFF7C8F9D7 -:10B4B000044604E021462846FFF7C2F90446014647 -:10B4C000FFF788F980462349FFF784F92249FFF7FF -:10B4D00029F94146FFF77EF92049FFF723F9414654 -:10B4E000FFF778F91E49FFF71DF94146FFF772F99A -:10B4F0001C49FFF717F9054641462046FFF76AF950 -:10B500002946FFF767F93146FFF70CF92146FFF7A7 -:10B5100009F93946BDE8F047FFF704B9DB0FC9BFA9 -:10B52000DB0FC93FDB0F4940DB0F49C00000C9BF3B -:10B5300022AAFDB90000C93F22AAFD390060ED3EF4 -:10B54000C30ACE37000049C022AA7DBA0000494094 -:10B5500022AA7D3A2DAD65BD8FB8D53D0FB511BE80 -:10B5600061C84C3EA8AAAABE2DE9F843044602468B -:10B5700050486946B0EB420F09D94FF0E640B0EBB6 -:10B58000420F94BF00204FF0FF30009034E04A4B50 -:10B5900022F0004083422BD948492046FFF71AF990 -:10B5A000FFF7A3FA8046FFF7A5F900F0030000902B -:10B5B00043494046FFF70EF9054642494046FFF72A -:10B5C00009F9064640494046FFF704F907463F4956 -:10B5D0004046FFF7FFF82146FFF7F9F83946FFF735 -:10B5E000F3F83146FFF7F0F82946FFF7EDF802E0EF -:10B5F0001046FFF7F1FC04462546009C002C18DAA3 -:10B600006800B0F17F4F3CBF4FF07E50BDE8F8833B -:10B6100009D14FF00100FFF79BFDBDE8F843002181 -:10B620000846FFF70DB92846BDE8F8430121FFF7AA -:10B6300047B9294614F0010F08461CD0FFF7CAF895 -:10B6400006462349FFF7C6F82249FFF7C0F83146FE -:10B65000FFF7C0F82049FFF765F83146FFF7BAF861 -:10B660002946FFF7B7F82946FFF75CF814F0020FF8 -:10B670001CD0BDE8F883FFF7ADF805461749FFF782 -:10B68000A9F81749FFF74EF82946FFF7A3F815491F -:10B69000FFF748F82946FFF79DF84FF07E51FFF776 -:10B6A00041F814F0020F08BFBDE8F88380F00040B5 -:10B6B000BDE8F883B61F927E490E494683F9223FC2 -:10B6C0001A61342C0020A23300A0FD390000C93FCC -:10B6D000336D4C39DA82083CA0AA2ABEB93AB2BA14 -:10B6E000CA9F2A3DDDFFFFBE70B50546FFF7C2FACF -:10B6F00004464000801C0DD12846FFF7F6F90546A8 -:10B700002046FFF7E9F82946FFF722F91CBF012080 -:10B71000FFF71EFD204670BD2DE9F04D0F460E4689 -:10B72000A0F50001804604464FF0007084B04FF051 -:10B730007E554FF0000B00EB47004FF07F4AB1F110 -:10B74000FE4F04D2B0F1804F80F0018141E0B0F1B2 -:10B75000804F3ED304F1FF40B0F1FE4F1FD200BF37 -:10B7600028F00048C6F3C75044467F2809DB9728D5 -:10B770007DDAC0F19600012101FA00F0411E31424C -:10B7800009D00120FFF7E4FC04B00021BDE8F04D32 -:10B790000846FFF755B8304218BFFE4DD7E06000AD -:10B7A00000281CBF4FF08070B0EB440F0BD91B2159 -:10B7B0004046FFF785F8804604466FF01A0B10F0FC -:10B7C000004FCDD1C3E0A4F50000B0F1FE4F1BD275 -:10B7D000BDE0B0F1007F11D300213846FFF7B8F883 -:10B7E00006D16000002818BFBAEB440F71D8B1E74A -:10B7F00006F0004040F0FC563746ABE7B0F1807FE2 -:10B8000038BFA6F50007A5D324F000406FF0FF4233 -:10B81000E14B8118994210D326F000410A449A4224 -:10B820000BD3B4F17E5F18BF5FEA460251D0B0F18E -:10B83000FF4F98BFB1F1FF4F06D904B039464046DB -:10B84000BDE8F04DFEF76EBFB4F1FF4F10D0C6F368 -:10B85000C7507F2809DB972812DAC0F19600012132 -:10B8600001FA00F0411E314206D0002009E06EE0EE -:10B8700016F0004F5DD127E0304218BF012000D103 -:10B88000022014F5000F13D024B3B4F1004F27D0D9 -:10B8900014F1814F56D04FF0FE40B0EB440F94BFEF -:10B8A00001200020012101EBE671884241D10BE02B -:10B8B00016F0004F02D001283FD03AE0012802BF25 -:10B8C000B64804B0BDE8F08D4FF0FF4004B0BDE8CD -:10B8D000F08D37E016F000400ED104B0BDE8F08DD9 -:10B8E000B6F1FF4F25D016F5000F05D016F0004F2A -:10B8F00018D008B101280AD00220FFF729FC04B0B3 -:10B900000021BDE8F04D4FF07E50FEF799BF0220B8 -:10B91000FFF71EFC04B04146BDE8F04D4FF07E50ED -:10B92000FEF78EBF002804BF04B0BDE8F08D0128EB -:10B9300003D004B00020BDE8F08D04B04FF000400B -:10B94000BDE8F08D04B04FF07E50BDE8F08D944816 -:10B950002044B0F5005F44D84046FFF7B1F900221B -:10B96000904BFFF781F9FFF7BEF904466FF0010134 -:10B97000FEF7A6FF8C49FEF72AFF2146FEF72AFFB5 -:10B980004FF07C51FEF723FF064621460846FEF79E -:10B9900021FF80F000403146FEF71CFF80468349BE -:10B9A0002046FEF717FF064681494046FEF712FF84 -:10B9B000804680492046FEF70DFF4146FEF7B2FE65 -:10B9C000044601463046FEF7ADFE00F5006B6FF30E -:10B9D0000B0B59463046FEF7F7FE2146FEF7A2FE56 -:10B9E000D4E004F58020C00C00F00F06C0F307106F -:10B9F0007F38A4EBC05483443046FEF76DFF6FF0F0 -:10BA00000301FEF75DFF4FF07E51FEF78BFE01460E -:10BA100002902046FEF7D8FE019020460299FEF7DC -:10BA200081FE00F500686FF30B0800904146029814 -:10BA3000FEF7CAFE2146FEF775FE02904FF07E50DB -:10BA40000099FEF7FDFE014600900198FEF7C2FE48 -:10BA500000F500646FF30B0420460299FEF7BAFE6E -:10BA6000029041462046FEF7B5FE0199FEF7AFFE73 -:10BA70000299FEF7A9FE0099FEF7ACFE0146009080 -:10BA80002046FEF74FFE0146FEF7A4FE80464A49D7 -:10BA9000FEF7A0FE4449FEF745FE4146FEF79AFE3A -:10BAA000804600212046FEF70BFF019020460099BA -:10BAB000FEF738FE4146FEF78DFE04460021009851 -:10BAC000FEF7FEFE2146FEF72DFE80460146019858 -:10BAD000FEF728FE00F500646FF30B042146019881 -:10BAE000FEF772FE4146FEF71DFE804633492046B2 -:10BAF000FEF770FE009032494046FEF76BFE80462E -:10BB000030492046FEF766FE4146FEF70BFE8046B2 -:10BB100001460098FEF706FE00F500646FF30B0483 -:10BB200021460098FEF750FE4146FEF7FBFD804699 -:10BB30002548784450F8361000EBC600019146685D -:10BB40004FEA0B10FEF7C8FE009031464046FEF764 -:10BB5000E9FD2146FEF7E6FD0199FEF7E3FD0099B8 -:10BB6000FEF7E0FD00F5006B6FF30B0B58460099F4 -:10BB7000FEF72AFE0199FEF727FE2146FEF724FE76 -:10BB80003146FEF721FE4146FEF721FE804607F5CD -:10BB900000641BE0000080BFFFFF3F00000080FF4B -:10BBA000001080C00000F03FABAAAA3E00B0B84130 -:10BBB0003BAAB841D49A38BB7EE24C3E00B0384232 -:10BBC0003BAA3842D49AB8BBB21300006FF30B04FF -:10BBD00021463846FEF7F8FD074621465846FEF74F -:10BBE000F9FD064639462046FEF79CFD4146FEF724 -:10BBF000F1FD044639465846FEF7ECFD2146FEF7B6 -:10BC000091FD074601463046FEF78CFD00F50064C5 -:10BC10006FF30B0421463046FEF7D6FD3946FEF79A -:10BC200081FD804601462046FEF77CFDFFF722F8A5 -:10BC300007460611FEF750FE2146FEF7C8FD4146B5 -:10BC4000FEF770FD04463549FEF7C4FD3449FEF7A2 -:10BC500069FD2146FEF7BEFD3249FEF763FD214630 -:10BC6000FEF7B8FD0146304807F00F04784450F85D -:10BC70002400FEF7AFFD2D49794451F82410FEF75A -:10BC800051FD2B49794451F82410FEF74BFD06F184 -:10BC90007D01FC2908D23146FEF712FE04B0294688 -:10BCA000BDE8F04DFEF796BD06F1BF01B1F5BF7FCF -:10BCB00016D83146FEF704FE2946FEF78BFD0446F2 -:10BCC000BAEB440F1AD060000CD02046FFF766F99B -:10BCD000042808BFFFF77AF9204604B0BDE8F08DCC -:10BCE000002E0BDA0220FFF733FAFFF76FF9014657 -:10BCF000284604B061F31E00BDE8F08D0220FFF776 -:10BD000027FA61214FF0E040FEF7DAFD01462846B0 -:10BD100004B061F31E00BDE8F08D0000FC596337EC -:10BD2000C9FF753A1872313D781300002C130000DA -:10BD3000E01200002DE9F8430446024653486946E4 -:10BD4000B0EB420F09D94FF0E640B0EB420F94BF81 -:10BD500000204FF0FF30009034E04D4B22F00040C7 -:10BD600083422BD94B492046FEF734FDFEF7BDFE3A -:10BD70008046FEF7BFFD00F00300009046494046B4 -:10BD8000FEF728FD054645494046FEF723FD0646D9 -:10BD900043494046FEF71EFD074642494046FEF72E -:10BDA00019FD2146FEF713FD3946FEF70DFD31461C -:10BDB000FEF70AFD2946FEF707FD02E01046FFF7F1 -:10BDC0000BF904462546009C002C1DDA6800B0F1F2 -:10BDD0007F4F09D22846FFF7E1F8042808BFFFF794 -:10BDE000F5F82846BDE8F88308D10120FFF7B0F93F -:10BDF000BDE8F84300210846FEF722BD2846BDE80D -:10BE0000F8430121FEF75CBD294614F0010F0846F6 -:10BE10001ED0FEF7DFFC05462349FEF7DBFC234975 -:10BE2000FEF780FC2946FEF7D5FC2149FEF77AFC97 -:10BE30002946FEF7CFFC4FF07E51FEF773FC14F05D -:10BE4000020F08BFBDE8F88380F00040BDE8F8832A -:10BE5000FEF7C0FC06461749FEF7BCFC1649FEF784 -:10BE6000B6FC3146FEF7B6FC1449FEF75BFC3146E2 -:10BE7000FEF7B0FC2946FEF7ADFC2946FEF752FC62 -:10BE800014F0020FE0D1BDE8F8830000B61F927EE7 -:10BE9000490E494683F9223F1A61342C0020A2330F -:10BEA00000A0FD390000C93FB93AB2BACA9F2A3D85 -:10BEB000DDFFFFBE336D4C39DA82083CA0AA2ABEF2 -:10BEC00070B50546FEF7E2FD044620F00040C0F1E3 -:10BED000FF40C00F08D025F00040C0F1FF40C00F68 -:10BEE00004BF0120FFF734F9204670BD5FD1000880 -:10BEF000AFD10008F5D100085CD1000863D100087B -:10BF000005D1000800D1000850D10008F5D0000884 -:10BF1000EFD1000808D10008C0D1000804D2000801 -:10BF20001FD100088DD100082CD10008EED00008E8 -:10BF300086D10008000000009BD10008DFD1000876 -:10BF40006AD10008FBD10008B5D10008E4D100088F -:10BF500038D1000847D10008DBD1000816D100080D -:10BF6000CAD100080ED20008D0D100089FD1000825 -:10BF700013D100087BD1000800000000AAD10008FE -:10BF80000FD10008A5D1000828D10008CAD10008A7 -:10BF9000DBD10008000000003DD80008F8D0000800 -:10BFA000DFD00008FDD70008E7D000085FD3000805 -:10BFB0000000000018D80008ABD7000833030008C1 -:10BFC00013D80008A5D6000887030008F8D6000893 -:10BFD00059D70008A906000875D600088CD50008B6 -:10BFE0005B07000826D700083DD80008D1080008E4 -:10BFF00088D30008F7D40008F108000870D60008BC -:10C000003DD80008BD0900086CD600087AD60008A3 -:10C01000E9090008B3D6000876D70008730C0008B9 -:10C0200010D30008D0D00008F70C0008FDD300089A -:10C0300049D70008AB08000822D7000889D70008B4 -:10C04000310D00081BD700080FD70008710E00083B -:10C05000C9D500083DD800081B0F000856D30008BA -:10C0600002000000780400200000000028230000E7 -:10C0700022D200080200000080050020B004000069 -:10C08000A40600003ED30008020000003C0500208A -:10C0900000000000D00700004AD3000802000000A2 -:10C0A0003E05002000000000D0070000C0D20008BC -:10C0B000020000004005002000000000D007000042 -:10C0C000A7D4000802000000820500200000000044 -:10C0D000D0070000B0D40008020000008405002052 -:10C0E00000000000D0070000EED7000802000000AA -:10C0F0004205002000000000D007000078D40008AE -:10C10000020000004405002000000000D0070000ED -:10C1100028D20008020000004605002000000000B0 -:10C12000D007000018D300080200000048050020D6 -:10C1300000000000D0070000B7D300080200000094 -:10C140004A05002032000000F2010000A8D30008D8 -:10C15000020000004C05002032000000F201000047 -:10C160007FD50008000000008605002000000000C8 -:10C1700001000000D8D30008040000008C05002056 -:10C18000B004000000C20100D4D300080400000085 -:10C190009005002080250000004B000051D20008CF -:10C1A00000000000940500200000000001000000D5 -:10C1B00064D3000800000000880500200000000093 -:10C1C00003000000E8D300080100000089050020FA -:10C1D000FFFFFFFF040000006DD300080000000017 -:10C1E0007E0500200000000002000000C8D4000806 -:10C1F0000000000095050020000000000100000084 -:10C2000006D3000800000000720500200A000000AC -:10C21000C8000000DED20008000000007305002006 -:10C220000A00000032000000CBD20008000000002D -:10C23000740500200A000000320000000BD5000841 -:10C24000000000007505002000000000090000004B -:10C2500030D60008000000004E050020000000005D -:10C260000800000018D20008000000004F05002060 -:10C27000000000000800000028D4000800000000B2 -:10C2800050050020000000000800000052D5000802 -:10C2900003000000520500204CFFFFFF6801000072 -:10C2A00047D4000803000000540500204CFFFFFFA6 -:10C2B00068010000D2D700080300000056050020E6 -:10C2C0004CFFFFFF68010000E1D5000801000000FD -:10C2D00058050020FFFFFFFF010000007BD300088E -:10C2E00000000000590500200000000005000000CB -:10C2F0006DD200080000000064050020000000006E -:10C30000800000001FD40008020000005A05002031 -:10C310000000000000010000C8D600080200000074 -:10C320005C05002064000000E8030000D9D6000886 -:10C33000020000005E05002064000000E803000029 -:10C3400096D6000800000000E8070020000000006A -:10C3500001000000B7D20008000000004E080020D5 -:10C360000000000020000000B4D20008000000001F -:10C370004F0800200000000064000000DDD4000829 -:10C38000000000005008002001000000FA0000003A -:10C39000F1D2000800000000510800200000000059 -:10C3A0000100000005D6000800000000520800202F -:10C3B000000000006400000090D3000800000000AE -:10C3C0000708002000000000FA0000001FD6000847 -:10C3D00000000000080800200000000064000000C9 -:10C3E00065D20008000000000908002000000000DD -:10C3F0006400000027D60008000000000A080020A2 -:10C4000000000000FA00000098D3000800000000BF -:10C410000B0800200000000064000000F5D30008B5 -:10C42000000000000C080020000000006400000074 -:10C430001CD8000800000000940800200000000044 -:10C44000C80000002BD8000800000000950800205C -:10C4500000000000C80000002CD30008020000000B -:10C4600096080020E8030000D00700007DD20008F5 -:10C47000020000009808002064000000D0070000BF -:10C480001DD5000801000000870500200000000005 -:10C4900004000000F7D50008010000009A08002001 -:10C4A000FFFFFFFF010000003BD600080100000075 -:10C4B0009B0800200000000001000000EBD60008EF -:10C4C000000000009C08002000000000FF000000A9 -:10C4D000B9D6000800000000140800200000000089 -:10C4E000FA00000097D200080000000016080020A3 -:10C4F0000000000064000000A6D200080000000058 -:10C50000150800200000000064000000B9D40008F5 -:10C5100000000000240800200000000001000000CE -:10C5200061D400080300000012080020D4FEFFFFC1 -:10C530002C0100006AD5000803000000100800204C -:10C54000D4FEFFFF2C01000002D400080000000010 -:10C5500017080020000000003000000010D4000880 -:10C560000500000018080020000000000100000085 -:10C570002ED50008050000001C0800200000000067 -:10C580000100000031D7000805000000200800204D -:10C590000000000001000000D1D5000803000000E9 -:10C5A0000E080020B0B9FFFF5046000058D6000822 -:10C5B00000000000ED07002000000000C80000009F -:10C5C00093D4000800000000F707002000000000DE -:10C5D000C80000003DD20008000000000108002053 -:10C5E00000000000C80000004DD600080000000058 -:10C5F000EE07002000000000C800000088D40008FA -:10C6000000000000F807002000000000C800000043 -:10C6100032D20008000000000208002000000000E4 -:10C62000C800000062D6000800000000EF070020EC -:10C6300000000000C80000009DD4000800000000B9 -:10C64000F907002000000000C800000047D20008E1 -:10C65000000000000308002000000000C8000000E7 -:10C6600001D70008020000009E0800200000000022 -:10C67000D007000032D4000800000000A20800200B -:10C680000000000001000000BBD50008020000000F -:10C69000A40800200A000000D007000005D8000808 -:10C6A00002000000A60800200A000000D0070000D9 -:10C6B000C6D3000800000000A10800200000000010 -:10C6C0006400000070D4000800000000EA070020A9 -:10C6D00000000000C800000059D40008000000005D -:10C6E000F407002000000000C800000051D400083A -:10C6F00000000000FE07002000000000C80000004D -:10C7000078D5000800000000E907002000000000C4 -:10C71000C800000063D5000800000000F3070020F7 -:10C7200000000000C80000005CD500080000000008 -:10C73000FD07002000000000C8000000E8D7000846 -:10C7400000000000EB07002000000000C80000000F -:10C75000E2D7000800000000F507002000000000FC -:10C76000C8000000DCD7000800000000FF07002020 -:10C7700000000000C800000043D7000800000000CF -:10C78000EC07002000000000C80000003DD70008B2 -:10C7900000000000F607002000000000C8000000B4 -:10C7A0002BD7000800000000000800200000000057 -:10C7B000C80000004AD5000800000000F007002073 -:10C7C00000000000C800000042D500080000000082 -:10C7D000FA07002000000000C80000003AD5000859 -:10C7E000000000000408002000000000C800000055 -:10C7F0004145525431323334000000000000803F84 -:10C8000000000000A8AAAA3F000000000000803F2E -:10C81000000080BFB0AA2ABF000000000000803FD7 -:10C820000000803FB0AA2ABF000000000000803F47 -:10C83000000000000000803F000080BF0000803F3B -:10C84000000080BF000000000000803F0000803F2B -:10C850000000803F000000000000803F0000803F9B -:10C8600000000000000080BF000080BF0000803F8B -:10C87000000080BF0000803F000080BF0000803FBC -:10C88000000080BF000080BF0000803F0000803FAC -:10C890000000803F0000803F0000803F0000803F9C -:10C8A0000000803F000080BF000080BF0000803F8C -:10C8B0000000803F00000000000000000000803FFA -:10C8C000000080BF00000000000000000000803F6A -:10C8D00000000000A8AAAA3F0000803F0000803F9F -:10C8E000000080BFB0AA2ABF000080BF0000803FC8 -:10C8F0000000803FB0AA2ABF000080BF0000803F38 -:10C9000000000000A8AAAA3F000080BF0000803FEE -:10C91000000080BFB0AA2ABF0000803F0000803F17 -:10C920000000803FB0AA2ABF0000803F0000803F87 -:10C93000000080BFD0B35D3F0000803F0000803F1B -:10C94000000080BFD0B35DBF000080BF0000803F0B -:10C950000000803FD0B35D3F0000803F0000803F7B -:10C960000000803FD0B35DBF000080BF0000803F6B -:10C9700000000000D0B35DBF0000803F0000803F9A -:10C9800000000000D0B35D3F000080BF0000803F8A -:10C99000000000000000803F000080BF0000803FDA -:10C9A000000080BF000080BF000000000000803F4A -:10C9B000000000000000803F0000803F0000803F3A -:10C9C0000000803F000080BF000000000000803FAA -:10C9D000D0B35DBF0000803F0000803F0000803F7B -:10C9E000D0B35DBF000080BF0000803F0000803FEB -:10C9F000D0B35D3F0000803F000080BF0000803F5B -:10CA0000D0B35D3F000080BF000080BF0000803FCA -:10CA1000D0B35DBF00000000000080BF0000803F79 -:10CA2000D0B35D3F000000000000803F0000803F69 -:10CA3000000080BF0000803F000080BF0000803FFA -:10CA4000000080BF000080BF0000803F0000803FEA -:10CA50000000803F0000803F0000803F0000803FDA -:10CA60000000803F000080BF000080BF0000803FCA -:10CA7000000080BF0000803F0000803F0000803F3A -:10CA8000000080BF000080BF000080BF0000803F2A -:10CA90000000803F0000803F000080BF0000803F1A -:10CAA0000000803F000080BF0000803F0000803F0A -:10CAB000F704353FF70435BF0000803F0000803F9A -:10CAC000F70435BFF70435BF0000803F0000803F0A -:10CAD000F70435BFF704353F0000803F0000803F7A -:10CAE000F704353FF704353F0000803F0000803FEA -:10CAF00000000000000080BF000080BF0000803FF9 -:10CB0000000080BF00000000000080BF0000803FE8 -:10CB1000000000000000803F000080BF0000803F58 -:10CB20000000803F00000000000080BF0000803F48 -:10CB30000000803F000000BF0000803F0000803FF9 -:10CB4000000000BF000080BF0000803F0000803F69 -:10CB5000000080BF0000003F0000803F0000803FD9 -:10CB60000000003F0000803F0000803F0000803F49 -:10CB70000000003F000080BF000080BF0000803F39 -:10CB8000000080BF000000BF000080BF0000803FA9 -:10CB9000000000BF0000803F000080BF0000803F19 -:10CBA0000000803F0000003F000080BF0000803F89 -:10CBB000000000000000803F0000803F0000803F38 -:10CBC000000080BF000080BF000000000000803F28 -:10CBD000000000000000803F000080BF0000803F98 -:10CBE0000000803F000080BF0000008000000000C7 -:10CBF0000000000003010000FCC700080400000062 -:10CC00002CC80008040000006CC8000802010000E5 -:10CC1000ACC8000800010000000000000600000091 -:10CC2000CCC80008060000002CC900080101000063 -:10CC300000000000040000008CC90008060000008D -:10CC4000CCC90008080000002CCA00080800000039 -:10CC5000ACCA0008080000002CCB0008010100004D -:10CC600000000000000100000000000000010000C2 -:10CC70000000000004000000ACCB00080000000031 -:10CC800000000000524F4C4C3B50495443483B5924 -:10CC900041573B414C543B506F733B506F73523B79 -:10CCA0004E6176523B4C4556454C3B4D41473B56B9 -:10CCB000454C3B0000C2010084D90008A7D90008F8 -:10CCC00000E1000062D900084ED90008009600007B -:10CCD00018D900083AD90008004B0000F6D800081F -:10CCE000E2D80008802500003DD800083DD80008A3 -:10CCF000B56206010300F00500FF19B562060103E5 -:10CD000000F00300FD15B56206010300F00100FB11 -:10CD100011B56206010300F00000FA0FB5620601CA -:10CD20000300F00200FC13B56206010300F00400EA -:10CD3000FE17B562060103000102010E47B5620647 -:10CD40000103000103010F49B5620601030001065A -:10CD500001124FB562060103000112011E67B562A0 -:10CD60000616080003070300510800008A41B56257 -:10CD700006080600C80001000100DE6A1048494AA2 -:10CD80004B4C4D44454647FF20212223242526278E -:10CD900048494A4B4C4DFF1048498A8B8C8D8485FD -:10CDA0008687FF202122232425262748498A8B8C29 -:10CDB0008DFF000088CD00087CCD0008A3CD0008C1 -:10CDC00097CD0008000C014008001002000C014043 -:10CDD0001000100200080140001014027D820008BB -:10CDE000198200084D8200089B81000833820008E8 -:10CDF000000000400008014001000000001C00008D -:10CE0000000000400008014002000000041C000077 -:10CE1000000000400008014004000000081C000061 -:10CE20000000004000080140080000000C1C000049 -:10CE3000000400400008014040000000001D000008 -:10CE4000000400400008014080000000041D0000B4 -:10CE500000040040000C014001000000081D00001B -:10CE600000040040000C0140020000000C1D000006 -:10CE7000002C01400008014000010000001B0100DF -:10CE8000002C014000080140000800000C1B0100BC -:10CE900000080040000C014040000000001E00009F -:10CEA00000080040000C014080000000041E00004B -:10CEB00000080040000C014000010000081E0000B6 -:10CEC00000080040000C0140000200000C1E0000A1 -:10CED0000004080CD39300088B930008AD9300085E -:10CEE000EB9300085F9200080000000000000000C3 -:10CEF0000000B33FB2BE7D3A00002E40DFCF513874 -:10CF000000007E40BF51FABA00E0A44019DAC3BA6B -:10CF100000E0C840C2ED8AB90040EB40CD1F2CBAFA -:10CF2000001006412AFFFABA00C01541DFCFD13701 -:10CF300000D024419A97703A0050334189478E3689 -:10CF400000404141E75B9D3800B04E41C00A98B9AE -:10CF500000A05B41558F943A00306841DA92C0BA24 -:10CF60000040744162B3C63A0000803F00A0853F94 -:10CF700000908B3F00C0913F0030983F00F09E3FF3 -:10CF800000F0A53F0050AD3F0000B53F0000BD3FA1 -:10CF90000060C53F0020CE3F0040D73F00C0E03FCB -:10CFA00000C0EA3F0020F53F000000007D36AC39AC -:10CFB0007D3C3839EBDCF438320A7E39124C2639A4 -:10CFC0009B6AED39A4EE83397F661E39F6398A39BA -:10CFD0002B426539A48211395B991F39C3EECD39D3 -:10CFE000DDE7C637A5A22F390000803FC3AA853FE1 -:10CFF000C2958B3FD3C3913FF037983F32F59E3FA8 -:10D00000D7FEA53F3F58AD3FF304B53FA408BD3F51 -:10D010002A67C53F8C24CE3FFD44D73FDFCCE03F9D -:10D02000C7C0EA3F7D25F53F0040404040404040BA -:10D0300040404141414141404040404040404040EB -:10D04000404040404040404040050202020202028F -:10D0500002020202020202020220202020202020DE -:10D0600020202002020202020202909090909090F2 -:10D0700010101010101010101010101010101010B0 -:10D080001010101002020202020288888888888824 -:10D090000808080808080808080808080808080810 -:10D0A00008080808020202024000000029D0000817 -:10D0B000000000006E83F9A22915444ED15727FCC9 -:10D0C000C0DD34F5999562DB4190433CAB6351FE82 -:10D0D000696E64657820283020746F203229004DF5 -:10D0E00050553630353000424D41323830005654BC -:10D0F00041494C34005934004144584C33343500D4 -:10D1000048455836005936004F43544F583800416F -:10D110004343003344004641494C53414645004196 -:10D120004952504C414E45004D41470048454C49FD -:10D130005F39305F444547004759524F5F534D4F69 -:10D140004F5448494E47004C45445F52494E4700B2 -:10D15000464C59494E475F57494E47004249005493 -:10D1600052490047494D42414C00494E464C4947BF -:10D1700048545F4143435F43414C00534F4654532F -:10D18000455249414C00435553544F4D0048454C7E -:10D19000495F3132305F4343504D0050504D00568F -:10D1A0004152494F004241524F004759524F00519E -:10D1B00055414450004D4F544F525F53544F50000F -:10D1C0004F43544F464C41545000534F4E41520030 -:10D1D000504F5745524D4554455200475053005605 -:10D1E00042415400534552564F5F54494C540048F5 -:10D1F000455836580051554144580053455249410D -:10D200004C5258004F43544F464C415458005445DB -:10D210004C454D4554525900616C69676E5F6163BE -:10D2200063006D69647263006E65757472616C335E -:10D2300064006770735F706F73725F640067707310 -:10D240005F706F735F64006770735F6E61765F64B9 -:10D2500000736F667473657269616C5F696E766581 -:10D2600072746564007468725F6D6964006D6F72DA -:10D270006F6E5F7468726573686F6C640066616975 -:10D280006C736166655F6465746563745F7468720E -:10D290006573686F6C640061636378795F6465616E -:10D2A0006462616E64006163637A5F646561646295 -:10D2B000616E64007961776465616462616E6400C7 -:10D2C0006D696E636F6D6D616E6400766261746D21 -:10D2D000696E63656C6C766F6C746167650076620D -:10D2E00061746D617863656C6C766F6C7461676591 -:10D2F00000616C745F686F6C645F666173745F6318 -:10D3000068616E676500766261747363616C650065 -:10D3100070726F66696C65006465616462616E64F9 -:10D3200033645F7468726F74746C65006661696CF5 -:10D33000736166655F7468726F74746C65006D69A3 -:10D340006E7468726F74746C65006D617874687265 -:10D350006F74746C65006C6F6F7074696D65004EEE -:10D360006F6E65006770735F7479706500736572C6 -:10D3700069616C72785F74797065006163635F687E -:10D3800061726477617265006665617475726500CB -:10D3900072635F7261746500726F6C6C5F70697448 -:10D3A00063685F7261746500736572766F5F707732 -:10D3B0006D5F72617465006D6F746F725F70776D11 -:10D3C0005F72617465006E61765F736C65775F7222 -:10D3D00061746500736F667473657269616C5F6216 -:10D3E00061756472617465006770735F6261756412 -:10D3F000726174650079617772617465007361763A -:10D4000065006261726F5F7461625F73697A650063 -:10D410006261726F5F6E6F6973655F6C70660067E3 -:10D4200079726F5F6C706600616C69676E5F6D61C9 -:10D4300067006E61765F636F6E74726F6C735F68A6 -:10D44000656164696E6700616C69676E5F626F61D8 -:10D4500072645F706974636800695F70697463689F -:10D46000006163635F7472696D5F70697463680003 -:10D47000705F7069746368006465616462616E64A2 -:10D4800033645F68696768006770735F706F737299 -:10D490005F69006770735F706F735F6900677073B7 -:10D4A0005F6E61765F69006D696E636865636B00CE -:10D4B0006D6178636865636B006163635F756E615E -:10D4C000726D656463616C0074656C656D65747222 -:10D4D000795F736F667473657269616C00616C74F7 -:10D4E0005F686F6C645F7468726F74746C655F6E94 -:10D4F00065757472616C006C697374206F72202D95 -:10D5000076616C206F722076616C00706F77657247 -:10D510005F6164635F6368616E6E656C00727373F4 -:10D52000695F6175785F6368616E6E656C006261EA -:10D53000726F5F63665F76656C00645F6C657665CD -:10D540006C00695F6C6576656C00705F6C65766514 -:10D550006C00616C69676E5F626F6172645F726FAD -:10D560006C6C00695F726F6C6C006163635F7472F6 -:10D57000696D5F726F6C6C00705F726F6C6C0072C3 -:10D58000657461726465645F61726D007072696E6A -:10D590007420636F6E666967757261626C65207373 -:10D5A000657474696E677320696E206120706173A1 -:10D5B0007461626C6520666F726D006E61765F7378 -:10D5C000706565645F6D696E0076657273696F6E14 -:10D5D000006D61675F6465636C696E6174696F6E2D -:10D5E000007961775F636F6E74726F6C5F646972EC -:10D5F000656374696F6E007961775F6469726563F2 -:10D6000074696F6E007468726F74746C655F616EBC -:10D61000676C655F636F7272656374696F6E0072C9 -:10D62000635F6578706F007468725F6578706F0013 -:10D63000616C69676E5F6779726F007472695F759C -:10D640006E61726D65645F736572766F006770738B -:10D650005F706F73725F70006770735F706F735F7E -:10D6600070006770735F6E61765F70006D6170004F -:10D6700068656C700064756D70006D617070696EC6 -:10D6800067206F66207263206368616E6E656C2030 -:10D690006F72646572007069645F636F6E74726F3D -:10D6A0006C6C65720064657369676E206375737472 -:10D6B0006F6D206D69786572006163635F6C706681 -:10D6C0005F666163746F72006779726F5F636D701C -:10D6D000665F666163746F72006779726F5F636D16 -:10D6E00070666D5F666163746F720067696D626119 -:10D6F0006C5F666C6167730064656661756C7473FA -:10D70000006770735F77705F72616469757300732F -:10D71000686F772073797374656D207374617475A5 -:10D720007300736574006578697400645F616C747C -:10D73000006261726F5F63665F616C7400695F6154 -:10D740006C7400705F616C74007361766520616E4B -:10D7500064207265626F6F74007265736574207403 -:10D760006F2064656661756C747320616E642072ED -:10D7700065626F6F74006D69786572206E616D65AA -:10D78000206F72206C697374006E616D653D766107 -:10D790006C7565206F7220626C616E6B206F7220F9 -:10D7A0002A20666F72206C697374006665617475F7 -:10D7B00072655F6E616D6520617578666C6167206A -:10D7C0006F7220626C616E6B20666F72206C697381 -:10D7D0007400616C69676E5F626F6172645F79612A -:10D7E0007700695F79617700705F796177006465C0 -:10D7F000616462616E6433645F6C6F77004D4D41AC -:10D8000038343578006E61765F73706565645F6D7E -:10D81000617800636D697800617578006661696C94 -:10D82000736166655F64656C6179006661696C73DC -:10D830006166655F6F66665F64656C617900434130 -:10D840004D535441423B0043414C49423B004750F9 -:10D850005320484F4C443B004845414446524545BF -:10D860003B00414E474C453B0047505320484F4DED -:10D87000453B004D41473B0043414D545249473BD6 -:10D88000004845414441444A3B0041524D3B004819 -:10D890004F52495A4F4E3B00564152494F3B00426E -:10D8A00041524F3B004245455045523B00474F5681 -:10D8B00045524E4F523B004C4C49474854533B0055 -:10D8C00050415353544852553B004C45444C4F57DC -:10D8D0003B004F53442053573B004C45444D415867 -:10D8E0003B0024504D544B3235312C3139323030DD -:10D8F0002A32320D0A0024505542582C34312C3132 -:10D900002C303030332C303030312C313932303013 -:10D910002C302A32330D0A0024505542582C343111 -:10D920002C312C303030332C303030312C333834F3 -:10D9300030302C302A32360D0A0024504D544B32F0 -:10D9400035312C33383430302A32370D0A00245028 -:10D950004D544B3235312C35373630302A32430D69 -:10D960000A0024505542582C34312C312C303030A0 -:10D97000332C303030312C35373630302C302A32A1 -:10D98000440D0A0024505542582C34312C312C308F -:10D990003030332C303030312C3131353230302C86 -:10D9A000302A31450D0A0024504D544B3235312C6C -:10D9B0003131353230302A31460D0A00DCD90008C9 -:10D9C000000000203C0400001EAF0008CCDA000874 -:10D9D0003C0400202C25000040B100080196031EE5 -:10D9E0007A44CBDC0502A102370113DD30025C086A -:10D9F000021A030936B3914B8AD8BC29491A620C22 -:10DA0000290832021A8F0C2908297C1A9F0C290830 -:10DA100032041A980C290832051A730C29083206A8 -:10DA20001A580C290832071A810C290829591A3E5C -:10DA30000C290832091A780C2908320A1A690C29AB -:10DA400008320B1A4E0C2908320C1AC00C29083265 -:10DA50000D1AA50C2908320E1ADA0C2908320F1AF1 -:10DA6000CA0C290832101AB70C290832111A470CAF -:10DA7000290832121AAD0C290832131AD20C2908BF -:10DA8000721402A7FF021001E20452038B803F04CC -:10DA900001165A03494AD931E91D12010A1C0285AF -:10DAA000C208342C01401A408C1A40193A405B14C9 -:10DAB000A24A048B127A33380B02030406070809C2 -:0CDAC0000204063B2910691481000000DC +:1026F000C5E906C3C5E904678842F1DCF0BDA64818 +:1027000010B5807C00284DD0A44CA148A41C42796F +:10271000E0882189082A27D006DC012A15D0042A5E +:1027200029D0052A06D10AE00E2A3BD0142A22D04D +:10273000152A25D02020FFF7BCF8002832D02188A8 +:10274000002005F0BBFA618813E094498E48891C8B +:1027500090F8B300498908B100201FE09148407803 +:102760000028F9D10021F7E70146002005F0A6FA7C +:102770002189012012E0002005F0A0FA6189F8E724 +:102780000146002005F09AFA2189012005F096FA09 +:102790006189022005F092FAA1890320BDE810406A +:1027A00005F08CBA10BD70B57D4E0024183E7B4DEF +:1027B00007E000BF36F81410204605F074FA641CD8 +:1027C000E4B228788442F5D370BD744A744B00217A +:1027D0001278183B04E000BF23F81100491CC9B26D +:1027E0009142F9D3DFE72DE9FC5F6C4C6E4E6F4DE3 +:1027F0002078032814D9B6F904004142002801DDED +:10280000024600E00A4602F1640200DC08466FF06E +:102810006301A1EB0001B5F9040003F097FFA88064 +:102820005E48DFF87C91DFF860A10078A9F1180913 +:10283000012839D90024804634E000BF9AF9B2005B +:10284000B5F904104042484308F09EF8544901EBA2 +:102850000417F96808F016F80190B5F9000008F0BF +:1028600093F8796808F00EF80090B5F9020008F0C6 +:102870008BF8B96808F006F88346B6F9060008F048 +:1028800083F8396807F0FEFF594607F0A3FF009967 +:1028900007F0A0FF019907F09DFF08F083F829F8E1 +:1028A0001400641C4445C9D3DFF8E4803B4CDFF8D6 +:1028B00000B198F80500A41C08287DD006DC01288A +:1028C00037D0042809D0052840D140E00E283DD05B +:1028D000142870D01528F7D1EAE00420FFF766FE2F +:1028E000034602210420FFF76FFEB5F9041000FB38 +:1028F00001F601210420FFF767FEB5F9021000FB85 +:102900000160184420810520FFF750FE0346022194 +:102910000520FFF759FEB5F9041000FB01F601216F +:102920000520FFF751FEB5F9021000FB01601844C5 +:102930000BE00520FFF73AFE034601210520FFF7D3 +:1029400043FEB5F9041000FB01306081D4E09AF930 +:102950007200BBF902103225484390FBF5F60AF1EC +:1029600072025B460020FFF721FE3044208092F97E +:102970000800B3F90010484390FBF5F20120FFF77F +:1029800015FE10446080B7E0E8070020800A0020B0 +:102990006C04002030CD0008DC080020B4000020CA +:1029A00008090020700A00204401002036010020A0 +:1029B0003400002000E063E0B84F787878B3B8F8CE +:1029C000D220B8F8D010B6F9060003F0BFFEE081BF +:1029D000A9F80000B87A4FF0010100284FF0030079 +:1029E00021D0FFF7F1FDB6F9021000FB01F302213F +:1029F0000320FFF7E9FDB6F9001000FB0130E0808D +:102A000001210420FFF7E0FDB6F9021000FB01F3FD +:102A100002210420FFF7D8FDB6F9001020E0FFE7FF +:102A2000B8F8D400D3E7FFF7CFFDB5F9021000FBEB +:102A300001F302210320FFF7C7FDB5F9001000FBE9 +:102A40000130E08001210420FFF7BEFDB5F902103E +:102A500000FB01F302210420FFF7B6FDB5F90010D9 +:102A600000FB013020810320FFF7A0FDE18808442E +:102A7000E0800420FFF79AFD2189084420813BE093 +:102A8000042301211846FFF79FFDC3F1050135F826 +:102A90001110484324F813001846FFF787FD34F857 +:102AA0001310084424F813005B1C062BE9D323E021 +:102AB000032302211846FFF787FDB5F9041000FB38 +:102AC00001F701211846FFF77FFDC3F1060121F050 +:102AD0000101695E01FB007024F813001846FFF73E +:102AE00065FD34F81310084424F813005B1C072B11 +:102AF000DFD3F188A9F800102020FEF7DAFEC0B37A +:102B00000020FFF753FD20800120FFF74FFD6449AF +:102B10006080097A69B39AF8B4205146920715D5B6 +:102B200091F972209AF97A105542BBF90220BBF94B +:102B3000003055433222594395FBF2F591FBF2F1F7 +:102B40006A1A238829449A1A228010E09AF972306E +:102B5000BBF90220268803FB02F5322295FBF2F531 +:102B600035442580BBF900104B4393FBF2F1084438 +:102B7000608000254FEA0A0606EBC5006C30B0F90C +:102B80000220B0F9001034F9150003F0DFFD24F83D +:102B900015006D1C082DEFD396F8B400DFF804A1E2 +:102BA000400711D500252020FEF783FE00B1022545 +:102BB0000024564606EB440001896019C0B205F0B6 +:102BC0007DF8641C042CF5D337494C46B9F90070E4 +:102BD00001200B7806E000BF34F91020BA4200DD76 +:102BE0001746401C9842F7D300254FF4804B894686 +:102BF0004DE0B8F8D2004646B84205DA34F8151070 +:102C0000381A081A24F815005846FEF752FE98B1F3 +:102C1000BAF9060040F2DC51884204DDB6F8D22051 +:102C2000B6F8D81003E0B6F8D620B6F8D41034F9C8 +:102C3000150003F08BFD15E0B6F8D220B6F8D010E1 +:102C400034F9150003F082FD24F81500BAF90600E6 +:102C5000B6F81611884207DA1020FEF72AFE38B1BE +:102C6000B6F8D40024F815000C48407818B10DE0EF +:102C7000B6F8D000F6E75846FEF71BFE10B1B6F8DE +:102C8000DA0001E0B6F8D40024F815006D1C99F8BC +:102C900000008542ADD3BDE8FC9F0000700A002013 +:102CA000C60A0020800A0020B40000202DE9F04769 +:102CB0001746894606460025DFF83C841AE00024C2 +:102CC00011E000BFD8F8001081F00801C8F800102A +:102CD000012005F09CF8484605F08EF8002005F02C +:102CE00096F8641CE4B2B442ECD33C2005F084F8BE +:102CF0006D1CEDB2BD42E2D3BDE8F0872DE9FC5F6B +:102D0000FE4C002540F2DC51B4F90600FC4E4FF4B5 +:102D1000FA73884201DA64210CE0F949B0F5FA6FE0 +:102D200091F8251004DAA0F2DC52514391FBF3F143 +:102D3000C1F164018946F34996F866E096F867B0F8 +:102D4000B1F814410022B246EC49EE4B40F2E63CA9 +:102D500031F91260311B01F2F317674503D80029DE +:102D600003DCA11B01E04FF4FA71022A34D0BEF15A +:102D7000000F05D08E4502DAA1EB0E0100E0002124 +:102D8000642391FBF3F3DD4F6FF01808243707EB52 +:102D9000430C37F91370BCF902C003FB08F3ACEB2A +:102DA000070C01EB83030CFB03FC64239CFBF3F394 +:102DB0003B44D54F27F812309AF823304B434FF459 +:102DC000FA7193FBF1F1C1F1640189B201FB09F1E0 +:102DD000642391FBF3F11CE0BBF1000F05D08B45A0 +:102DE00002DAA1EB0B0100E0002193F9EC30DFF8EF +:102DF00018C35B424B43ACF804309AF824300029E6 +:102E000000DC49424B434FF4FA7193FBF1F1C1F1FD +:102E100064010AEB0207642397F801C0DFF8E88237 +:102E20000CFB01FC9CFBF3FCA8F1540808F802C061 +:102E300097F80BC008F103080CFB01FC9CFBF3FCAA +:102E400008F802C07F7D4F4397FBF3F108F10303BD +:102E5000A642995405DAAC4931F812305B4221F8A8 +:102E60001230521C032AFFF66FAFDFF898A24FF41E +:102E7000FA625446BAF8161103F068FCB4F8161159 +:102E80004FF47A72401A5043C1F5FA61B0FBF1F188 +:102E9000642291FBF2F0994B6FF01806303303EB8C +:102EA000400433F910307043B4F9024001EB800064 +:102EB000E41A444394FBF2F0DFF84C828F4E18443E +:102EC000103EA8F80600707AA8F17C04E8B38F4899 +:102ED000B4F91E10B0F90000401A07F055FD8C49F6 +:102EE00007F0D0FC8B4907F003FD074608F094FB80 +:102EF0000190384608F076FF00904746B8F9000088 +:102F000007F042FD8346009907F0BCFC8046B7F904 +:102F1000020007F039FD8146019907F0B3FC4146F4 +:102F200007F058FC07F03EFD80464846009907F040 +:102F3000A9FC81465846019907F0A4FC494607F0D0 +:102F40009BFC07F02FFD388000E001E0A7F802802D +:102F50000220FEF7AEFC002750B3E078401CC0B260 +:102F60000621B0FBF1F2E07001FB1200B8B90020BD +:102F700003F08AFE2179614A01F00703AC3A491C4B +:102F800022F813002171002032F81010401C29444F +:102F90008DB20828F8DBE80801F00EF8A072A07ADC +:102FA000E18C884203D89AF80811814201D9A770B0 +:102FB00001E00420A070A07803F05FF956484E4D60 +:102FC000008818B10220FEF75FFC10B95348008852 +:102FD00020B1286880F00800286011E0B17808204E +:102FE00011B14549091D0860717811B14249083194 +:102FF00008604FF40060FEF75CFC08B103F05DFA76 +:103000008020FEF756FC48B1E16C606B411A05D494 +:103010004CF250310844E06405F010FAA16C606B8A +:10302000411A03D4717BF9B10120B07002F011F89C +:103030002020FEF729FC68B1216D606B411A09D48C +:10304000E17A052906D3364908442065286880F0CE +:10305000100028603348816800290ED002B02A4849 +:10306000BDE8F05F5C380847B770296881F0080157 +:1030700029602D490844A064D8E7BDE8FC9F10B53D +:10308000204C204490F80A0104F022FEA0F2EE2128 +:1030900040F2DD52914201D3B4F8140110BD2DE984 +:1030A000F047194EDFF854807C3EA8F19C087079F7 +:1030B000124F401C00247071A14608F14005F16BCD +:1030C00020468847727908EBC40102F0030221F818 +:1030D000120025F81490002035F8143031F8102033 +:1030E000401C1A44C0B225F814200428F4D335F942 +:1030F0001400801CC11719E00C0C0140800A00204C +:10310000E80700206C04002044010020B0010020EA +:10311000DB0F4940000034437E0100208001002085 +:10312000F04902004C0C002020A1070000EB917038 +:10313000801025F8140037F91410C91E884202DAED +:10314000811C27F8141037F91410C91C884202DDBD +:10315000801E27F81400641CE4B2082CAFD3CBE522 +:10316000FE480288FE48417852B9827842B100296F +:1031700005D101214170FB48FB490088C883704795 +:103180000029FCD10122FF2102208FE52DE9FC5FFF +:103190000020F54982467C31054607460190B1F989 +:1031A00002004342002801DD044600E01C468B4635 +:1031B000B1F900104A42002901DD0E4600E0164632 +:1031C000B44203DD002806DC184604E0002901DDD6 +:1031D000084600E01046DFF8949300240090E04E8B +:1031E000F07808B93079E8B3022C3FDADE484FF4C2 +:1031F000FA72443030F914103BF9140001EB40002E +:10320000514203F0A3FADA49DFF868A331F9141048 +:10321000411A0AEB4400B0F9280001EB00089AF8C3 +:103220000810642001FB08F191FBF0F09AF81C10E3 +:1032300001EB8102494201EB810103F087FA019021 +:10324000C94842F21072743050F8241001EB0800A3 +:10325000514203F07BFAC449743141F824009AF8D2 +:10326000121000E008E048434FEA203AF07818B125 +:10327000307908B9022C48D13BF91450B84F05EB0E +:1032800085000101BB48A83F00EB04084FF47A52C7 +:1032900098F8010091FBF0F039F91410401A57F832 +:1032A00024100844514203F051FA47F8240039F938 +:1032B000140000F52070B0F5A06F02D857F8240074 +:1032C00002E0002047F824007D2190FBF1F098F8FF +:1032D0000B10484387113079A8B1022C13DA0098FB +:1032E000009AC0F5FA710198009B484305FB020063 +:1032F0004FF4FA7201FB0AF107FB031190FBF2F0A5 +:1033000091FBF2F608E0F07820B1022C02DA564682 +:10331000019801E028463E46934A39F914102832B4 +:103320005023125DDFF838824A4392FBF3F28E4B52 +:10333000821A6833A8F13C0833F9140023F81410FA +:10334000081A08F10C0158F8243051F824C041F84B +:1033500024309C44844448F8240083482E30005D87 +:1033600000FB0CF0C11700EBD1609119A1EB6010CC +:103370007D496E3121F81400641C032CFFF62FAF39 +:103380007BE62DE9F05F764E4FF0000BDFF8E4A10D +:10339000DFF8D4915C46A83E714DE87808B92879E9 +:1033A000D0B1022C18DA70484FF4FA72443030F978 +:1033B0001410383030F9140001EB4000514203F092 +:1033C000C5F96B4931F91410411A0AEB4400B0F900 +:1033D000280001EB000B01E0022C52D0E878E0B3AA +:1033E0009AF8080000FB0BF0001160490AEB040793 +:1033F00031F91410FA7A451A787856F8241068438F +:103400004FEAE018B9F80C006843C01200FB021044 +:103410004FF4001246F82400514203F097F946F8A1 +:10342000240043134E480C3850F8241040F8245020 +:10343000B9F80C00691A02094FF6FF70B0FBF2F000 +:10344000484347498011243901F10C0251F824C046 +:1034500052F824506544054400E01CE042F824C0C2 +:1034600041F82400787D6843011208EB030008440A +:103470003D496E3121F81400641C032C8CDBBDE83F +:10348000F09F9AF8240038491B307C31B1F90410C0 +:1034900048434011A9E7344A9AF823007C321B3094 +:1034A00032F9142050432A790011002A9DD09AF84D +:1034B000121001FB0BF100EB212096E72A490128AD +:1034C00001D02D4800E02D48086470472DE9F84FE1 +:1034D0000027B946B8460820FEF7EBF9DFF8A0B0A0 +:1034E00068B19BF8120120B1012802D0022806D150 +:1034F00002E002F042FE01E003F00AFB8046DFF842 +:1035000068A0174C4FF00005DAF83410DAF85400D0 +:103510004FF00106081A02D5B8F1000F7DD044F62D +:1035200020621144CAF85410FFF7B9FD4FF48040EF +:10353000FEF7BFF928B10A485630007808B900F004 +:103540007DFC9BF81B0168B305494FF47A7210317A +:1035500001EB40000021B0F9060013E080010020DB +:10356000700A0020B0010020C80000206800002080 +:1035700034000020E80700208D3100088333000864 +:103580006C040020A0F57A7003F0E0F807F0FCF975 +:10359000FE4907F0ADF9FE4907F074F907F01BFA90 +:1035A000AAF822004FF40070FEF783F9B0B3DFF8F9 +:1035B000E483BAF90E2098F8ACC00CEB8C01914270 +:1035C0001DDA6078D8B1BBF91431F349002000BF8F +:1035D00021F81030401C0328FADBB8F8AE30CB805D +:1035E00098F8AD00604400EB8000904202DA00F0F1 +:1035F00025FC2570BAF81010491CAAF8101098F88C +:10360000AC0000EB8001BAF90E00814204DA607868 +:1036100010B900F013FC257001E068E204E0BAF88C +:103620000E10491CAAF80E10BBF816C1BBF81821E1 +:10363000DFF864830020BF0838F91030634501DDEE +:1036400047F08007934201DA47F04007401C042806 +:10365000F1DB9AF8071050468F4205D18179FA299B +:1036600003D2491C817100E085718AF807704FF41C +:1036700080473846FEF71DF958B1BBF81411BBF866 +:10368000DC00B8F906200B1A934202DA0844904293 +:1036900009DC3846FEF70DF9E8B9B8F90610BBF8B1 +:1036A0001601814217DABC48B8380560456085606C +:1036B000BA4805604560B748C08F60B1B64846302B +:1036C000007820B1207810B1FFF74AFD03E0607860 +:1036D00008B100F0B3FB9AF80600142817D16078FF +:1036E000B0B1AC4FF88F28B99AF807005F2801D124 +:1036F00000F0A4FB9BF81A01002808D0F88F0028DE +:1037000005D19AF807007D2801D100F097FB8FE0E2 +:103710009AF80700572809D00420FEF7CAF8E8B144 +:103720009AF8071050465A2921D017E09C494FF4C7 +:103730007A7008804FF48070FEF7BBF808B101F092 +:1037400068FF0420FEF7A0F810B196490A2008800F +:103750000820FEF799F808B9934805809AF8070001 +:103760005D2817D05B2817D05E2817D023E0818A08 +:1037700019B18582AAF816601DE0818C21B1002163 +:10378000818419B1022102E00121F9E703218AF8BD +:10379000001010E0012702E0022700E00327781E56 +:1037A0008BF8780300210846FDF7A9FE3A46282148 +:1037B0000220FFF77BFA774FF88F18B99AF80710B5 +:1037C0006F290ED09BF81A1121B118B99AF8070089 +:1037D0007E2806D09AF80700972805D0A72808D099 +:1037E00008E0FFF7BDFC05E070494FF4C8700880A1 +:1037F00000E0A6739AF80700BB2806D0B72807D0C8 +:10380000BE2809D0BD280AD012E0788D801C01E0C6 +:10381000788D801E788505E0388D801C01E0388D1C +:10382000801E388501210846FDF769FE8AF806509A +:103830000420FEF73EF820B3BAF824205046322187 +:103840006AB162785AB1B8F90630BBF816219342D2 +:1038500005DD514A463212780AB9418285844E4AC2 +:103860004632527C32B1028B838A1A4309D1AAF8BC +:10387000121006E0818A21B1617811B98582AAF817 +:1038800016600020C64640F2A46700BF0EEB400160 +:10389000B1F9082040F214518A4201DA012300E014 +:1038A000002300EB40018B40A2F2155CBCF5C77F02 +:1038B00002D84FF0010C01E04FF0000C01F10108BB +:1038C0000CFA08FC43EA0C03BA4201DD012200E0D5 +:1038D0000022891C8A40134343EA0903401C1FFA53 +:1038E00083F90428D2DB2C4F00204637294901EB0D +:1038F0004001C98F11EA090100D001213954401C4F +:103900001428F3DB787840B9224890F8AC0000EB3B +:103910008001BAF90E0081420ADA0220FDF7B4FFF5 +:1039200030B1E07828B91D4805604560E67000E0D8 +:10393000E570B87838B1E570207928B91748056086 +:103940004560267100E025713878B84600B92670C8 +:10395000E178102009B9217909B1154901E014492C +:10396000091F08600420FDF78FFF70B198F803006D +:10397000474650B3A07938BB0E48A67101680E487F +:10398000016006480830C18818E02BE000007A4446 +:1039900000C07F44E8070020800A00203C0100208E +:1039A00080010020AE010020B00100207E01002037 +:1039B000140C01405C00002060000020FF48AAF8C1 +:1039C0001A100560FE48056000E0A5714FF4005034 +:1039D000FDF76FFF30B1387918B1E07B10B9E673AD +:1039E00000E0E5730220FDF74FFF18B90820FDF74E +:1039F0004BFFD0B198F80510404639B1617931B923 +:103A0000F04966710A88F0490A8000E065718179A1 +:103A100019B1617A11B9667200E0657298F8070011 +:103A200018B1E8480188AAF81E102020FDF72CFFE5 +:103A3000F0B3E07AE8B39AF80B005746052844D370 +:103A400098F80A1059B1E07990BBE671DF49257208 +:103A50003D72081F02F09BFA0220787039E0E57190 +:103A600098F80B0030B3D94A143AB2F90000002894 +:103A700000DC4042D649B1F8C01088421DDAB2F9E4 +:103A80000200002800DC4042884216DA207A78B929 +:103A9000CE4826720C383D7200F1100102680A60AF +:103AA000406841F8040FC948001D02F070FA02E0B6 +:103AB0000FE00AE001E07E700BE02572387A40B931 +:103AC0008AF8086002F038FA03E0E57125728AF896 +:103AD000015098F80C0008B1A67200E0A5729BF89E +:103AE0000500082801D00E2843D1657241E0DAF8BC +:103AF0005C005746042801DD401FF865052838D2D0 +:103B0000DFE800F0030B151F2A000820FE65FDF713 +:103B1000BBFE10B100F06DFC58BBF86D401CF865A1 +:103B20000420FDF7B1FE10B100F073FB08BBF86D87 +:103B3000401CF8650420FDF7A7FE10B1FEF77FFAE0 +:103B4000B8B9F86D401CF8654FF48070FDF7B1FE10 +:103B500010B102F0C0F90CE0F86D401CF8651020BF +:103B6000FDF792FE08B100F0C6FC4FF40050FDF7DF +:103B7000A0FE04F018F9CAF83400BBF80C20574630 +:103B800012B1BB6DC31A71D41044D946B865FEF7A3 +:103B9000EDF9FFF7B3F804F006F97863398F411AAD +:103BA000B981B8630820FDF76FFE48B3874914391F +:103BB000B1F9042002F145008A2822D8607900B3C7 +:103BC0008048038880480088181A00B210F1B40FAA +:103BD00002DC00F5B47000B2B42802DBA0F5B470CA +:103BE00000B299F9EC305B42434318B2637B3BB1BE +:103BF000774B5B7A43431E2093FBF0F0101A8880CA +:103C000003E070480188704801800420FDF73CFE05 +:103C100058B3A07948B36E4991F8690038B36B483E +:103C2000B7F91A201438B0F90630A3EB020CBCF136 +:103C3000000F01DCA2EB030C91F868108C4509DD44 +:103C4000DFF878C19342CCF800507E7200DD494223 +:103C5000194409E0797A21B15E490B685E490B602D +:103C60007D72574909881144C1803AE0E4E0FFE7DA +:103C7000DFF85881B7F91A00A8F11408B8F906302E +:103C80001A1A002A01DD134600E0C31A91F86810E1 +:103C90008B420FDDB98B4FF4FA6C114409B291FBE2 +:103CA000FCF34D4A0CFB131115681D441560B983D4 +:103CB0007E7207E0797A29B146490A6846490A6066 +:103CC000BD837D723E490988084400B2A8F8060009 +:103CD000B9F8D010B9F8D220963102F037FDA8F823 +:103CE00006003B4D95F86A0050B1E07808B920799C +:103CF00030B13648394A1438C18812881144C1801D +:103D00002020FDF7C1FDE8B3E07908B9207AC8B3F7 +:103D1000207BB8B32B4CB4F9000006F035FE304ED2 +:103D2000314606F0AFFD08F05DF80090B4F90000F0 +:103D300006F02AFE314606F0A5FD07F06DFC234C87 +:103D4000064695F8B900303CDFF898A0A4F11C08AD +:103D500010B3A146B4F90200241DB4F90210401AB0 +:103D600001F008FA15F8B92F514202F0EFFC618812 +:103D700008446080B9F90000B4F90010401A01F05D +:103D8000F9F900E04EE02A78514202F0DFFC218888 +:103D9000084400B2208001E0B4F9000006F0F4FD10 +:103DA0008346009906F06EFD0546B4F9020006F060 +:103DB000EBFD8146314606F065FD15E02800002048 +:103DC00024000020B0010020B20100205801002092 +:103DD000E80700205C000020600000200A000020AE +:103DE00035FA8E3C00002041294606F045FD554637 +:103DF000514606F07DFD06F0D5FDA8F800004446CA +:103E00005846314606F03EFD06464846009906F003 +:103E100039FD314606F0DEFC294606F069FD06F064 +:103E2000C1FD6080386C8047FEF7DDFCFEF767FC63 +:103E3000BDE8F84FFEF7B7BCBDE8F88F03484178FE +:103E4000002901D00021417070470000700A002055 +:103E50002DE9F843FE4CFF4BFF490026B4F8EE2055 +:103E60009846A1F1100004F0EAFB08B101260EE02B +:103E7000B4F8EE10F84804F0F1FD40B9B4F8EE10D3 +:103E8000F54803F082FD10B9032004F05FF8F34D0C +:103E90005FF0000794F8ED0006283CD2DFE800F060 +:103EA0000707192833030220FDF7FBFC33E08DF8E8 +:103EB00000704FF44870E849ADF8020010396846C8 +:103EC00002F085FF08B10120287094F8ED00012868 +:103ED00021D06EB1E049B4F8EE204346A1F11000C4 +:103EE00004F0ADFB0220287094F8ED0002281DD0EC +:103EF000D948103804F0ACFC28B10320287094F89D +:103F0000ED00032812D0D448103805F02EFB10B174 +:103F1000042028700AE0287840B994F8ED0010B128 +:103F200084F8ED70B6E70220FDF7BBFCCA481030FC +:103F300004F097FE38B9C848103002F0EFFF10B90E +:103F40000420FDF7AEFC0220FDF79EFC28B1C2491B +:103F500094F8E300103909688847BF4914F8E20F64 +:103F600009688847A07803F0F3F810B90820FDF736 +:103F700098FCBB486421B0F9262092FBF1F001FBCC +:103F8000102406B20820FDF77FFCB64D90B1204604 +:103F900006F0FAFCB44906F075FC0446304606F01B +:103FA000F3FC214606F016FCB04906F06BFC2860D5 +:103FB000BDE8F8832F60FBE770B50546A44890F88C +:103FC000060106F0EAFC0446284606F0E6FCA8498D +:103FD00006F058FCA74906F08BFC214606F052FC7F +:103FE00006F0F9FC80B270BD70B500252C460020AB +:103FF00002F04AFE05440A2003F0FEFE641C202C59 +:10400000F5D3C5F34F10FFF7D7FF914A022192F87D +:10401000073100BF03FB01F4844202D8491C062982 +:10402000F8D39548017092F80801484393490880F5 +:1040300070BD2DE9F05FDFF82492914E884FB9F8FA +:104040000220834C0025C2B38E4900204FF4C8786B +:10405000424501D141F8205051F8203036F910C0C6 +:10406000634441F8203026F8105004EB4003401C14 +:10407000A3F8FA500328EBDB012A19D10868C830ED +:1040800090FBF8F024F8FA0F4868C83090FBF8F07D +:1040900060808868C83090FBF8F1B9F80600081A0B +:1040A000A0803D850121FA3C7D850846FDF727FA71 +:1040B000B9F80210491EA9F802100420FDF7F9FB17 +:1040C000002874D0704BDFF894816E491A8808F18B +:1040D00020080C31A8F1180A322A05D0F2B30020CA +:1040E0009B46322A14D015E034F8FA0FA8F80000E5 +:1040F0006088A8F80200A088A8F80400B7F828C0D3 +:10410000AAF800C0B7F82AC0FA3CAAF802C0E6E74D +:1041100041F8205051F8203036F910C0634441F87E +:10412000203026F8105004EB4003401CA3F8FA504E +:104130000328D6DB012A1AD15448554B05800120AB +:104140001880544B02201870B8F8000024F8FA0FB9 +:10415000B8F802006080B8F8040000E00AE0A0802F +:10416000BAF800303B85BAF80200FA3C7885521E56 +:10417000ABF8002048480288012A18D105800A6857 +:10418000322092FBF0F224F8FA2F4A6892FBF0F208 +:104190006280896891FBF0F1B9F80600081AA080E6 +:1041A0003D850121FA3C7D850846FDF7A8F9308858 +:1041B00034F8FA1F401A308070886188401A708085 +:1041C000B088A188401AB080BDE8F09F224810B5A1 +:1041D000103841682A488847BDE8104029E730B5C3 +:1041E0001E4C1F4AE06892F82F200146401C824274 +:1041F00000D10020294A1368224A183242F821309F +:10420000274952F820200D682B449A1A0A60E06072 +:1042100030BD70B52348114C00682169411A01D5A1 +:10422000002070BD20610C4D6069103578B128699F +:1042300080476868804728882169084420616A6946 +:1042400019491648904700206061022070BD2DE09A +:104250006C040020EC0800204C0C00207C010020A5 +:10426000E8070020300000208988883C00002041B9 +:104270003333534000F07F4568010020EE000020FA +:104280007A0000201C0B0020DA000020E000002053 +:10429000DC000020C8000020DE000020A00000207C +:1042A0001C000020FC000020A4000020A86880471B +:1042B000E8688047FFF793FF012060616888216903 +:1042C00008442061012070BD2DE9F05FA24DA8884F +:1042D00000286AD0DFF884820024A3464FF47A795C +:1042E000A8F10C06A888484507D104EB840208EB26 +:1042F000820146F824B0C1F810B0994F56F8241046 +:1043000037F91400014446F8241006F03DFB01463D +:1043100004EB840208EB8200824600F0EFF827F8F5 +:1043200014B0904F27F814B0A888012837D1DAF8D4 +:104330001000012808DD401E06F026FB0146DAF8D1 +:104340000C0006F0D5FA00E0002007F011FE8246CE +:10435000854890F8F800A8B106F01FFB514606F01A +:104360004FFB0FD27D49A5F80490C8F810B0C1F8F2 +:1043700024B0C1F838B0C6F808B0C6F804B0C6F822 +:1043800000B00CE056F82400012200F5FA7090FB12 +:10439000F9F027F814000F210A20FEF787FC641CAF +:1043A000032C9FDBA888401EA8806D496D4A002021 +:1043B00031F8103032F810401B1B21F81030401C2F +:1043C0000328F5DB00E7654810B54C3041686448C8 +:1043D0008847BDE8104077E710B5644810240460B2 +:1043E00002F005FF6148001F04605B49012048702E +:1043F00010BD2DE9F0415E48574C0068A169411A93 +:1044000002D50020BDE8F0815A490844A0615A480D +:1044100002F0B5FEDFF864C14F4B00269CF80E0099 +:104420005549514A26339D1D88B1A069E06100209D +:1044300002EB4007A7F8006131F8107023F8107004 +:1044400025F81070401C0328F2D38CF80E606078B9 +:1044500070B10888B2F80071C01B08804888B2F8B3 +:104460000271C01B48808888B2F80471C01B888024 +:10447000E06998B3A769381A414FB84218D23B484F +:104480000838026882F008020260002031F910202A +:1044900033F91040A24201DA23F8102035F9104018 +:1044A000A24201DD25F81020401C0328EED315E0C0 +:1044B0000020E66133F9101035F91040214402EB79 +:1044C000400401EBD17141F34F01401CA4F80011ED +:1044D0000328EFD301210846FDF711F8012091E7E9 +:1044E00010B5012004F001FA1020FDF7D5F9254997 +:1044F0000020086010BD234804F04BBA2DE9F041BC +:10450000044600690E46401C206101281FD006F0B9 +:104510003BFA256880462946304606F0ADF9074645 +:10452000414606F0E5F9294606F054F90546606073 +:104530002946304606F0A0F90146384606F0A2F9B1 +:10454000A16806F047F92560E060A0605AE7666060 +:1045500000202660F9E700007C010020000C00200C +:1045600074000020A80000206C040020140C0140FE +:10457000FC000020A086010086000020700A0020B8 +:1045800080C3C901B000002070B5FB4CFB4EC1B226 +:104590000546A170306805F009F8E079A178484037 +:1045A000E071C5F30721A170306804F0FFFFE079E6 +:1045B000A1784840E071C5F30741A170306804F06C +:1045C000F5FFE079A1784840E071290EA1703068CC +:1045D00004F0ECFFE079A1784840E07170BD70B55F +:1045E000E54CE64EC1B20546E170306804F0DEFFEE +:1045F000E079E1784840E071C5F30721E170306867 +:1046000004F0D4FFE079E1784840E07170BD10B566 +:104610000446DA482146006804F0C8FFD648C1794C +:104620006140C17110BDD44AD548117A405C491C23 +:104630001172704700B5FFF7F6FF0346FFF7F3FF6F +:1046400003EB002080B200BD10B5FFF7F3FF044676 +:10465000FFF7F0FF04EB004010BD70B504460D46B7 +:104660002420FFF7D4FF4D20FFF7D1FF0CB121200C +:1046700000E03E20FFF7CBFFBF4C0020E071284652 +:10468000FFF7C5FF607ABDE87040C0E70146002033 +:10469000E3E701460120E0E7B748C079B7E770B526 +:1046A00004460D460846FFF7F1FF03E014F8010B3E +:1046B000FFF7ADFF2800A5F10105EDB2F6D170BD01 +:1046C00010B5044603E000BFFFF7A1FF641C20788B +:1046D0000028F9D110BD2DE9F05FDFF89CB2DFF8BA +:1046E000989201274FF0000A0BF10C0B00251AE0FD +:1046F000A3481438405D00EB40010BEB8108D8F86B +:10470000040006F03AF806460FB1B2440AE000246D +:1047100006E000BFD8F80400005DFFF778FF641CD6 +:10472000B442F7DB6D1C99F800008542E0DB002FF6 +:1047300005D00AF0FF00FFF7A9FF0027D6E7BDE884 +:10474000F09F70B50246032300218E4803F0D4FC8D +:104750008A49FF2208608A481421143805F0C7FFEF +:10476000874D0020143D012428700220FDF78CF8AD +:1047700020B1012068700220A87003240420FDF7F6 +:1047800083F850B103202855641C4FF40050FDF706 +:1047900090F810B104202855641C0220FDF774F82D +:1047A00018B90820FDF770F840B105202855641CA1 +:1047B00006202855641C07202855641C2020FDF77E +:1047C00078F810B108202855641C4FF48070FDF76C +:1047D00070F828B10A202855641C0B202855641C49 +:1047E00069484079082801D00E2802D10C202855AC +:1047F000641C0D202855641C0420FDF75AF810B1E4 +:1048000011202855641C132028555B48641C047033 +:1048100070BD2DE9F05F584EDFF864B14FF000082D +:10482000717A594D594C5A4FC1464FF0010AABF1BC +:10483000140B782978D011DC3046A1F1640100789E +:1048400014293BD2DFE801F0FCFBFAF9F8F7F6F5A2 +:10485000F4F3F2F1F0EFEEEDECEBEAE94C48CF299E +:10486000407871D014DCCA295FD008DCA0296CD054 +:10487000A4296BD0C82927D0C9291FD138E0CB295A +:1048800065D0CC2971D0CD2970D0CE2916D17BE34B +:10489000D4296CD00ADCD0296AD04FF00008D12985 +:1048A00067D0D22966D0D32908D1DFE0EF2918D00C +:1048B000F02960D0FA2979D0FE2978D00020FFF7BE +:1048C000E8FEBDE8F05FE7E60024324DFFF7B2FEF8 +:1048D00025F81400641C082CF8D30020FFF7D6FE3E +:1048E000EFE7FFF7A7FE6085FFF7A4FE2085F4E75A +:1048F000FFF799FEF872FFF796FE27490870FFF759 +:10490000A3FE264C2060FFF79FFE6060FFF792FE3B +:1049100023490880FFF78EFE22490880224801784B +:1049200041F002010170D8E761E10023FFF77BFE4F +:10493000E5186870FFF777FEE872FFF774FE5B1CFE +:1049400068750A2BF2D3C8E749E04BE35CE3002526 +:104950005F4606E0FFF76EFE795D6D1C04EB4101DA +:10496000C88730788542F5D3B7E721E005E358E101 +:10497000FDE2C9E26BE02BE3B4010020DC0800207B +:10498000880C0020003801406C040020E80700205B +:10499000700A0020800A0020D30000204C01002073 +:1049A000760100207801002064010020F1E2F2E2AB +:1049B000FFF739FE04F81F0FFFF735FE6070FFF7B1 +:1049C00032FE2071FFF72FFE6071FFF72CFEA07101 +:1049D000FFF729FEA070FFF726FEE0707DE7FFF7E6 +:1049E00029FEFFF727FEE93525F8190CFFF72CFE05 +:1049F000FFF720FEA4F8AE00FFF71CFEFFF724FE31 +:104A0000FFF718FE00EB80004000E084FFF70BFE8C +:104A10006877FFF708FEE87713E0D2E150E2B3E1F0 +:104A2000CCE10CE2DAE1B6E19CE183E174E16AE118 +:104A300051E13EE120E111E10BE1D5E0A1E028E008 +:104A400018E0FFF7F0FDA877FFF7EDFD45E7002838 +:104A50008AD1FFF7E8FD85F87803022801D985F8A7 +:104A6000788300210020FCF74AFD36E7FFF7E2FDDE +:104A7000F94987E20720FFF709FEE620FFF7C7FDA7 +:104A80006879FFF7C4FD0020FFF7C1FD4FF000403B +:104A9000B7E20B20FFF7FAFDF048008800B2FFF7FD +:104AA0009EFD02F0AEFE00B2FFF799FD0220FCF77A +:104AB000EBFE04460420FCF7E7FE44EA400408202D +:104AC000FCF7E2FE44EA80042020FCF7DDFE44EA25 +:104AD000C0041020FCF7D8FE44EA0010FFF77FFD69 +:104AE000F9783A79490041EA8201BA79002041EA2D +:104AF000C2017A79367841EA42117A7AD44641EA9B +:104B00008211D74AD37941EAC311137A41EA0321CA +:104B1000537A41EA4321FB7941EA83213B7A41EA16 +:104B2000C321BB7A41EA0331537B41EA4331937B92 +:104B300041EA8331137C41EA0341137941EA0311CD +:104B4000537C41EA4341937CD27C41EA834141EA70 +:104B5000C24479785F460C43002208E0BB5C0CFA43 +:104B600003F3234202D00CFA02F10843521CB24272 +:104B7000F4D3FFF709FD95F8780300BFFFF747FD71 +:104B80009FE61220FFF782FDB648B74D4FF00004B4 +:104B90000088B0F5806F0BD935F91400C11700EB10 +:104BA0005170C010FFF71BFD641C032CF4D306E00A +:104BB00035F91400FFF713FD641C032CF8D3AB4D3B +:104BC000002400BF35F91400FFF709FD641C032C15 +:104BD000F8D3A74D002400BF35F91400FFF7FFFC00 +:104BE000641C032CF8D36CE61021A24833E0382073 +:104BF000FFF74CFD5FF0000504EBC50636F96C0FBE +:104C0000FFF7EDFCB6F90200FFF7E9FCB6F9040086 +:104C1000FFF7E5FCB079FFF7FAFC6D1C082DEBD32C +:104C20004FE60020FFF732FD5FF00005FFF702FDC1 +:104C300004EBC50626F86C0FFFF7FCFC7080FFF74D +:104C4000F9FCB080FFF7EFFC6D1CB071082DEDD3BF +:104C500037E610218848FFF722FD32E61020FFF7E3 +:104C600015FD864D002400BF35F91400FFF7B7FC91 +:104C7000641C082CF8D324E61020FFF707FDF87A0F +:104C8000FFF7C5FC7E480078FFF7C1FC7D4C20682B +:104C9000FFF77AFC6068FFF777FC7B48008800B27A +:104CA000FFF79DFC7948008800B2FFF798FC784830 +:104CB0003DE00520FFF7EAFC7648008800B2FFF7E8 +:104CC0008EFC7548B0F90000FFF789FC7348007846 +:104CD00000F0010052E70820FFF7D8FC704D0024D7 +:104CE00035F91400FFF77BFC641C022CF8D36D48E7 +:104CF000B0F90000FFF773FC6B48B0F9000000BF8B +:104D0000FFF76DFCDDE50620FFF7C0FC6748006893 +:104D1000FFF73AFC66480AE00520FFF7B7FC654854 +:104D20000078FFF774FC0020FFF759FC6248008808 +:104D300000B2E5E70720FFF7A9FC14F81F0FFFF703 +:104D400066FC6078FFF763FC2079FFF760FC607910 +:104D5000FFF75DFCA079FFF75AFCA078FFF757FC3E +:104D6000E0780BE71E20FFF791FC002566197078AC +:104D7000FFF74DFCF07AFFF74AFC707DFFF747FC28 +:104D80006D1C0A2DF2D39CE52F20FFF77FFC4B48CA +:104D9000FFF796FC95E54006000EFFF777FC00252F +:104DA0005F4607E0785D04EB4000B0F93E00FFF796 +:104DB00016FC6D1C30788542F4D382E5FFF78BFC3E +:104DC0007FE5FFF763FC00245D4603E0285DFFF705 +:104DD0001EFC641C30788442F8D372E51620FFF77D +:104DE00055FC0020FFF7FBFB35F9D00FFFF7F7FB71 +:104DF000B5F90200FFF7F3FBB5F90400FFF7EFFB8D +:104E0000B4F9AE00FFF7EBFB0020FFF7E8FB002052 +:104E1000FFF7BAFBB4F926000A2190FBF1F000B2CB +:104E2000FFF7DDFB95F83600FFF7F1FB95F838004A +:104E3000FFF7EDFB95F83700FFF7E9FB62E008208C +:104E4000FFF724FC0024601CC0B2FFF7E0FB641CE9 +:104E5000082CF8D335E50000B2010020D400002072 +:104E6000C60A002082010020800000206800002087 +:104E700086000020B6000020F0080020800A0020F4 +:104E8000D30000204C010020760100207801002092 +:104E900066010020720100207401002064010020DE +:104EA00034000020B0010020E60000205C0000205B +:104EB0002C000020D2000020EA000020E8CD0008ED +:104EC000FFF7B1FB04461220FFF7E0FB14B1102CF2 +:104ED00002D004E0954800E09548D0E900892046DA +:104EE000FFF795FB4046FFF74FFB4846FFF74CFBAB +:104EF00090480068FFF748FB0020FFF770FB002098 +:104F0000FFF76DFB002039E6FFF78DFB8446FFF7C6 +:104F10009BFB0546FFF798FB0646FFF795FB04460B +:104F2000FFF788FBFFF786FBFFF77DFBBCF1000F67 +:104F300011D0BCF1100F7FF4DAAC7D49C1E9005605 +:104F40000CB17C4804607C4A0220091D107078482E +:104F500001F01DF8C1E47548002CC0E9005687F83F +:104F6000078087F80CA0F5D072480460B5E40028EB +:104F7000F0D10120FCF779FCAFE40028EAD16F49B9 +:104F80004FF4C8700880A8E40028E3D187F80EA089 +:104F9000A3E4012166E50820FFF778FB68486A4A28 +:104FA0006A4D016867481268B1FBF0F1B2FBF0F09E +:104FB00000EB4002C2EBC01001EBC000E88000240F +:104FC00035F91400FFF70BFB641C042CF8D378E4CC +:104FD0000420FFF75BFBB4F92A00FFF700FBB4F9EC +:104FE00028008DE60C20FFF751FB59480068FFF7B9 +:104FF000CBFA5748001D0068FFF7C6FA544808303E +:105000000068FFF7C1FA5CE4524D29780AEB810091 +:10501000C0B2FFF73BFB2878FFF7F9FA00244E4EA9 +:105020004E4FDFF83C81DFF83C910EE0305DFFF73A +:10503000EEFA385DFFF7EBFA18F80400FFF7E7FA2D +:1050400019F80400FFF7E3FA641C28788442EDD3D2 +:1050500037E470B5444C454E0025607810B3BDE888 +:105060007040FBF75DBF306804F0B3FAA17951B12D +:1050700001291CD002291FD0032923D0042929D0BB +:1050800005293FD12CE0242803D00021A17149B982 +:1050900001E00121FAE7232802D0522832D102E0B0 +:1050A000FBF73EFF2EE0012002F071FF2AE04D28C1 +:1050B00004D10220A07125E03C2801D00020F9E7AE +:1050C0000320F7E740281CD8607125712572E07134 +:1050D0000420EFE76072E1794140E1710520E9E7E2 +:1050E00021796279914207D2E2794240E271204A05 +:1050F0005054491C217105E0E179814201D1FFF74B +:1051000088FBA571306804F061FA0028ABD16078A3 +:10511000002809D14FF40060FCF7CBFB002803D036 +:10512000BDE8704001F0E3B970BD000054010020FB +:105130005C01002060000020C90000207E010020EA +:105140000804002040420F000C0400206A010020E7 +:10515000E8F7FF1F7A010020DA0A0020EA0A00209F +:10516000FA0A00200A0B0020B4010020DC0800200D +:10517000880C002044F25061884201DDA0EB410020 +:10518000FE49884202DA48F6A041084470472DE9FA +:10519000F04706465068994614460D46301A05F009 +:1051A000F3FB296805F0A4FB2061A768394605F0E8 +:1051B00063FB8046F24890F8B80005F0EEFBF14939 +:1051C00005F060FB01464FF07E5005F091FB2D6825 +:1051D000294605F0FFFA0146284605F089FB4146BD +:1051E00005F050FB394605F0F5FA2061C4E901608D +:1051F0000146D9F8080005F045FBBDE8F04705F089 +:10520000D1BB2DE9F0411D4614460E4605F0BCFB0E +:10521000696805F037FB316805F034FB216805F05B +:10522000D9FA2060ED680746284605F0BBFB064624 +:1052300085F0004005F0B6FB0546384605F0B2FBA8 +:105240003246294601F082FA05F09EFB2060BDE857 +:10525000F04105F0A7BB70B5CB4CD4E90D01401A65 +:10526000FFF788FF0028D4E90D01A0EB010002DD63 +:10527000FFF780FF02E0FFF77DFF404241F294110B +:10528000884228DAD4E90D01401A05F07DFBBF49B8 +:1052900005F0F8FA0646E06B05F07FFB0546304660 +:1052A00006F0A0FD294605F0EDFA05F07BFB00B203 +:1052B00040F6B8322082514201F048FA616B08444E +:1052C00048F6A0416064884200DD401A002800DAF8 +:1052D0000844606470BD606BFBE72DE9FE4F054636 +:1052E000FFF7B9FFA84842F22831406C081A05F0D0 +:1052F0004BFBA64905F0C6FA044606F08DF901906D +:10530000204606F06FFD00900024284605F03CFB87 +:10531000DFF874A2DFF87892DFF878B20AF1300A89 +:10532000029099481A3030F9140005F02DFB05461B +:105330005DF82410029805F0A5FA294605F09CFABC +:1053400005F030FB00B24FF47A7255462AF814008B +:10535000514201F0FBF98E4900B225F81400603982 +:1053600000F03CFE04EB8406894B8749074609EBB5 +:105370008602904635F91400603B2831FFF741FF63 +:10538000834B81490744424635F91400603B28317C +:10539000FFF7FDFE384400B240F6B8325D462BF808 +:1053A0001400514201F0D2F925F81400784859F858 +:1053B00026102838641C40F82610022CB1DBBDE80A +:1053C000FE8F2DE9F05F704E0024DFF8C491503657 +:1053D000DFF8C0B1A6F1360AA9F128096C4956F8E0 +:1053E0002400803900F0FAFD3AF81410664F401A94 +:1053F0003037674900B227F81400703900F0EEFD2D +:10540000054637F9140056F8241004EB84070844C5 +:105410005F4B5D4909EB87029046703B2831FFF7EF +:10542000F0FE28445A4B58492BF814005D4642467A +:1054300056F82400703B2831FFF7A9FE4FF4FA62BA +:10544000514201F083F93AF914103131622900D840 +:10545000002035F8141040F6B832084400B225F8A0 +:105460001400514201F072F925F81400484859F827 +:105470002710641C40F82710022CAFDBBDE8F09F1A +:1054800070B50546086819681446401A05F07CFA9C +:105490003D49C96A05F0F6F905F084FA01463A4833 +:1054A0005030416029682268891A016070BD2DE979 +:1054B000F0410F46DDE90685116800681E46081AAE +:1054C00005F062FA044630683968401A05F05CFA63 +:1054D0002D49C96A05F0D6F90646014605F0D2F90C +:1054E00007462146084605F0CDF9394605F072F920 +:1054F00006F03EFD284905F0C5F905F06CFAC8F83C +:10550000000084F00040314605F05CFF234905F0BF +:10551000B9F9234905F05EF905F044FA286000283E +:1055200003DA48F6A04108442860BDE8F0812DE97F +:10553000F0471C48144CD0E90056617804F1480942 +:1055400091B34FF07E50A16A05F0D2F98246D9F8A6 +:105550000400301A05F018FAE16A05F093F9514693 +:1055600005F090F905F01EFA07B2D9F8000004F131 +:105570001A08281A05F008FA514616E0B0B9FFFFDC +:10558000E8070020DB0FC940BC020020D3023739F6 +:10559000680D0020280100202C7D8E3FA00CB34513 +:1055A00000A00C464C0100201AE005F06BF905F054 +:1055B000F9F901B204F12400B0F902203A4402EBF7 +:1055C000D27242F34F02A8F80220B0F90030194419 +:1055D00001EBD17141F34F01A8F800104280018026 +:1055E00001206070C9E90056BDE8F08710B5044697 +:1055F00005F0CAF9002C01DC80F00040F74905F005 +:1056000077F9F74905F03EF906F006F8F549C86262 +:1056100010BD10B5F44CE07A002811D0F3480078A2 +:1056200005280DD3F249F34A0868106049685160B3 +:10563000FFF7DCFFF048EB490088888201202073E7 +:1056400010BD2DE9F043E749EC48E74B8E7A012580 +:1056500002790024062E29D004DC022E09D0032E64 +:1056600004D116E0122E33D0302E3DD00020BDE8FC +:10567000F083DF4A466856608668166000694FF41A +:105680007A7290FBF2F0DE4A1080C87AD8724D73BD +:1056900051E04079C00701D0032A03D00020C8722E +:1056A00010B148E00120FAE7DC7244E0C27AD20788 +:1056B00002D0827A032A03D00022CA7212B102E019 +:1056C0000122FAE7DC72C94A90F82F00107032E02C +:1056D000CC4B828A1A80806942F2107290FBF2F001 +:1056E000C94A10808D7326E0C84B102A1A7001D960 +:1056F00010221A700022C64EC64FDFF81CC3DFF816 +:105700001C931D7815E000BF02EB420300EB8303FE +:1057100093F8088006F8028093F8098007F8028061 +:1057200093F80B800CF8028093F80C8009F8028043 +:10573000521CAA42E8DB487B8A7B104097D04C730E +:105740008C73012093E72DE9F041A64900240A4615 +:1057500091F809E092F807C0157A0CEB0003D78A9C +:10576000DEB22246BEF1090F51D2DFE80EF0080585 +:105770000F151C2333434900622803D04A72B52811 +:1057800002D044E0022033E0012031E003224A72DB +:105790000873C87108723AE004224A72CE71721915 +:1057A0000A72887233E005224A72CE7172190A7247 +:1057B000C8822CE006234B72731907EB0020CE71D0 +:1057C00080B20B72C882B0F5007F01D9CA824A72DA +:1057D0000A831CE0CE7172190A720A8BC82A01D2A0 +:1057E000864B9854521C90B20883B8420FD10720C0 +:1057F00048720CE008234B72844508D04A7206E0D8 +:105800004A72854203D1FFF71CFF00B101242046F4 +:105810008BE670B5034600200246054611E02E2CAB +:1058200004D1521C00290FD054181D559C5C00EB6C +:1058300080004000A4F13006092E01D83038204401 +:10584000521C9C5C002CEAD170BD2DE9F041002671 +:10585000804635463746044604F00AFF016800E0FA +:10586000641C2078085C2028FAD0404609E01EB16C +:1058700006EB86025206160E10F8012B303E32441B +:10588000D6B2221A022AF2DC09E01DB105EB85022C +:105890005206150E10F8012B303D2A44D5B2844231 +:1058A000F3D820782E280ED1641C002007EB870245 +:1058B000570022788B5C202B02D1303F1744641CA8 +:1058C000401C0428F2DB56480621454307EBC7007D +:1058D00000EB071005EB8000B0FBF1F051494E439F +:1058E00000EBC61021E62DE9F04700273D4C0546A8 +:1058F000242815D0414E2046F03EC0782C2D13D0E0 +:105900002A2D11D021460D2D497964D00A2D62D05F +:105910000F2802D23554401CE07000295CD0BAE058 +:10592000A770E7702771B6E03754A0784FF00109EF +:1059300028B1A179012921D002294ED0A2E0A77176 +:105940003078472807D17078502804D1B07847289C +:1059500002D0522809D095E0F078472804D1307958 +:10596000412801D184F806908CE0F0784D2804D1CC +:105970003079432801D10220A07183E0DFF87080E4 +:1059800002280CD003280FD0042816D0052819D0DF +:10599000062849D0072850D0092855D072E017486A +:1059A000F038FFF752FF05E0307853286AD1D8F875 +:1059B00000004042C8F8000064E01048F038FFF7EB +:1059C00044FF05E0307857285CD1D8F80400404205 +:1059D000C8F8040056E063E05AE03BE08096184BBC +:1059E00035FA8E3CBC020020700A0020D300002053 +:1059F0004C01002054010020B0010020B80D00200F +:105A00007601002078010020660100207A01002044 +:105A1000DA0A0020EA0A0020FA0A00200A0B002015 +:105A200040420F002D3101003078302801D901208B +:105A300000E00020FE49C87224E00021FD48FFF785 +:105A4000E8FEFD4908701DE00021FA48FFF7E1FE7D +:105A5000FA4916E0072802D008280DD012E00121EB +:105A6000F448FFF7D6FE41F2184148434FF47A71EB +:105A7000B0FBF1F0F24904E00121EE48FFF7C9FE66 +:105A8000F0490880A078401CA070E7702A2D04D04F +:105A90002079684020710020A6E584F80590FAE797 +:105AA0000029F8D0307800F0C7FA0501707800F0CE +:105AB000C3FA28442179C0B288426771EBD1A0793A +:105AC0000128E8D190E52DE9FF5FDF49C0B291F8E8 +:105AD0001C1119B1012904D002297CD1FFF703FF61 +:105AE00001E0FFF730FE002875D0D24C1034A068DA +:105AF000E06002F072F9A0602020FBF7CDFED348F1 +:105B00004FF0000B0178012910D001210170C84825 +:105B1000C17A00295FD0C849097805295BD382463C +:105B2000407830B19AF80C1031B108E080F800B03C +:105B3000EDE78AF80CB002E008B1FFF76AFDC4484F +:105B400005218E460278C44C521CB2FBF1F301FBD6 +:105B50001322C0490270002091F90090BC4954F80A +:105B600020306831BA4D41F82030BC49783593FB7C +:105B7000F1F145F82010BA4D00EB80074D4303EBDF +:105B8000C51342F2107593FBF5F5AEB2B04D40353A +:105B900025F81060A74DC83505EB8707AC4D57F8C1 +:105BA00022C0603555F8208047F82230A8EB0C0C55 +:105BB000634445F8203093FBFEF3A94D6D426943E1 +:105BC00003EBC111A24B7033B9F1010F43F8201060 +:105BD00007D1B61E00E080E0B6F5797F01D844F821 +:105BE0002010401C0228B9DB02F0F7F8984D296A12 +:105BF000401A04F0D2FE9B4904F07AFEA86202F03B +:105C0000ECF82862A86A4FF07E51884200DB084613 +:105C1000A86203A902A8944BCDE900011A1F211D17 +:105C20008D48FFF744FC02986426B0FBF6F08F49DC +:105C30008F4A57460880039890FBF6F010809AF838 +:105C40000C0018B9A1F800B0A2F800B0FFF76FFC83 +:105C5000387A10B9F87900283FD07D49343101F104 +:105C6000080000F11C07CDE900013B1D3A46211D4B +:105C70007948FFF71CFC231D774A391D3846FFF78A +:105C8000FFFB744C94F90000012828D0022824D18D +:105C9000784F0121B7F9BE0000F0ABF9FFF71DFB0B +:105CA00097F8BA00744A18B1686C90FBF6F010804F +:105CB000B7F8B600E96B88420BD2D5E90D01401A5E +:105CC000FFF758FA002800DC404242F21071884287 +:105CD00003DD01202070A88A1080BDE8FF9FFFF738 +:105CE00070FBFAE72DE9F047624C607904F055FE4D +:105CF000DFF88891494604F0FBFD4E4D20352860C1 +:105D0000E07B04F04AFE494604F0F2FD5C4EEE6092 +:105D10006860A07904F041FE5A4F394604F0E8FD6E +:105D200010352860207C04F038FE494604F0E0FD80 +:105D30006860A07E04F031FEDFF82881414604F05F +:105D4000D7FDC5E90206E07904F027FE394604F0E4 +:105D5000CFFD10352860607C04F01FFE494604F03A +:105D6000C7FD6860E07E04F018FE414604F0C0FD07 +:105D7000C5E9020638E42DE9F0412E4C0646103400 +:105D80000027032527704FF48070FBF792FD002851 +:105D900019D0667002F021F8C4E901702A4890F821 +:105DA0001C0100B90125FFF79DFF374906EB4600AE +:105DB0002B4651F820203549354802F09DF93549E8 +:105DC00048600120207023E52DE9F041194C03279C +:105DD00010341D4A60782F4D00EB400192F81C31C1 +:105DE000294E686813B1012B1ED105E056F8211029 +:105DF00003F0F2FB27700BE52378012B4CD056F80B +:105E0000211003F0E9FBDFF88080002608F13C0850 +:105E1000686818F8061003F0C9FB042001F0ECFFD5 +:105E2000761C8C2EF4D3277000206060F0E4000014 +:105E3000700A0020C80C0020D3000020760100204A +:105E400078010020660100206C040020640100201D +:105E5000BC020020C90000204C0100208096980060 +:105E6000D3CEFEFF00007A445801002072010020CA +:105E700074010020E8070020B20100200000C842A1 +:105E80000000FA440000204118CE0008C75A00085C +:105E900000440040DC0800200027904607EB470044 +:105EA00056F82010686803F097FB98F91D0100EB85 +:105EB000400006EB80004168686803F07AFBC82068 +:105EC00001F09AFF7F1C052FE8DB98F81D01607038 +:105ED00002202070A8E710B55E4C207805282AD251 +:105EE000DFE800F02903031C0600BDE810406BE763 +:105EF00060680521401C60606078401CC0B2B0FB47 +:105F0000F1F201FB1200607001F067FF5249A060DE +:105F1000002008705149C87201200BE001F05DFFBC +:105F2000A168401A40F6C411884204D92020FBF72A +:105F3000B8FC0420207010BD2DE9F05FDFF814A13B +:105F40000024474FDFF81C81DFF81C910AF1400A5A +:105F500025460AF1280B00BF27F8145028F81450E2 +:105F600004EB840629F814500AEB860000F06DF863 +:105F70000BEB860000F069F83648903000EB8600A5 +:105F800000F063F8641C022CE6DBBDE8F09F7CB5F2 +:105F9000364C02682260096861600068FFF726FBE2 +:105FA000A4F1240101F10800314ECDE90001231DC7 +:105FB0002246311D3046FFF77AFAA4F15805331D09 +:105FC000686B68643246211D2046FFF759FA686BFA +:105FD000A8632848B0F8BC0068827CBD10B50C46A8 +:105FE00004F0D2FC216804F04DFCBDE8104004F040 +:105FF000D9BC70B51D4C583CE26B21B1B0EB520FCF +:106000000BD3500809E0904200D31046194900B262 +:10601000B1F8BC10814200DB0846B4F9125000B25E +:10602000A84208DD1449A06A04F02CFC04F0BAFC74 +:10603000284400B2608270BD3038C0B2092801D94E +:10604000C01FC0B200F00F00704700210160416026 +:1060500081607047D80C0020D3000020700A002017 +:106060000C0100202C010020280100201403002036 +:106070004C010020E80700200000C842F0B5404A6B +:10608000404C1178E9B192F805C01779032104F169 +:106090001C035E1816F8015CFD4005F00F05072D86 +:1060A00009D213F801E016F8016C06EA0C060EEBB3 +:1060B000062644F82560891CC9B21029E9D30021BD +:1060C0001170314907280ED2937863B151782E4A66 +:1060D000104490F80A0149B154F820004FF4777148 +:1060E00001EB500006E0B1F81401F0BD34F82000D7 +:1060F00000F5777080B2F0BD70B5214C01260546E1 +:10610000A67001F050FEA168421AC4E9020241F2F1 +:1061100088300021824200D9E1701A4AE0781C32AE +:1061200015540F2802D0401CE07070BD174826702F +:10613000018070BD70B504461348114990F81221D2 +:10614000032007252AB1012A08D108714D710120C9 +:1061500003E002220A7148710020487001234FF4C5 +:10616000E1320B490B4801F0C7FF01460A48C16004 +:106170000CB10A492160457470BD01480078704730 +:106180003C030020800E00206C040020D60000207C +:10619000F960000800440040DC0800207D60000831 +:1061A00070B57C4C06460125207880B901F015FEBB +:1061B000A1683231884207D32570012001F027FE03 +:1061C00001F00BFEA06070BD20780028FBD001F02C +:1061D00004FEA16831448842F5D30020207001F00C +:1061E00016FE01F0FAFD6C49A060087808B1401E67 +:1061F0000870657070BDF8B5664D8DF800008DF8BB +:1062000001108DF802208DF80330A8791DF80010D8 +:1062100044292DD04C2929D04D2925D04E292AD0CA +:1062200032240026032806D274B12046FFF7B8FFB7 +:10623000A879032808D301F0D0FDA968001B884283 +:1062400002D95548AE7106706878012801D0002C3B +:1062500009D1A879032801D2401CA8716E702E7054 +:10626000002001F0D4FDF8BD6424DAE7C824D8E7A3 +:106270004FF4FA64D5E70024D3E72DE9F047DFF8BF +:106280001CA10546434C9AF80D004FF00109002669 +:1062900010B184F8029000E0A6704FF40070FBF794 +:1062A00008FB3F4F18B33F493F484FF0020C91F8AD +:1062B000AC30B0F9000003EB830282420FDA97F8AA +:1062C0000180B8F1000F0AD084F8049091F8AD1065 +:1062D000194401EB8101814201DA84F804C0824251 +:1062E00003DA797809B984F804C000B9267120204E +:1062F000FBF7CAFA40B19AF80A1011B99AF80B00E4 +:1063000008B1F87AA8B1E6702079022814D00128E3 +:1063100017D0E078012817D0A078012817D0042DD5 +:1063200019D0022D1ED0012D1ED0607901281ED05B +:1063300022E084F80390E7E74E22442311464C20E4 +:106340000DE04D234C2208E04D234E2201E04D2369 +:106350005322532102E044234D224D215320BDE816 +:10636000F04748E7442305E044234E22F5E77878D8 +:1063700010B14E234D22ECE70748007818B1BDE874 +:10638000F04732200CE72670BDE8F047002001F00E +:106390003EBD00004C030020C8000020C60A0020BB +:1063A000700A0020E8070020D600002010B5D84C65 +:1063B0005E28A26807D05D280CD001461046BDE8D3 +:1063C000104003F0F3B85D21104603F0EFF83E21D2 +:1063D000A068F4E75D21104603F0E8F83D21A068CD +:1063E000EDE72DE9F041132000F04AF9C94C20688F +:1063F000002800DC4042C84D90FBF5F000B200F0F0 +:1064000051F91B2000F03CF92068002800DC4042D4 +:106410000A2690FBF6F042F2107790FBF7F107FBAB +:10642000110000B200F03EF9232000F029F92068A5 +:10643000002801DA532000E04E2000F033F912204A +:1064400000F01EF96068002800DC404290FBF5F087 +:1064500000B200F027F91A2000F012F96068002855 +:1064600000DC404290FBF6F090FBF7F107FB1100D7 +:1064700000B200F017F9222000F002F9606800284D +:1064800001DA572000E04520BDE8F04100F00AB9EC +:1064900010B54FF40040FBF70CFAA04A9C4920B11C +:1064A00092F82901012806D002E0002082F8290193 +:1064B0000868886010BD9A48FBE770B5974890F867 +:1064C000291111B9974A52780AB1012400E0002439 +:1064D000954D2A78944209D039B914B14FF4165029 +:1064E00001E0D0F82001FEF72CF92C7070BD2DE9E9 +:1064F000F0478A4890F8290118B98A48407800285E +:106500007ED08348806803F061F8002878D101F0DC +:1065100064FC854D6968401A7D2871D301F05DFCEB +:1065200068606878814F401CDFF80482DFF80492CD +:106530006870002404F12400C0B200F0A1F838888B +:1065400004F02BFA064638F9140004F01DFA31461F +:1065500004F0CEF9494604F095F904F023FA00B2AC +:1065600000F0A0F8641C032CE4DB00F096F86878D7 +:106570004FF06404800724D1102000F081F86E4EA3 +:10658000306890FBF4F000B200F08CF8212000F0AD +:1065900077F8306890FBF4F104FB110000B200F0D2 +:1065A00081F8142000F06CF86448B0F9000000F0A5 +:1065B00079F81C2000F064F8002000F073F800F077 +:1065C0006CF86878400735D1022000F059F85C4833 +:1065D0004FF00A08B0F9001091FBF8F000B200F09B +:1065E00061F80220FBF765F9E0B100F065F8554865 +:1065F0006E21007848431521B0FBF1F63A2000E007 +:106600003CE000F03DF8B6FBF4F738B200F04AF891 +:106610003B2000F035F804FB1760401DB0FBF8F09C +:1066200000F040F82020FBF72FF908B1FFF7D9FE62 +:1066300000F033F86878282820D10020687001F035 +:10664000CCFB4FF47A71B0FBF1F43C25B4FBF5F6CA +:10665000B6FBF5F005FB1067172000F011F83802C3 +:1066600000B200F01FF8182000F00AF805FB1640F1 +:1066700000F018F8BDE8F04700F00FB8BDE8F0876B +:1066800070B5234C05465E21A06802F08FFF2946B5 +:10669000A068BDE8704002F089BF1D485E21806897 +:1066A00002F084BF10B50446C0B2FFF77FFEC4F30A +:1066B0000720BDE8104079E670B52248224E40F62A +:1066C000340200783178184DB0FBF1F050432A22A3 +:1066D000B0FBF2F06A88B2FBF1F301FB13214FF635 +:1066E000FF7202EA011141EA0024C0F303200443CF +:1066F0000620FFF7C5FF20B2FFF7D4FF6888317886 +:10670000401C80B2B0FBF1F201FB1200688070BD4A +:10671000DC0800204C010020A08601006C04002051 +:10672000D8140020700A00205803002082010020A5 +:106730008000002000007A4420000020B0010020EA +:10674000E8000020D200002068010020884201DA21 +:10675000084670479042FCDD104670472DE9F0472F +:10676000BD49BD48E831B0F9E600B1F90050B1F9D2 +:10677000024010B90DB9002C7ED0B84A002111702A +:1067800004F002F9B64F394604F07CF8DFF8D492F1 +:10679000494604F0ADF88046284604F0F5F839463D +:1067A00004F070F8494604F0A3F80646204604F0C9 +:1067B000EBF8394604F066F8494604F099F80746C4 +:1067C000304604F029FF0446404604F025FF2146E8 +:1067D00004F058F8A44C2060384604F01DFF05462C +:1067E000404605F0FFFA294604F04CF805463846C5 +:1067F00005F0F8FA8246304605F0F4FA8146404644 +:1068000004F00AFF494604F03DF8514604F03AF816 +:10681000294604F031F86060384605F0E3FA054691 +:10682000404605F0DFFA294604F02CF805463846C4 +:1068300004F0F2FE8246304605F0D4FA8146404626 +:1068400004F0EAFE494604F01DF8514604F01AF837 +:10685000294603F0BFFFA060304604F0DDFE054688 +:10686000404605F0BFFA294604F00CF8E0603846CF +:1068700004F0D2FE054600E057E0404604F0CCFEAE +:10688000294603F0FFFF0546384605F0ABFA82467D +:10689000304605F0A7FA8146404605F0A3FA49467E +:1068A00003F0F0FF514603F0EDFF294603F092FF9D +:1068B0002061384605F096FA0546404604F0ACFEE5 +:1068C000294603F0DFFF0546384604F0A5FE824660 +:1068D000304605F087FA8146404605F083FA49467E +:1068E00003F0D0FF514603F0CDFF294603F0C4FF6B +:1068F0006061304605F076FA80F00040A0613846CD +:1069000005F070FA0546304604F086FE294603F08D +:10691000B9FFE061384604F07FFE0546304604F0DA +:106920007BFE294603F0AEFF2062BDE8F0872DE92B +:10693000F0470546B0F90080B0F90260B0F90400F4 +:1069400004F022F8484C8246A16803F09BFF0746FA +:10695000304604F019F88146616803F093FF06465B +:10696000404604F011F88046216803F08BFF314661 +:1069700003F030FF394603F02DFF04F013F82880B0 +:106980005046616903F07EFF07464846216903F0DF +:1069900079FF06464046E16803F074FF314603F094 +:1069A00019FF394603F016FF03F0FCFF68805046DC +:1069B000216A03F067FF07464846E16903F062FF7A +:1069C00006464046A16903F05DFF314603F002FF31 +:1069D000394603F0FFFE03F0E5FFA880A5E7092A8A +:1069E00011D2DFE802F0100509161C21262A2E001C +:1069F00002880A80428803E042880A8002880CE00C +:106A00004A808088888015480078002822D108466E +:106A10008DE7028852420A8042885242F0E742885B +:106A200052420A800288EBE7028852420A8042887A +:106A30000CE042880A80028808E002880A804288C6 +:106A400003E0428852420A80028852424A8080888B +:106A50004042D7E7704700006C040020600300202C +:106A6000DB0F494000003443AC0E00204449084489 +:106A7000444990F80A0151F820004FF4777101EB76 +:106A8000500080B2704710B5044601F08CF93E49C1 +:106A900002464868131A0020B3F57A6F00D948708F +:106AA0004A604A780AB90F2C0AD1087032B1354BC6 +:106AB00020331344182A03F8014C02D0521C4A70A8 +:106AC00010BD304A2032D27D0AB901220A704870C6 +:106AD00010BD10B504462A4800212A4BB0F8140115 +:106AE0004200A2F5F76200BF43F82120491C0829A3 +:106AF000FADB0123254A2649264801F0FDFA014622 +:106B00002548C1600CB1254921600821417410BDA0 +:106B10001D4B10B5187840B11A484FF000022030D4 +:106B2000817DC908C90702D01A70002010BD1C4918 +:106B3000401C0A8030F8011CC1F30A0411490C60A2 +:106B40000488C4F3CA044C600468C4F38A348C60BB +:106B5000B0F80340C4F34A04CC608488C4F30A1438 +:106B60000C614468C4F3CA344C61B0F80740C4F304 +:106B70008A048C6100894009C8611A70012010BD27 +:106B80006C040020D00E002064030020A0860100C9 +:106B9000876A000800440040DC0800206D6A000895 +:106BA000D60000202DE9F0410646007890B008B1EB +:106BB000012500E00025DFF8D880404602F0D0FE35 +:106BC0003448009000243448CDE90104012725B160 +:106BD0000220CDE90304802002E0CDE90374002007 +:106BE00005904FF480700690800007902020089058 +:106BF0000002CDE909046946404602F01EFF01216A +:106C0000404602F044FF8DF830500B948DF83170FF +:106C10004FF46020CDE90D040DB1022000E0012009 +:106C20001C4C8DF83C004C3C0BA9204602F004FEA5 +:106C3000032301220421204602F053FE2DB13178B6 +:106C400003230222204602F04CFE0121204602F0DE +:106C50001CFE0121204602F00EFE204602F01FFE1F +:106C6000204602F021FE0028FAD1204602F023FE41 +:106C7000204602F025FE0028FAD10121204602F02C +:106C800026FE10B0BDE8F081034931F810007047CE +:106C9000080002404C2401406C0300202DE9FF470E +:106CA000DFF86C81814698F80000D0B300273E469B +:106CB0003D463C46641CE4B202AB0822322153201C +:106CC00000F063FD9DF808009DF80910202C00EBF2 +:106CD000012000B207449DF80A009DF80B1000EB5C +:106CE000012000B206449DF80C009DF80D1000EB49 +:106CF000012000B205449DF80F0000F07F0001D292 +:106D00000028D7D197FBF4F0ADF8000096FBF4F023 +:106D1000ADF8020095FBF4F0ADF8040088F80240ED +:106D20001EE0FFE702AB06223221532000F02DFDCA +:106D30009DF808009DF8091000EB0120ADF8000057 +:106D40009DF80A009DF80B1000EB0120ADF8020041 +:106D50009DF80C009DF80D1000EB0120ADF804002B +:106D600098F8012049466846FFF739FEBDE8FF87DD +:106D700070B5274D04464FF0080228784FF02D01DA +:106D800000284FF053000ED000F0F9FC0A22312108 +:106D9000532000F0F4FC0C222C21532000F0EFFCD7 +:106DA0009022382108E000F0EAFC0A223121532029 +:106DB00000F0E5FC0A222C21532000F0E0FC1549EC +:106DC00040F20910002C088000D06C7070BD38B5FE +:106DD000054600208DF800000F480C460F4900685A +:106DE00088420AD06B4601220021532000F0CDFCDE +:106DF00018B19DF80000E52801D0002038BD0449F5 +:106E0000287808700648206006486060012038BD78 +:106E100070030020820100200C040020001BB7003A +:106E2000716D00089D6C000810B54FF48044204639 +:106E300002F08AFE012805D1204602F093FEB949EE +:106E40000120087010BD70B50D46B649B64A064619 +:106E500088885389B2F91440C01A13895843B2F98B +:106E60001230C013DB02044493FBF4F31844D061E6 +:106E700000EB8000082202EB40000411886800F05B +:106E8000D0F806B13060002D00D02C6070BD38B550 +:106E9000A44C207810B96088401C60806B460322A7 +:106EA000F621772000F071FC9DF800009DF801109C +:106EB000000440EA01209DF8021008439A49B1F904 +:106EC0002010C1F10801C840A06038BD96483421A7 +:106ED00090F8200001EB80109249C2B200200870A7 +:106EE000F421772000F04BBC38B58E4C207810B9D7 +:106EF0006088401C60806B460222F621772000F0FB +:106F000044FCBDF8000040BAA08038BD854900208F +:106F10002E220870F421772000F031BC2DE9F043D7 +:106F200004468248824985B00068884203D1002027 +:106F300005B0BDE8F083DFF8EC9199F8010008B1E5 +:106F40000120F5E74FF40055ADF80C5002208DF804 +:106F50000F001020774E8DF80E0003A9304601F087 +:106F600039FF6F00ADF80C7004208DF80E0003A9F6 +:106F7000304601F02FFF35610E21022001F060FF45 +:106F800000208DF8080008208DF809004FF0010856 +:106F9000019747468DF80A8001A802F09FFD28203E +:106FA0008DF810000F208DF811008DF812008DF86B +:106FB000137004A802F00DFC142000F01DFF6B46B6 +:106FC0000122D021772000F0E0FB574F9DF8000010 +:106FD0000321F8753984552801D07561A7E76B4600 +:106FE0000122D121772000F0D0FB9DF8000000F0B5 +:106FF0000F0139760009787600F05CF889F8018095 +:1070000041F27070208046F6781060804A486060D7 +:107010004A48A0604A48E0604A4820614A486061A6 +:107020008EE770B54049CA69B1F90E40A2F57A629F +:1070300002FB02F31D136C43E512B1F90240B1F9F2 +:107040000460544305EBE424B1F9005004EB8505DA +:1070500091F82040A54056437213B1F90C601B1300 +:107060005E4302EB2642921C9210C98802F5004250 +:10707000AD1C5143C90B4CF25032A0EBA500E240CD +:107080005043B0F1004F03D24000B0FBF1F002E0FA +:10709000B0FBF1F040000112494340F6DE325143AB +:1070A0002A4A0914424301EB224101F6CF6100EB69 +:1070B000211070BD00B587B06B461622AA2177203B +:1070C00000F063FBBDF8000041BA17480180BDF82D +:1070D000021049BA4180BDF8041049BA8180BDF858 +:1070E000061049BAC180BDF8081049BA0181BDF83F +:1070F0000A1049BA4181BDF80C1049BA8181BDF826 +:107100000E1049BAC181BDF8101049BA0182BDF80C +:10711000121049BA4182BDF8141049BA818207B0F1 +:1071200000BD0000740300200C0F00200C040020A0 +:10713000001BB700001001400D6F0008E96E000849 +:10714000CD6E00088F6E0008476E000843E3FFFF16 +:1071500038B5044600208DF800006B4601220A2154 +:107160001E2000F012FB18B19DF80000482801D045 +:10717000002038BD0CB18D480470012038BD7FB5AA +:10718000054602AB062203211E2000F0FEFABDF8E0 +:10719000080040BA00B203F0F7FB844C241D2168BC +:1071A00003F070FB03F0FEFBADF80000BDF80A0031 +:1071B00040BA00B203F0E8FBA16803F063FB03F000 +:1071C000F1FBADF80400BDF80C0040BA00B203F0CA +:1071D000DBFB616803F056FB03F0E4FBADF8020053 +:1071E000201F294602786846FFF7F9FB7FBD2DE98D +:1071F000F0476F4800246F49006825468EB02E4640 +:107200004FF0010888420CD14FF48050ADF82800AF +:1072100002208DF82B0004208DF82A000AA9664868 +:1072200008E06649884207D14FF48040ADF8280055 +:107230000AA9634801F0CEFD322000F0DDFD1122E5 +:1072400000211E2000F09BFA602201211E2000F088 +:1072500096FA642000F0D0FD6846FFF790FFDFF853 +:1072600058A1DFF8609100270AF10C0A01220221DF +:107270001E2000F084FA322000F0BEFD6846FFF7C1 +:107280007EFFBDF90210BDF90400BDF900200D44D8 +:1072900014440644814201DA0B4600E0034693425F +:1072A00001DD104602E0814200DA0846484502DC72 +:1072B0004FF0000808E0DAF8001081F01001CAF879 +:1072C00000107F1C0A2FD1DB122200211E2000F0AB +:1072D00056FA0027012202211E2000F050FA322027 +:1072E00000F08AFD6846FFF74AFFBDF90020BDF9AE +:1072F0000210BDF90400A41A6D1A361A814201DA8F +:107300000B4600E00346934201DD104602E0814255 +:1073100000DA0846484502DC4FF0000808E0DAF8D9 +:10732000001081F01001CAF800107F1C0A2FD1DB79 +:10733000204603F029FB244F0146384603F0D8FAD3 +:107340001A4C20F00040241D2060284603F01CFB4E +:107350000146384603F0CCFA20F000406060304629 +:1073600003F012FB0146194803F0C2FA20F0004076 +:10737000A060702200211E2000F001FA20220121CD +:107380001E2000F0FCF9002202211E2000F0F7F977 +:10739000642000F031FDB8F1000F04D14FF07E50B1 +:1073A00020606060A0600EB0BDE8F0878003002020 +:1073B0000C04002000127A00000C0140001BB700F2 +:1073C0000010014000F0FFFF00406F4601C05E4624 +:1073D00030B587B005464FF44060ADF81400022088 +:1073E0008DF817001C208DF8160005A9FB4801F048 +:1073F000F1FCFB4CE56000F007FAE06802F0B8FB36 +:10740000684602F020FC00224FF44071E06802F070 +:1074100050FC0025ADF804504BF6FF70ADF80600A7 +:107420004FF48040ADF80C00EE4800900121E06878 +:1074300002F017FC6946E06802F0ADFB4FF4A06073 +:1074400002F0C2F922208DF810008DF811508DF84D +:10745000125001208DF8130004A802F0BAF921207F +:107460008DF810008DF8115004A802F0B2F907B0A1 +:1074700030BD38B5DA4CE068818A009111F4706F44 +:1074800001D001212170009911F4E06F25D0018B0A +:1074900000224FF4806102F00CFC009880051CD49F +:1074A000E0680188890518D40188C9050CD50188D0 +:1074B000C905FCD4012102F0E8FBE06801888905D8 +:1074C000FCD4FFF785FF08E0012102F0DEFB00227B +:1074D0004FF44071E06802F0ECFBE068818A21F42F +:1074E000706181820020207138BDC2E72DE9F04132 +:1074F000BB4CE068818A4FF00105C9B2CA074FF062 +:10750000000627D0018821F400610180012102F0EA +:10751000C6FBE670607A20B1607860B9A079FF2878 +:1075200009D061790022E06802F0D0FBA079FF2841 +:1075300048D0FF20C9E06570E079022804D1E068F6 +:10754000018841F40061018061790122E06802F064 +:10755000BDFB37E08A074FF4806745D5BFF3508FF6 +:10756000E079012810D1607A70B1607860B10021B3 +:10757000E06802F094FBBFF3508FE068018B0121BB +:1075800002F083FBA57018E0E068008BBFF3508F1A +:10759000E079022808D1607A30B1607820B100210A +:1075A000E06802F07CFB06E0E079032805D1607A10 +:1075B00018B1607808B1002200E001223946E06885 +:1075C00002F077FB94F90310E079401C814209D165 +:1075D0006670A07828B100224FF44071E06802F094 +:1075E00068FB2671BDE8F0814A0753D5A570627A21 +:1075F0007B494978CAB3C9B3E17902291FD900216F +:1076000002F04DFBE06802F05EFB94F90310626942 +:107610005054491CE1700121E06802F036FBA5706E +:10762000E06802F050FB94F9031062695054491C61 +:10763000E17001223946E06802F03BFB25E00121C0 +:1076400002F023FBE06802F03EFB94F9031062694C +:107650005054491CE170E06802F035FB94F90310C6 +:1076600062695054891CE1700FE000E000E009B944 +:10767000217A31B1012102F008FBE078401CE07072 +:1076800003E0012102F0F7FA6570E0680188C9059E +:10769000FCD497E74A061AD502F015FB94F90310BB +:1076A00062695054491C48B2E070E179C01C8142C3 +:1076B00004D100223946E06802F0FBFAE17994F93E +:1076C00003008142E5D100F10100E0707AE709068C +:1076D000DFD594F903104B1C5AB20BD02369595CC7 +:1076E000E27002F0EEFAE07994F9031088423FF478 +:1076F0005AAF67E7E270A17902F0E3FA607A0028F6 +:107700007FF451AFE0790028F1D05BE7EEE6B0E618 +:10771000ECE670B5324C4FEA400047F230556071EC +:10772000A171012020720021617223616361E27105 +:1077300020712170E068818889050ED40188C9050F +:1077400005D401888905FCD4012102F094FA0122B4 +:107750004FF44071E06802F0ACFA207910B16D1E70 +:10776000FBD104E01DB1207880F0010070BD60897C +:10777000401C6081E068FFF72BFE002070BD07B55C +:1077800002AB0122FFF7C5FF0EBD70B5144C4FEAE6 +:10779000400047F230556071A17100202072012134 +:1077A000617263612361E27121712070E0688188F8 +:1077B00089050ED40188C90505D401888905FCD442 +:1077C000012102F058FA01224FF44071E06802F002 +:1077D00070FA207940B16D1EFBD10AE0000C014027 +:1077E00090030020801A06001DB1207880F001006F +:1077F00070BD6089401C6081E068FFF7E9FD0020F2 +:1078000070BD2A48408970472DE9F84F4FF4406712 +:10781000ADF800704FF0020A8DF803A01420DFF8D5 +:1078200090B08DF802006946584601F0D3FA204D19 +:1078300010352F60DFF8789000262C1505F104082C +:1078400009F1080902E00A2000F0CAFAD9F800009C +:107850004005F8D5C8F800400A2000F0C1FA2C60B5 +:107860000A2000F0BDFA761CF6B2082EEED34FF4D3 +:1078700000694646C8F800900A2000F0B1FA34606A +:107880000A2000F0ADFA2C600A2000F0A9FAC5F831 +:107890000090ADF800708DF803A01C208DF8020058 +:1078A0006946584601F096FABDE8F88F900300202B +:1078B000000C014038B504466B4602221B216820AB +:1078C000FFF763FFBDF8000043F2903140BA08446F +:1078D0004FF48C71B0FBF1F02330208038BD1FB520 +:1078E000044602AB06221D216820FFF74EFFBDF8BB +:1078F0000800214640BA02B2D01702EB9070801007 +:10790000ADF80000BDF80A0040BA02B2D01702EB91 +:1079100090708010ADF80200BDF80C0040BA02B2C1 +:10792000D01702EB90708010ADF804002F48427819 +:107930006846FFF754F81FBD70B50446192000F0E3 +:107940005BFA002215216820FFF719FF10B9032008 +:1079500000F0FCFA254D1621287840F01802682026 +:10796000FFF70DFF002217216820FFF708FF012213 +:107970003D216820FFF703FF01223E216820FFF729 +:10798000FEFE002C00D06C7070BD70B504460D4634 +:10799000192000F031FA002215216820FFF7EFFED0 +:1079A00000281CD012482060124860601248A06075 +:1079B0001248E0600D48622D12D004DC0A2D13D06D +:1079C000142D05D10EE0BC2D06D0B5F5807F01D079 +:1079D000032102E0002100E001210170012070BDBF +:1079E0000221FAE70421F8E70521F6E7A8030020C1 +:1079F00039790008DF780008B5780008184492311A +:107A0000FEB5064614460D46684602F039FC0120D4 +:107A1000ADF804000021ADF80050ADF80610ADF847 +:107A20000810ADF802406946304602F079FBFEBD11 +:107A300070B51646D04A02EB0015D04A02EB00148E +:107A40000122206801F003FBD4E90101182200F0B3 +:107A500087F9217B3246206800F03FF9A07B18B1FE +:107A60000121206802F01EFC0121206802F010FCB8 +:107A7000207B30B1042807D008280AD00C2806D172 +:107A80000AE02068343001E0206838302860284659 +:107A900070BD20683C30F9E720684030F6E72DE9FA +:107AA000F0410546B4480F4600EB0516B348B271E5 +:107AB00000EB05142822D4E9010100F051F9217BE3 +:107AC00000222068FFF79CFF01224FF6FF7120463D +:107AD00001F0DAFA3A462946204601F09BFA304690 +:107AE000BDE8F08170B5A648002402894281018179 +:107AF000891A8BB240F68C218B4201D9C47070BDBB +:107B00009F49A3F2EF2540F2DB569E4AC978B54261 +:107B10001BD2082919D2984DE035042925F81130D7 +:107B200007D2C588AB4204D9012305798B402B438A +:107B3000037103790F2B08D10471B2F90030142BB3 +:107B400002DD143B138000E01480491CC1701480D6 +:107B500070BD70B5884A894B02EB001203EB00132D +:107B6000D47918681B7B8CB151811489824D091B13 +:107B700091819479E03525F814100024D4712246BF +:107B80001946FFF73DFF7F48048070BD1181012138 +:107B9000D171BDE870400222194631E72DE9F04766 +:107BA0000446774DE1890020E980A17901B10220E6 +:107BB000617801B1401C7449DFF8D081002651F88A +:107BC00020704FF47A79BA5D02F00F0002F0F001F4 +:107BD000FF2A65D0A2781AB102285ED003285CD0B3 +:107BE000E2783AB1042858D0052856D0062854D057 +:107BF000072852D0E2790AB182424ED011F0300FFC +:107C000002D0227802B90021227932B1A27922B9B8 +:107C1000082801D0092800D1802162792AB1A279EF +:107C20001AB9021F032A00D88021CA0605D50022EE +:107C30005749FFF734FF082008E08A0608D5AA78DC +:107C40005449FFF72CFFA87800F10100A87024E048 +:107C50004A0612D52289B8FBF2F1A28989B202B98B +:107C60004A46FFF7E5FE0146434A2878F03242F8DB +:107C7000201000F1010028700FE009060DD562897F +:107C8000B8FBF2F189B24A46FFF7D2FE0146424AFA +:107C9000687842F82010401C6870761C0E2E92DB2B +:107CA0000020BDE8F087364A1278904205D23A4A61 +:107CB000303A52F82000006801807047304A52780C +:107CC000904204D2344A52F8200000680180704784 +:107CD0003149403931F8100070477FB506461546E6 +:107CE0000C46684602F0C2FA7020ADF80000012090 +:107CF000ADF802000020ADF804000220ADF8080045 +:107D0000C001ADF80650ADF80C0074B1042C15D0CC +:107D1000082C1CD00C2C07D16946304602F04CF9D7 +:107D20000821304602F0E7FA7FBD6946304602F08E +:107D300098F80821304602F0C8FA7FBD69463046FF +:107D400002F0C4F80821304602F0C5FA7FBD69464A +:107D5000304602F0F7F80821304602F0C6FA7FBD3F +:107D600008B5ADF800108DF8022002218DF803103F +:107D7000694601F02FF808BD300F002054CF0008ED +:107D8000AA030020D600002018CF000840420F00B0 +:107D9000E57A0008537B00085010002080484168B5 +:107DA000491C4160704710B57D484FF0E0234168A1 +:107DB0009A694468A142FAD10368006803EB43045E +:107DC000C4EBC313C2EBC302B2FBF0F001EB410200 +:107DD000C2EBC11100EBC10010BD71484068704793 +:107DE00030B50546FFF7DFFF4FEA0004FFF7DBFF82 +:107DF000001BA842FAD330BD30B504464FF47A7563 +:107E000002E02846FFF7ECFF641EFAD230BD644959 +:107E1000896808474FF4805108B1624801E0614821 +:107E2000001F016070474FF4805110B15D48001F82 +:107E300000E05C48016070472DE9F04F8DB01822DA +:107E40005949684602F041FC032701F016FC012164 +:107E5000564801F0A1FF012144F61D2001F093FFD7 +:107E60000121084601F086FF01F0B1FF4FF6FF70D7 +:107E7000ADF818004B484FF0000A8DF81AA006A97B +:107E8000143800F0A7FF06A9494800F0A3FF06A98F +:107E9000484800F09FFF4848416841F00071416048 +:107EA000464DDFF81C813E4E2968414501D14548C9 +:107EB00000E04548B0600020FFF7A9FF3C490820DA +:107EC0001031086010200860A946002483466D46E2 +:107ED000D9F80010414506D105EBC4008179142979 +:107EE00001D180F806B005EBC401091D55F8340036 +:107EF00000F070FF641CBC42EAD307A801F0F4FE56 +:107F000032490798B0FBF1F0306031484FF47A7194 +:107F10000068B0FBF1F0B0F1807F0CD220F07F411F +:107F20004FF0E020491E41612A4AF0211170C0F84B +:107F300018A0072101612848FFF74AFA00F0C9FF9D +:107F40006420FFF759FF0DB0BDE8F08F184A1021EB +:107F5000143211600821121F11600446151F40F2EF +:107F6000DB104443286880F010002860286880F007 +:107F700008002860A01EFFF73FFF0120FFF747FF22 +:107F80001920FFF739FF0020FFF741FFEAE710B1A2 +:107F90001349124808600F491248173908607047A2 +:107FA000B80300201408014028CF00080700400053 +:107FB000000C014000100140000001400C040020B2 +:107FC000001BB700277E0008157E000840420F0006 +:107FD0000804002023ED00E000580040EFBEADDEB5 +:107FE000F04F00200400FA057CB5FA4C0D46FA4922 +:107FF0002160A060A4F53070606100F58070A06120 +:108000004FF48070E0602061F4482063F348012160 +:1080100014386063880301F0B6FE02208DF8030077 +:108020000002ADF8000018208DF80200EC4EA80701 +:1080300003D56946304600F0CDFE4FF48060ADF8C0 +:10804000000048208DF80200E80703D0694630465A +:1080500000F0C0FE0E208DF8040001208DF8050010 +:108060008DF806008DF8070001A801F0B2FB20464C +:108070007CBD2DE9FC41D74C0D464C34D6492160DE +:10808000A0608020E06040202061A4F586706061DF +:108090008030A061D3480121A064480401F07CFE37 +:1080A00002268DF803600420ADF8000018208DF83A +:1080B0000200CB4FA80703D56946384600F08AFE78 +:1080C0000820ADF8000048208DF80200E80703D032 +:1080D0006946384600F07EFE26208DF80400012017 +:1080E0008DF805008DF806608DF8070001A801F0F5 +:1080F00070FB2046BDE8FC812DE9F0438946064629 +:10810000B9490024B7488FB01D4617468E4204D1A6 +:1081100019461046FFF768FF05E0864204D119466C +:108120001046FFF7A6FF04464FF00008C4F8208071 +:10813000C4F81C80C4F82880C4F82C90C4F82480AB +:10814000A6642571A760ADF83080ADF834800B9738 +:10815000ADF83280ADF83880ADF83680E80702D04F +:108160000420ADF83600A80705D5BDF8360040F06C +:108170000800ADF836000BA9304602F0E3F8012103 +:10818000304602F037F9684601F074FC301D00906B +:108190004FF48050CDE909088020CDF81080CDE95A +:1081A00005084746CDF81C80E80723D0206BD8B1DE +:1081B000E068CDE902702020089060690190206B92 +:1081C00001F0CEFB6946206B01F037FC0121206BEA +:1081D00001F05DFC01224021304602F02DF9206BB8 +:1081E00001F06AFC206405E0012240F2255130468E +:1081F00002F00AF9A80724D5606BE0B1206903906A +:10820000102008970290606B01F0AAFB6946606B32 +:1082100001F013FC01220221606B01F043FC0021FC +:10822000606B01F047FC606B4760012280213046A3 +:1082300002F002F905E0012240F22771304602F017 +:10824000E3F80FB02046BDE8F0837FB50446002078 +:10825000ADF80400ADF808000091ADF80600ADF8E7 +:108260000C00ADF80A0020790D46C00702D00420AA +:10827000ADF80A002079800705D5BDF80A0040F066 +:108280000800ADF80A006946A06C02F05BF8A56032 +:108290007FBD826A81691144426BD160D0E90921B6 +:1082A00000238A4205D9511A426B5160416A8162AA +:1082B00004E00269511A426B5160836280F84430D5 +:1082C000406B012101F0E3BB016B11B14968006C07 +:1082D00001E01C3003C8814201D00120704700201A +:1082E0007047416B11B190F844007047243003C8C7 +:1082F000814201D1012070470020704710B501462E +:10830000036BC268406943B10B6CD21A805C5B1E80 +:108310000B6401D1CA680A6410BD0B6AC05C5B1CA7 +:10832000B3FBF2F402FB14320A6210BD436A8269A5 +:10833000D154416A0269491CB1FBF2F302FB1311EB +:108340004162416B19B10968C90706D1A1E7806C88 +:10835000012240F2277102F057B8704710B51D4C4A +:108360004FF4005001F0ABFB0021606B01F08FFB7C +:10837000D4E90901884203D02046BDE8104088E7CF +:10838000012084F8440010BD1249886C028812064E +:108390000ED5D1E909329A420BD08B699A5C828062 +:1083A000886A0A69401CB0FBF2F302FB1300886282 +:1083B0007047002240F2277102F026B870B5054CD4 +:1083C0004C34A06C0588A9061CD58088E16A69B187 +:1083D000884717E03013002040CF000858000240C3 +:1083E000000801400044004000380140E269616932 +:1083F0008854E069E16800F10100B0FBF1F201FB93 +:108400001200E06128060FD5D4E9091088420CD08B +:10841000A169085CA16C8880A06A2169401CB0FB3E +:10842000F1F201FB1200A06270BDA06CBDE87040CB +:10843000002240F2277101F0E7BF0000FEB52C4C8E +:108440000125207878B1012823D0022820D164208A +:108450008DF8000027488DF8015000264078E0B3E1 +:108460008DF802503CE07A208DF8000022486B46DF +:108470000222B0F90000FF21C0F1B40000EBD0707F +:10848000C0F347008DF801006D20FFF742F9257019 +:10849000FEBD1A4E79208DF80000B6F900000A25BD +:1084A00090FBF5F05A30B4220021FEF74FF98DF819 +:1084B0000100B6F90200B42290FBF5F05A30002119 +:1084C000FEF744F98DF802006B460322FF216D2070 +:1084D000FFF71FF902202070FEBDFFE78DF8026054 +:1084E0006B460322FF216D20FFF713F92670F3E797 +:1084F000C4030020700A0020B001002034000020D6 +:108500001FB5044602AB062243216820FFF73DF960 +:10851000BDF80800214640BA02B2D01702EB9070B5 +:108520008010ADF80000BDF80A0040BA02B2D017C2 +:1085300002EB90708010ADF80200BDF80C0040BA5C +:1085400002B2D01702EB90708010ADF804007C48A6 +:1085500042786846FEF743FA1FBD38B504464FF42B +:108560000050ADF8000002208DF8030004208DF8C3 +:108570000200744874490068884202D16946734811 +:1085800004E07349884203D16946724800F022FC36 +:1085900080226B216820FFF7F2F80520FFF72CFC02 +:1085A000002219216820FFF7EAF803226B216820D6 +:1085B000FFF7E5F8022237216820FFF7E0F8604D69 +:1085C0001A2168202A78FFF7DAF818221B21682080 +:1085D000FFF7D5F810221C216820FFF7D0F8002CF7 +:1085E00000D06C7038BD1FB5044602AB06223B219B +:1085F0006820FFF7CAF8BDF80800214640BAADF878 +:108600000000BDF80A0040BAADF80200BDF80C0049 +:1086100040BAADF804004A4882786846FEF7DFF9B0 +:108620001FBD47494C4ACB7813B14FF4FF6301E0BB +:108630004FF480531380002800D0887070472DE9D4 +:10864000FE4F8146984692460D462320FFF7D4FB05 +:108650006B46012275216820FFF797F8002804D0A7 +:108660009DF80000682802D00020BDE8FE8F062299 +:1086700001AB11466820FFF788F89DF809009DF8C6 +:108680000710C007400F01F0010140EA41009DF8CA +:1086900005102B4C01F0010108434FF001064FF08B +:1086A000000704D0012833D002280DD02CE06B46FF +:1086B00001220C216820FFF768F89DF8000010F0F7 +:1086C0000F0021D0042823D0E7702449C9F80010F6 +:1086D00023492448C9F804102860234868602348C7 +:1086E000E860B8F1000F02D0E17888F80010504639 +:1086F000BAF1620F19D00DDC05281ED00A281AD055 +:10870000BAF1140F0BD114E00520FFF71FFCDCE7D2 +:10871000E670DAE7BC2806D0BAF5807F01D00320E6 +:1087200004E0277003E0267001E0022020700120A1 +:108730009BE70420FAE70520F8E70620F6E70000AB +:10874000C50300200C04002000127A00000C014038 +:10875000001BB700001001408201002023860008A2 +:10876000E78500085B8500080185000819449231FF +:108770001FB5044602AB062201211C20FFF705F8B5 +:10878000BDF80800214640BA40F38D02D01702EB35 +:1087900090708010ADF80000BDF80A0040BA40F3B8 +:1087A0008D02D01702EB90708010ADF80200BDF87A +:1087B0000C0040BA40F38D02D01702EB907080108D +:1087C000ADF80400334802786846FEF708F91FBD8B +:1087D00038B504462020ADF8000002208DF80300D3 +:1087E00004208DF8020069462B4800F0F3FA0022BD +:1087F0002A211C20FEF7C3FF02220E211C20FEF7B7 +:10880000BEFF03220F211C20FEF7B9FF12222B21ED +:108810001C20FEF7B4FF02222C211C20FEF7AFFF24 +:1088200001222D211C20FEF7AAFF00222E211C2050 +:10883000FEF7A5FF05222A211C20FEF7A0FF1749FD +:108840004FF48070002C088001D01248047038BDAD +:1088500038B5044600208DF8000011481149006821 +:1088600088420CD06B4601220D211C20FEF78DFFA3 +:1088700028B19DF800002A2803D01A2801D0002032 +:1088800038BD0949216009496160024948700120E9 +:1088900038BD0000C903002000080140820100200B +:1088A0000C040020001BB700D18700087187000866 +:1088B000434810B50068434CA188084203D0FFF735 +:1088C00072FAA0600AE0FFF76EFAA168884205D943 +:1088D000401A3B2190FBF1F061690860E068BDE857 +:1088E000104001F03FB9E3E7E2E7FEB50125354C62 +:1088F000022110B1012810D109E04FF4807060808E +:108900004000A080E06009202070172004E065800E +:10891000A180E1602570072060706088ADF80000DC +:108920001026274F8DF802608DF80310083F694626 +:10893000384600F04FFAA088ADF8000004208DF80A +:1089400002006946384600F045FA2178012000F01F +:1089500077FAE06801F006F9E068019000208DF8F0 +:1089600008008DF809608DF80A5001A801F0B6F8EA +:1089700094F9010000F01F018D4040094FF0E02103 +:1089800001EB8000C0F80051FFF727FA3C38206166 +:10899000FEBD70B50546FFF720FA0A4C21693C314F +:1089A00088420CD3C4E90405054960880831086091 +:1089B0000B20FFF715FA024960880C31086070BD82 +:1089C000080C0140CC0300201FB5044602AB062270 +:1089D000A8216820FEF7D9FEBDF80800214640BA5C +:1089E00002B2D01702EB90708010ADF80000BDF815 +:1089F0000A0040BA02B2D01702EB90708010ADF8B6 +:108A00000200BDF80C0040BA02B2D01702EB907021 +:108A10008010ADF80400264842786846FDF7DFFF75 +:108A20001FBD70B504466420FFF7E6F9F02223214C +:108A30006820FEF7A4FE10B90320FFF787FA05208F +:108A4000FFF7DAF91A4D2021287840F00F0268204C +:108A5000FEF795FE002C00D06C7070BD38B5044652 +:108A60000D461920FFF7C8F96B4601220F21682037 +:108A7000FEF78BFE9DF80000D32801D0002038BD02 +:108A80000C4820600C4860600C48E0600848362DB7 +:108A900005D04E2D07D05D2D07D0002100E04021EC +:108AA0000170012038BD8021FAE7C021F8E70000FD +:108AB000E4030020238A0008C9890008DDE9A73102 +:108AC0002DE9F04FB74C83468E4660892689010216 +:108AD000B5484FF0000A4068421AA6FB027CA08805 +:108AE0004FEAE2754FEA10414FEA00430AFB02C029 +:108AF00006FB05064FEAD71040EA466013EB000973 +:108B000041EBE611E6886388A6FB02C84FEA5340B2 +:108B10004FEAC3370AFB028306FB05364FEA1C23E4 +:108B200043EA0663FB1840EB2620A689A6FB027CDD +:108B30000AFB02C206FB05244FEAD75242EA44224E +:108B40004FF4FA654FEAE454521944F10004A24686 +:108B5000551B74F1000448DA944D5519A5FB0567BF +:108B60004AF1FF3404FB057705FB047C0525A6FBD1 +:108B700005480CFB0585002706FB07556F104FEADB +:108B8000340CB9EB0C0961EB0701A40844EA8574C5 +:108B90001B1B60EBA500864D551B7AF1FF3424DAD0 +:108BA00040F2DC555619A6FB06474AF1000505FBC5 +:108BB000067706FB05750726A4FB06C805FB068697 +:108BC000002704FB0767B9EB0C0961EB07010B27D2 +:108BD000A4FB07C805FB0785002604FB06546410A8 +:108BE0004FEA3C055B1B60EB04006F4CA56800245A +:108BF000A5FB036704FB037305FB0030740D44EA17 +:108C0000C0244015B4EB090360EB0100410441EAC4 +:108C1000D330BBF1000F01D0CBF80000BEF1000F44 +:108C200001D0CEF80020BDE8F08F10B500F072F84A +:108C30005D49886010BD5C48012200784030C1B2B7 +:108C40007720FEF79CBD10B500F064F856494860E7 +:108C500010BD5548012200785030C1B27720FEF790 +:108C60008EBD2DE9FE4305465248534900688842AF +:108C70000FD04FF40054ADF8004002208DF80300EF +:108C800010204E4E8DF802006946304600F0A2F8E2 +:108C900074610A20FFF7B0F801AB0122A021772010 +:108CA000FEF773FD002823D001221E217720FEF756 +:108CB00066FD4FF42F60FFF793F80024DFF8E4809F +:108CC0002646A02707EB4400C1B202AB0222772060 +:108CD0000296FEF75AFDBDF8080040BA28F81400C5 +:108CE000641C082CEEDB2F4800F026F810B10020A1 +:108CF000BDE8FE8342F210702880688030486860CA +:108D00003048A8603048E8603048286130486861E1 +:108D10000120EDE708B56B46032200217720FEF71E +:108D200034FD9DF800009DF80110000440EA012088 +:108D30009DF80210084308BDF0B5C289002102F475 +:108D40007F4502F00F040123C5810A4630F8126006 +:108D500006B10023521C082AF8DB4FF0FF36F3B9A6 +:108D60000022D30722F0010302D0C35C594002E085 +:108D7000C35A81EA132108230F0401D581F4C0519D +:108D800049005B1E002BF7DC521C102AE9DB25434F +:108D9000C581C1F30330844201D10020F0BD3046CB +:108DA000F0BD0000C8130020E803002030F8FFFFEA +:108DB00024FAFFFF0C040020001BB7000010014044 +:108DC000538C0008478C0008378C00082B8C000857 +:108DD000C18A0008F0B500234FF0010C0A880CFA94 +:108DE00003F52A4228D04FEAD30200EB82064FEA6D +:108DF000437491F802E04FEAD46734680EF00F0232 +:108E00005FEACE6E03D591F803E04EEA02024FF01E +:108E10000F0E0EFA07FE24EA0E04BA402243326017 +:108E20008A78282A02D0482A03D005E0C268AA43DB +:108E300001E0C2682A43C2605B1C102BCED3F0BD98 +:108E400010B58A0721F003040649130F21440F22AD +:108E50008C689A4094438C608A68984002438A6088 +:108E600010BD0000000001404FF4805108B14E4891 +:108E700001E04D48001F016070472DE9F0410446B4 +:108E80004A4817460D460088484E0C3E1CE015B176 +:108E900015F8010B00E0FF2080460221304601F06A +:108EA000D9FB0028F9D04146304601F0CFFB012123 +:108EB000304601F0CFFB0028F9D0304601F0C8FB66 +:108EC000C0B20CB104F8010B7F1EE0D20120BDE856 +:108ED000F081F0B501218C0389B0204600F05CFFE1 +:108EE0000121204600F06AFF18208DF816004FF48B +:108EF0002040ADF814002C4E03208DF81700143ECE +:108F000005A93046FFF766FFADF8144004208DF840 +:108F1000160005A93046FFF75DFFA010ADF814005C +:108F200010258DF8165005A93046FFF753FF1F4E48 +:108F30000C3E304601F040FB4FF48270ADF8020069 +:108F400068010024ADF80A000720ADF81000ADF864 +:108F500004400220ADF80E40ADF806000127ADF840 +:108F60000040ADF80870ADF80C506946304601F08D +:108F700047FB0121304601F05FFB0DA00068069021 +:108F80000120FFF771FF042206A907A8FFF775FF6C +:108F90000020FFF769FF9DF81D00EF2802D0204652 +:108FA00009B0F0BD3846FBE7140C01400C38004016 +:108FB0009F0000002DE9F04180461D4616460C46F4 +:108FC000084600F0E7F80746404600F0D8F807EBFF +:108FD0008000C0B2102805D2734901EB00108560F3 +:108FE00004710673BDE8F08151B104290BD0082942 +:108FF0000CD00C290DD101225FF0100101F05DB9F8 +:1090000001220221FAE701220421F7E701220821C7 +:10901000F4E7704770B50D460446017B13460068BF +:109020002A46FFF7C7FF217B2068BDE87040DBE7D9 +:1090300008B58DF8000000208DF8010001208DF8A2 +:1090400002008DF80300684600F0C3FB08BDFEB5C2 +:10905000064614460D46684601F0FFF853486D1E5B +:1090600044435348ADF8045069460068B0FBF4F03F +:10907000401EADF800000020ADF80600ADF802007B +:10908000304600F0B5FEFEBD10B504460068FFF79F +:10909000DEFF0121206801F0FBF8607BBDE8104095 +:1090A000C6E770B50546084600F074F80446284641 +:1090B00000F065F804EB80003B49C0B201EB001002 +:1090C00070BD70B50546022101F028F9012825D0B0 +:1090D0000421284601F022F901282CD00821284635 +:1090E00001F01CF9012833D01021284601F016F9AF +:1090F00001283AD11021284601F01CF90C212846FC +:10910000FFF7CFFF0446284601F005F9A2680146A3 +:10911000002A2AD0207BBDE8704010470221284653 +:1091200001F008F900212846FFF7BBFF0446284656 +:1091300001F0EBF8EAE70421284601F0FBF80421EE +:109140002846FFF7AEFF0446284601F0E0F8DDE7C9 +:109150000821284601F0EEF808212846FFF7A1FF74 +:109160000446284601F0D5F8D0E770BD1148A8E7BD +:109170004FF08040A5E71048A3E71048A1E701465B +:1091800000200F4A01E0401CC0B252F820308B4250 +:10919000F9D17047014600200A4A01E0401CC0B2E4 +:1091A000135C8B42FAD17047D813002040420F0065 +:1091B00008040020002C014000040040000800408A +:1091C000F403002034D00008016B4A689268896873 +:1091D0000A4290F8441204D00020002900D1012056 +:1091E000704701200029FBD100207047D0F83431AE +:1091F00001299A685B6801D021B107E090F8440228 +:1092000030B103E090F84402012801D05A61704760 +:109210001A6170470189406889B2482200F052B94A +:1092200070B5044601EB4100AC491646B1FBF0F0C5 +:1092300081B21D4603222046FFF726FF2A4631460B +:109240002046BDE87040FFF7E5BE0189406889B25D +:10925000102200F037B900B50346032083F83C0222 +:109260001846FFF7B1FF30B1B3F8400293F8391256 +:109270000843A3F8400293F83902400083F839020A +:1092800093F83E02401E10F0FF0083F83E0205D125 +:10929000012083F83802022083F83C0200BDC26836 +:1092A000016A521E914201D3002100E0491C016273 +:1092B000704710B50124034680F83C42FFF784FF55 +:1092C00001280FD1002083F8380283F83A4293F83E +:1092D0004002A3F840021A6A59698854BDE8104058 +:1092E0001846DCE710BD00B50346FFF76DFF01210E +:1092F00001280BD003F23A2300201870D8800420F4 +:1093000098700820187103F8011C00BD83F83C1206 +:1093100000BD90F83C12491E11F0FF0180F83C128C +:1093200008D190F83A1201B1DDE790F8381201B196 +:10933000BFE790E77047D0E90910814201D10120D1 +:1093400070470020704730B5044690F83B02002576 +:10935000F8B194F83D02401E10F0FF0084F83D0281 +:1093600016D1B4F8420200F001014008A4F842020C +:109370002046FFF73BFF032084F83D0294F83F02AC +:10938000401E10F0FF0084F83F0201D184F83B52E8 +:1093900030BD2046FFF7CFFF0028F9D1A16AA269AE +:1093A000481CA062515C2269904200D3A5624FF430 +:1093B000007004F23B2440EA4100A4F807000A20B0 +:1093C00020710120A070207030BD00EBC00101EBC6 +:1093D000801010B5424901EBC0042046FFF7B3FFEF +:1093E0002046BDE8104094E770B53D4C06463D4828 +:1093F000206003202071A66084F844123A4820635C +:109400001030C4F83401002504F134012562616193 +:109410004FF48070E060206104F59C71C4E906158A +:10942000A562656284F83B52012084F83A0284F810 +:10943000385284F83C02206BFFF7ECFED4F834017C +:10944000FFF703FF01212046FFF7D0FE3220FEF791 +:10945000D3FCAFF289032A463146206BBDE8704049 +:10946000DEE6D0E90721914202D14FF000007047BB +:1094700002D9A1EB020003E0C0680844A0EB02009F +:10948000C0B2704700B50346FFF7EBFF00280BD0D2 +:109490005969D869095CDA68521E904201D2401CB1 +:1094A00000E00020D861084600BD436A8269D154BB +:1094B000416A0269491CB1FBF2F302FB13114162DC +:1094C0007047704708B5ADF800108DF802200221F2 +:1094D0008DF803106946FFF77DFC08BDC0C62D005E +:1094E000D814002038D0000894CF00081FB50446D7 +:1094F00002AB062202211820FEF747F99DF808006A +:109500009DF80910800800EB0120ADF800009DF8DF +:109510000A009DF80B10800800EB0120ADF8020056 +:109520009DF80C009DF80D10800800EB0120ADF8AF +:1095300004001A48214602786846FDF750FA1FBD1C +:1095400010B5044608220F211820FEF718F90E2244 +:1095500010211820FEF713F911494FF48050002C08 +:10956000088001D00D48047010BD38B504460020B5 +:109570008DF8000001466B4601221820FEF705F920 +:1095800018B19DF80000FB2801D0002038BD054827 +:10959000206005486060012038BD00000404002000 +:1095A0008201002041950008ED94000802681268CD +:1095B000104770B50C46054603E02A682846126835 +:1095C000904714F8011B0029F7D170BD0168496864 +:1095D00008470168896808470268D268104701682F +:1095E000096908476E48016841F00101016041685E +:1095F0006C4A1140416001686B4A1140016001688A +:1096000021F480210160416821F4FE0141604FF4A2 +:109610001F0181606549C00308607047604A10B54A +:109620005068634B10F00C01624803D0042903D04A +:10963000082903D0036016E0416813E051685368BD +:1096400001F470114FF0020413F4803F04EB9141D8 +:1096500006D053689B03436800D55B084B43E9E79A +:10966000554B594301605168524AC1F30311083206 +:10967000515C0268CA40026010BD3EB400210091F6 +:109680004FF4E01301914648CDE901314B4A04689B +:1096900044F480340460846944F0100484614FF41D +:1096A000A064056805F400350195009D6D1C0095CA +:1096B000019D15B9009DA542F3D10568AD0301D503 +:1096C000022114E0056845F001050560009101687C +:1096D00001F0020101910099491C0091019911B911 +:1096E0000099A142F3D10168890739D5012102917E +:1096F00033490C6844F010040C600C6824F0030437 +:109700000C600C6844F002040C60416841604168E0 +:109710004160416841F480614160116821F070410D +:109720001160244C22496160416821F47C11416040 +:10973000116841F0004111602049091FCA6822F4F4 +:109740000042CA608968090403D51E494FF480139A +:10975000616002990193012908D002290AD100E031 +:10976000FEE7416843F48032114302E0416841F46E +:1097700060114160016841F08071016001688901F8 +:10978000FCD5416821F003014160416841F00201CC +:1097900041604168C1F381010229FAD13EBC3DE735 +:1097A000001002400000FFF8FFFFF6FE08ED00E0A9 +:1097B00000127A000804002000093D000410014056 +:1097C00000200240001BB7001849084318490860F0 +:1097D0007047F0B50F21C478027801234FF0E026DE +:1097E000DCB1134C2468457804F4E064C4F5E0640B +:1097F000240AC4F10407E1408478BD400C402C43A6 +:1098000021010C4C1155007800F01F018B404009DC +:1098100006EB8000C0F80031F0BD02F01F0083406D +:10982000500906EB8000C0F88031F0BD0000FA0559 +:109830000CED00E000E400E010B54268464B0C7906 +:109840001A400B6842EA0422134343608368434A88 +:109850001340D1E9024222434C7943EA44031A43BC +:109860008260C26A097C22F47002491EC9B242EACF +:109870000151C16210BD0029816802D041F001018F +:1098800001E021F00101816070470029816802D068 +:1098900041F4807101E021F480718160704781683A +:1098A00041F008018160704701460020896809077E +:1098B00000D501207047816841F004018160704744 +:1098C000014600208968490700D50120704700291A +:1098D000816802D041F4A00101E021F4A00181607F +:1098E000704770B5072409290AD9C568A1F10A068D +:1098F00006EB4606B440A543B3401D43C56007E0F0 +:10990000056901EB4106B440A543B3401D43056121 +:109910001F23072A09D2446B521E02EB8202934096 +:109920009C4391400C43446370BD0D2A09D2046BE3 +:10993000D21F02EB820293409C4391400C4304638C +:1099400070BDC46A0D3A02EB820293409C43914081 +:109950000C43C46270BD0000FFFEF0FFFDF7F1FF95 +:1099600001684FF6FE721140016000210160416004 +:109970008160C1605749574A0839904203D148680D +:1099800040F00F0006E0534A1432904204D1486878 +:1099900040F0F000486070474E4A2832904203D1B0 +:1099A000486840F47060F5E74A4A3C32904203D17F +:1099B000486840F47040EDE7464A5032904203D187 +:1099C000486840F47020E5E7424A6432904203D18F +:1099D000486840F47000DDE73E4A7832904203D197 +:1099E000486840F07060D5E73B4A111F904203D1B0 +:1099F000086840F00F0006E0374A1432904204D164 +:109A0000086840F0F00008607047334A28329042FE +:109A100003D1086840F47060F5E72F4A3C32904269 +:109A200003D1086840F47040EDE72B4A5032904271 +:109A3000EAD1086840F47020E5E730B5036847F6DE +:109A4000F07293430C6A8A682243D1E904452C439F +:109A500022438C692243CC6922434C6A22438C6A9C +:109A600022431A430260CA6842600A6882604968F9 +:109A7000C16030BD0021016041608160C160016151 +:109A800041618161C1610162416281627047002967 +:109A9000016802D041F0010102E04FF6FE72114070 +:109AA00001607047002A026801D00A4300E08A433F +:109AB0000260704741607047406880B27047C100E3 +:109AC00003D50549091F08607047024908394860F5 +:109AD00070470000080002400804024030B52349E6 +:109AE0008379026853B30B6893430B600A1D1368B4 +:109AF0000468A343136002790A441368046823438B +:109B000013601A4A083213680468A3431360131DD4 +:109B10001C680568AC431C604479102C05D02144B6 +:109B20000A68006802430A6030BD11680468214376 +:109B30001160196800680143196030BD007908445C +:109B400001689143016030BD084A01460020126857 +:109B5000064B0A4014331B680B4202D0002A00D087 +:109B6000012070470149143108607047000401402A +:109B70005A4910B588424FF0010101D14C0501E06E +:109B80004FF48004204600F019F92046BDE810404B +:109B9000002100F013B970B50446808886B00D46E8 +:109BA00020F03F06684600F09FF84D490298B0FB50 +:109BB000F1F189B20E43A680228822F001022280B0 +:109BC000484B2A689A421CD85200B0FBF2F080B28F +:109BD000042800D20420491C2184A083208840F05E +:109BE0000100208021884FF6F5300140A8886A895D +:109BF000104308432080A88929890843208106B0A2 +:109C000070BDEB88A3F53F46FF3E05D102EB420253 +:109C1000B0FBF2F080B208E002EBC20303EB0212E9 +:109C2000B0FBF2F080B240F48040020501D140F078 +:109C300001004FF4967251434FF47A72B1FBF2F186 +:109C400040F40040C7E741F2883101600021818083 +:109C50004BF6FF72C280018141814FF480418181C6 +:109C600070470029018802D041F0010101E021F094 +:109C70000101018070470029018802D041F4807100 +:109C800001E021F48071018070470029018802D031 +:109C900041F4007101E021F4007101807047002956 +:109CA000018802D041F4806101E021F480610180EB +:109CB0007047002A828801D00A4300E08A438280EC +:109CC000704701827047008AC0B2704712B141F0FC +:109CD000010101E001F0FE010182704700540040E3 +:109CE00040420F00A086010030B53C494A683C4B19 +:109CF00012F00C0405D03B4A042C126803D0082C47 +:109D000024D0036000E002604A680F2303EA1212C5 +:109D1000354B9C5C0268E24042604C68072505EACE +:109D200014241C5D22FA04F484604C6805EAD424EF +:109D30001B5DDA40C2604968032303EA91312A4B74 +:109D40001B1F595CB2FBF1F1016130BD4B684C68DF +:109D500003F470134FF0020514F4803F05EB9343B6 +:109D600005D04C68A40300D552085A43CBE71F4ADC +:109D70005343C6E7194A0029516901D0014300E065 +:109D8000814351617047154A0029916901D001430F +:109D900000E0814391617047104A0029D16901D0E8 +:109DA000014300E08143D16170470C4A0029D1682A +:109DB00001D0014300E08143D1607047074A002988 +:109DC000116901D0014300E08143116170470348EC +:109DD000416A41F08071416270470000001002400A +:109DE00000127A000C0400202404002000093D0029 +:109DF00030B50288FD4BFE4C98420DD0A0420BD0EE +:109E0000B0F1804F08D0FB4DA84205D0FA4DA842D2 +:109E100002D0FA4DA84203D122F070054A882A43A5 +:109E2000F74DA84206D0F74DA84203D022F4407562 +:109E3000CA882A4302808A8882850A8802859842D5 +:109E40000AD0A04208D0F04A904205D0EF4A904292 +:109E500002D0EF4A904201D1097A01860121818224 +:109E600030BD30B5028C22F001020284028C83885E +:109E7000048B22F0020224F073050C882C430D8918 +:109E800015434A882A43D94DA8420BD0D84DA84241 +:109E900008D0DD4DA84205D0DC4DA84202D0DC4DF3 +:109EA000A8420DD122F008054A8923F440732A43C1 +:109EB00022F004058A882A438D891D43CB892B43D0 +:109EC00083800483C9888186028430BD70B5028C8A +:109ED00022F010020284028C8488038B0D8823F404 +:109EE000E6464FF6FF7303EA052535430E8922F057 +:109EF000200203EA061616434A8803EA0212324396 +:109F0000BA4EB04202D0BA4EB04215D122F080060D +:109F10004A8924F4406403EA0212324322F04006E4 +:109F20008A8803EA021232438E8903EA86062643B0 +:109F3000CC8903EA8404344384800583C98801877B +:109F4000028470BD70B5028C22F480720284028C8F +:109F50008488838B0D8823F073031D4322F40073E0 +:109F60000E894FF6FF7202EA06261E434B8802EA6C +:109F7000032333439D4EB04202D09D4EB04215D1D3 +:109F800023F400664B8924F4405402EA032333434C +:109F900023F480668B8802EA032333438E8902EA26 +:109FA00006162643CC8902EA041434438480858350 +:109FB000C9888187038470BD70B5028C22F48052F9 +:109FC0000284048C8288838B0D8823F4E6464FF646 +:109FD000FF7303EA0525354324F400560C8903EA90 +:109FE000043434434E8803EA063626437F4CA042AD +:109FF00002D07F4CA04205D122F480448A8903EA32 +:10A000008212224382808583C988A0F8401006848A +:10A0100070BD828B22F440628283828B4FF6FF7385 +:10A0200003EA01210A4382837047828B22F00C02EB +:10A030008283828B0A4382837047028B22F44062C0 +:10A040000283028B4FF6FF7303EA01210A43028366 +:10A050007047F0B5048C24F010040484078B048C42 +:10A060004FF6FF7527F4734705EA03333B4305EAD0 +:10A0700002221A435D4B05EA011698420ED05C4B52 +:10A0800098420BD0B0F1804F08D05A4B984205D07F +:10A09000594B984202D0594B984205D124F02001E7 +:10A0A000314341F0100104E024F0A0030B4343F0DE +:10A0B000100102830184F0BD028B22F00C020283A6 +:10A0C000028B0A430283704770B5048C24F00104AC +:10A0D0000484058B048C4FF6FF7606EA03131343C2 +:10A0E00025F0F305414A2B4390420ED0404A90425E +:10A0F0000BD0B0F1804F08D03E4A904205D03E4A86 +:10A10000904202D03D4A904202D124F0020201E086 +:10A1100024F00A020A4342F001010383018470BD66 +:10A120002DE9F05F0D4604460888304FDFF8C0C0C7 +:10A13000DFF8C0804988AA882B894FF0804960B336 +:10A14000042832D04FF6FF7E082836D0208C9B465C +:10A1500020F480502084A38B268C704600EA0222D3 +:10A1600023F473431A4300EA0B3010430EEA013E16 +:10A17000BC420BD0644509D04C4507D0444505D0BE +:10A180001D4A944202D01D4B9C425AD126F40051E4 +:10A1900041EA0E0141F4805158E02046FFF794FF58 +:10A1A000E9882046BDE8F05F86E72046FFF751FFCB +:10A1B000E9882046BDE8F05F3FE7208C20F48070FE +:10A1C0002084B4F81CA0208C0EEA031313432AF059 +:10A1D000F30A0EEA012B43EA0A03BC4220D064458D +:10A1E0001ED04C451CD044451AD013E0002C014031 +:10A1F000003401400004004000080040000C004012 +:10A2000000100040001400400040014000440140A4 +:10A2100000480140494A944202D0494A944204D13C +:10A2200020F4007040EA0B0002E020F420600843B4 +:10A2300040F48070A3832084E9882046BDE8F05F65 +:10A24000F3E626F402420A4342F48051A0832046FA +:10A250002184E988BDE8F05FDBE64FF6FF7181807D +:10A2600000210180C180418001727047002101807E +:10A2700041808180C180018141818181C18170479C +:10A2800000210180418001228280C18001817047CC +:10A290000029018802D041F0010101E021F0010113 +:10A2A00001807047002930F8441F02D041F400417A +:10A2B00001E0C1F30E0101807047002A828901D0BC +:10A2C0000A4300E08A4382817047028B22F0080231 +:10A2D0000A4302837047028B4FF6FF7322F4006239 +:10A2E00003EA0121114301837047828B22F00802A7 +:10A2F0000A4382837047828B4FF6FF7322F4006219 +:10A3000003EA0121114381837047808E7047008FDB +:10A310007047808F7047B0F84000704702460020B9 +:10A32000138A92890B4202EA010202D0002A00D06D +:10A3300001207047C94301827047000000080040B7 +:10A34000000C004030B50446008A85B00D464CF63E +:10A35000FF710840E98801432182A1894EF6F3107C +:10A360000140A8882A8910436A890A431043A081C2 +:10A37000A08A4FF6FF410840A9890143A18268469F +:10A38000FFF7B2FC3048844201D1039800E0029804 +:10A39000A1890904002900EBC00101EB0010296824 +:10A3A00002DA4FEA410101E04FEA8101B0FBF1F02E +:10A3B0006422B0FBF2F14FEA01114FEA11136FF082 +:10A3C00018056B4300EB8300A3891D044FF0320393 +:10A3D00006D503EBC000B0FBF2F000F0070005E08B +:10A3E00003EB0010B0FBF2F000F00F0008432081F7 +:10A3F00005B030BD0029818902D041F4005101E04F +:10A4000021F400518181704710B5C1F3421301F06E +:10A410001F040121A140012B07D0022B07D01430CB +:10A42000002A026805D00A4304E00C30F8E7103037 +:10A43000F6E78A43026010BD002A828A01D00A43EF +:10A4400000E08A4382827047003801403948384929 +:10A4500041603949416070473648016941F08001E7 +:10A460000161704733490420CA68D20701D0012036 +:10A470007047CA68520701D502207047C968C906EB +:10A48000FBD50320704700B50346FFF7EBFF02E062 +:10A49000FFF7E8FF5B1E012803D0002B00D1052049 +:10A4A00000BD002BF4D1FAE770B505464FF4302615 +:10A4B0003046FFF7E8FF042811D11E4C206940F018 +:10A4C000020020616561206940F040002061304653 +:10A4D000FFF7D9FF216941F6FD721140216170BD7E +:10A4E000F8B5064600204FF4005C00900D4660462B +:10A4F000FFF7C9FF042816D10E4C206940F0010077 +:10A50000206135806046FFF7BEFF41F6FE770428E4 +:10A5100006D1B61C280C009630806046FFF7B3FFCA +:10A52000216939402161F8BD0249C86070470000C7 +:10A530002301674500200240AB89EFCD144815493F +:10A54000026800608A4203D01348804713480047DE +:10A55000134E4FF0090030601248016821F070611D +:10A56000016041020160104C182020600F49104822 +:10A5700008601048D0F800D040680047FEE7FEE7CA +:10A58000FEE7FEE7FEE7FEE7FEE7FEE7FEE7FEE7A3 +:10A59000F04F0020EFBEADDEE5950008ED000008AD +:10A5A0001810024004000140140C0140000C01404E +:10A5B0004434434400F0FF1F2A4910B588420AD1B1 +:10A5C000841401212046FFF7F0FB2046BDE810402F +:10A5D0000021FFF7EABB2449884202D1012104147B +:10A5E00004E0224988420AD10121C4132046FFF722 +:10A5F000E5FB2046BDE810400021FFF7DFBB10BDA2 +:10A6000030B502884C8802F441530A88CD88224331 +:10A610008C882C4322430C8922434C8922438C8909 +:10A620002243CC8922431A430280828B22F40062A7 +:10A630008283098A018230BD0029018802D041F05D +:10A64000400101E021F040010180704781817047A5 +:10A65000808970470246002012890A4200D00120FA +:10A66000704700000030014000380040003C0040CE +:10A670000048704710D20008A0F16101192900D8E4 +:10A68000203870472DE9F05F994615460F468346FE +:10A690004FF0FF36DDF828A011E0A819441009FB9F +:10A6A000047080460146584652469047002802D022 +:10A6B00004DA254603E04046BDE8F09F2646A5EBB8 +:10A6C00006000128E9DC0020F6E740EA01039B07C9 +:10A6D00003D009E008C9121F08C0042AFAD203E017 +:10A6E00011F8013B00F8013B521EF9D27047D2B27B +:10A6F00001E000F8012B491EFBD270470022F6E76B +:10A7000010B513460A4604461946FFF7F0FF2046E7 +:10A7100010BD421E12F8013F002BFBD111F8013B86 +:10A7200002F8013B002BF9D1704730B505462A46A7 +:10A730000B4612F8010B13F8014B08B1A042F8D0F8 +:10A740001CB1002802D06D1CF1E7284630BD10B5C1 +:10A75000044604E00B7800F8013B03B1491C521E8B +:10A76000F8D2204610BDCAB2401E10F8011F8A421E +:10A7700002D00029F9D100207047421C10F8011BBB +:10A780000029FBD1801A70472DE9F04105460020D1 +:10A7900090460E46044600E0641C44450BD2285DFA +:10A7A00000F058F90746305D00F054F9381A02D12C +:10A7B000295D0029F0D1BDE8F08170B5064600F0B2 +:10A7C00059FC046805460A220021304600F048F989 +:10A7D0002C6070BDF0B480EA0102D40F4200B2EBED +:10A7E000410F02D20246084611464A0042D0C30D2C +:10A7F000DDB2C1F3C752AD1A202D35DAC1F316010F +:10A8000041F4000204B15242C5F1200602FA06F1F9 +:10A810002A411044B3EBD05F23D0C4B1012DA0EB8B +:10A82000C35009DCF0BC4FF0004202EAC35200F50D +:10A830000000DBB200F055B9400000F1807000EB81 +:10A84000C350A0F1807040EAD170490009E0490886 +:10A8500041EAC071A0EBC35000F50000400800EBD6 +:10A86000C350F0BC00F034B96142012202EB410157 +:10A87000001BF6E7F0BC704781F00041AAE780F0CA +:10A880000040A7E780EA010210B502F00043400053 +:10A8900026D04A0023D04FEA106101EB1261C0F3C9 +:10A8A0005600C2F3560240F4000042F40002A0FB3E +:10A8B0000220A1F17F014FEA0040140401D000F111 +:10A8C000010050EA124001D44000491EC2B20C06F9 +:10A8D00004EBD010401C4008802A02D003E0002086 +:10A8E00010BD20F00100002900DA0020184310BD3F +:10A8F00030B480EA010202F0004530F0004221F05D +:10A90000004015D0A0B1C0F3C753C2F3C754C2F37F +:10A910001601C0F31600E41A41F4000140F40002ED +:10A920007D34914201D3641C00E04900002C02DA1E +:10A9300030BC002070474FF400000023914201D347 +:10A94000891A034340084FEA4101F7D151B19142BE +:10A9500002D14FF0004105E002D24FF0010101E0C9 +:10A960006FF0010103EBC450284430BC00F0B0B8D4 +:10A97000420005D0C0F3C7525242914201DC002090 +:10A98000704700EBC1507047C10F80EAE070084487 +:10A99000CA079623002100F0A4B89623002211468E +:10A9A00000F09FB800F0004220F00040C10DC0F35D +:10A9B000160040F400007F2901DA00207047962934 +:10A9C00003DCC1F19601C84001E096398840002AB5 +:10A9D000F4D04042704720F00040C10DC0F3160093 +:10A9E00040F400007F2901DA00207047962903DC3B +:10A9F000C1F19601C8407047963988407047000001 +:10AA0000002801DBC0F10040002901DBC1F1004159 +:10AA100081427047002801DBC0F10040002901DBC2 +:10AA2000C1F100418842704730B50B460146002015 +:10AA30002022012409E021FA02F59D4205D303FA00 +:10AA400002F5491B04FA02F52844151EA2F1010281 +:10AA5000F1DC30BDA0F14101192900D82030704748 +:10AA60002DE9F04791460F4680460446002614F82B +:10AA7000015B2DB1FFF7FCFD0068405DC007F6D11A +:10AA80002B2D02D02D2D18D0641E4A463946204663 +:10AA900000F0E1F927B13968A14201D1C7F800807F +:10AAA00071054FF002040BD54042002803DD00F091 +:10AAB000E1FA0460A007BDE8F08746F48066E4E7A9 +:10AAC0000028F8DA00F0D6FA04606FF00040F2E7F0 +:10AAD0000029A8BF7047401C490008BF20F00100B2 +:10AAE000704710B4B0FA80FC00FA0CF050EA010490 +:10AAF00004BF10BC704749B1CCF1200421FA04F422 +:10AB000011FA0CF118BF012121430843A3EB0C01FA +:10AB1000CB1D0106000A002BBEBF002010BC7047F1 +:10AB200000EBC35010440029A4BF10BC7047401C68 +:10AB3000490008BF20F0010010BC7047F0B40028A5 +:10AB400002DCF0BC00207047C0F3C751C0F3160010 +:10AB500040F40000CA0701D14000491E3F2202EB29 +:10AB60006105002211464FF4000626FA01F3134452 +:10AB7000D418844201D8001B1A464000491C1729EA +:10AB8000F3DD5100814202D24FF0FF3100E000219D +:10AB900002EBC550F0BCFFF79BBF10B541000CD0D5 +:10ABA000C0F3C751962908DC7E2909DC06DB410287 +:10ABB00004D000F0004040F07E5010BD002010BDD9 +:10ABC000C1F19604C4F1200100FA01F1E040FFF761 +:10ABD0007FFFA04010BD2DE9FE4F804681EA0300B3 +:10ABE000C00F0C46009021F0004123F00045B8EB67 +:10ABF0000200A94105D24046214690461C460B461C +:10AC0000024623F00040104304D14046214603B0E1 +:10AC1000BDE8F08F270DC7F30A00C3F30A51029075 +:10AC2000401A0190402866DAC3F3130040F4801BF9 +:10AC30000098924620B10023D2EB030A63EB0B0B82 +:10AC400001985946C0F14002504600F0D3F806463C +:10AC50000D4650465946019A00F0EBF810EB0800FB +:10AC60006141002487EA115284EAE7731A433BD01A +:10AC7000009A3AB3019A012A4FEA075210DC001BEE +:10AC800061EB02014FF0004202EA0752CDE90042B7 +:10AC9000001C41F5801132462B4600F038F9B6E72A +:10ACA000001B61EB0201001C41F5801300185B41A1 +:10ACB0002018A2F5001747EB030140EAD570B6193A +:10ACC0006D4111E06D084FEA360645EAC0754FEA5E +:10ACD0000752001B61EB0201001C41F5801149087D +:10ACE0004FEA30000019514132462B4603B0BDE80F +:10ACF000F04F00F0FFB80098012240000023D0EB95 +:10AD0000020263EBE073009821464FEAE074B8EB6F +:10AD1000000061EB0401E9E783F000435BE781F0A9 +:10AD2000004158E710B500F0004420F00040C20D8B +:10AD3000C0F3160040F400007F2A07DA7D2A00DA0B +:10AD40007D22763A00FA02F1002008E0962A09DC1A +:10AD5000A2F1760100FA01F1C2F19602D040FFF7AC +:10AD6000B7FE01E0963A9040002C00D0404210BD62 +:10AD700000F0004230F000400AD0C10D01F56071D2 +:10AD8000C0F3160042EA0151C20840071143704760 +:10AD900000200146704701F0004330B421F000412B +:10ADA00050EA010206D00A0DA2F56072C1F3130148 +:10ADB000002A02DC30BC00207047440F44EAC10482 +:10ADC000C100E01830BC00EBC250FFF781BE0000AC +:10ADD000064C074D06E0E06840F0010394E80700E8 +:10ADE00098471034AC42F6D3F5F784F950DB0008ED +:10ADF00070DB0008202A04DB203A00FA02F1002070 +:10AE000070479140C2F1200320FA03F319439040A8 +:10AE10007047202A04DB203A21FA02F00021704713 +:10AE200021FA02F3D040C2F12002914008431946B2 +:10AE30007047202A06DBCB17203A41FA02F043EA9A +:10AE4000E07306E041FA02F3D040C2F120029140E3 +:10AE50000843194670472DE9F05F824600780027C5 +:10AE600015468B460AF10104B946302801D09DB140 +:10AE700013E014F8010B0127782803D0582801D0DB +:10AE800045B10AE00DB1102D07D10027102514F8A7 +:10AE9000010B02E0082500E00A250026B0460EE07E +:10AEA00005FB080005FB06F1012701EB10461FFA20 +:10AEB00080F8B6F5803F00D3B94614F8010B294657 +:10AEC00000F077F80028EBDABBF1000F05D00FB1E6 +:10AED000641E00E05446CBF80040B9F1000F06D0E4 +:10AEE00000F0C8F802210160C81EBDE8F09F48EAE2 +:10AEF0000640FAE710B5002B08DA401C41F10001CA +:10AF000092185B411A4301D120F0010010BD2DE9D8 +:10AF1000F04D92469B4611B1B1FA81F202E0B0FACF +:10AF200080F220329046FFF765FF04460F4640EA64 +:10AF30000A0041EA0B0153465A46084303D1204612 +:10AF40003946BDE8F08D114653EA010015D0C8F12D +:10AF500040025046FFF75DFF05460E4650465946F3 +:10AF60004246FFF747FF084301D0012000E00020E0 +:10AF7000054346EAE0762C4337430A984FEA4453A8 +:10AF8000A0EB08004FEAD4240A304FF0000244EA54 +:10AF900047544FEAD72502D500200146D1E70105E5 +:10AFA00010196941DDE9084500196941BDE8F04D16 +:10AFB000A0E73A2800D2303820F02002412A01D3FD +:10AFC000A2F13700884201D34FF0FF30704770B5CF +:10AFD00001EB020410F8015B15F0070301D110F832 +:10AFE000013B2A1106D110F8012B03E010F8016B88 +:10AFF00001F8016B5B1EF9D12B0705D40023521E0B +:10B000000FD401F8013BFAE710F8013B02F102020C +:10B01000A1EB030303E013F8015B01F8015B521E8F +:10B02000F9D5A142D6D3002070BD00000FB4054B66 +:10B0300010B503A9044A029800F0E8F810BC5DF8C6 +:10B0400014FB00001523000834040020410008020E +:10B0500018BF04200A0E18BF40F001004FF07F42D5 +:10B0600032EA010108BF40F00200012808BF0520B4 +:10B070007047000000487047380400206FF05E0100 +:10B080000807FFF775BC00002DE9F04D0E46144689 +:10B090004FF07F41B1EB440F9EBF4FF0FF31316065 +:10B0A000BDE8F08D4FF0004040EA0421C4F3C750E2 +:10B0B0007838431100F01F00DFF814C1C0F12002FE +:10B0C000FC445CF823500CEB83038540D3F804C0A8 +:10B0D0002CFA02F72F439D680CFA00FC25FA02F8BF +:10B0E000DB6805FA00F023FA02F240EA02054CEAB6 +:10B0F000080CA7FB0132ACFB01C0A5FB015101EB21 +:10B100000C058D4234BF4FF0010C4FF0000CC118FC +:10B110006144BCF1000F02D0814202D903E08142B8 +:10B1200001D2012000E00020104400F120024FEA8B +:10B1300092188006CA0C40EA42304F03C6F80080DD +:10B14000FFF722FC82463846FFF727FC6FF012011A +:10B15000FFF70EFC07462846FFF71FFC6FF025019E +:10B16000FFF706FC834639465046FFF733FB594646 +:10B17000FFF730FB00F500656FF30B0551462846DD +:10B18000FFF77AFB3946FFF777FB5946FFF777FB66 +:10B190001049FFF777FB07460F492846FFF772FB78 +:10B1A0003946FFF717FB07460C492846FFF76AFBAD +:10B1B0003946FFF70FFB14F0004F08BFBDE8F08DD4 +:10B1C000C8F1805180F000403160BDE8F08D000092 +:10B1D00050210000DB0FC92F22AAFD290000C92F32 +:10B1E00002E008C8121F08C1002AFAD17047704750 +:10B1F000002001E001C1121F002AFBD170470000AE +:10B200000149086070470000380400202DE9FF4F15 +:10B210008BB09A460F4605460026C9E0252837D14F +:10B2200000246D1C6649A04601222B78203B02FABF +:10B2300003F0084202D004436D1CF6E728782E285C +:10B2400017D115F8010F44F004042A280ED06FF02E +:10B250002F022878A0F1300109290AD808EB8801CB +:10B2600002EB410100EB01086D1CF2E757F8048B7B +:10B270006D1C287869283FD006DC002871D063282F +:10B280000CD0642804D137E0732811D075284ED033 +:10B2900052460D99904706F1010688E017F8040B15 +:10B2A0008DF8000000208DF80100E946012003E040 +:10B2B00057F8049B4FF0FF3061074FF0000401D4B2 +:10B2C0000AE0641C44450DDA8442FADB19F80410E4 +:10B2D0000029F6D106E0641C8442FCDB19F8041056 +:10B2E0000029F8D1264404E019F8010B52460D99C3 +:10B2F0009047641EF8D25AE001CF4FF00A0B0028A5 +:10B3000004DAC0F100004FF02D0102E0210504D560 +:10B310002B218DF82410012103E0E10705D0202125 +:10B32000F7E70DF1200908910CE00021F9E701CFC2 +:10B330004FF00A0BF9E75946FFF776FB01F13002AF +:10B3400009F8012D0028F6D1ADEB090000F1200B22 +:10B35000600701D44FF00108D84503DDA8EB0B00CE +:10B3600001E029E000208046002406E009A85246BA +:10B37000005D0D999047761C641C08988442F5DBAB +:10B3800004E0302052460D999047761CB8F1000138 +:10B39000A8F10108F5DC05E019F8010B52460D99FA +:10B3A0009047761CBBF10001ABF1010BF4DC6D1C86 +:10B3B000287800287FF432AF0FB03046BDE8F08F18 +:10B3C000092801002DE9F0474FF0684202EB4003E5 +:10B3D0000C460546B3F1654F3CBF02EB4102B2F1AA +:10B3E000654F3FD34FF07F42B2EB400F28BFB2EB27 +:10B3F000410F03D2BDE8F047FFF7ECB940EA010383 +:10B400005B0008BF44F0FF410AD0B2EB400F08BF19 +:10B41000B2EB410F06D125F0804024F08041054673 +:10B420000C461FE0B2EB400F12BF5FEA410245F04D +:10B43000FF4004F0004115D04FEA410292EA400378 +:10B4400010D4002AB4BF4FF03E564FF09F4631460D +:10B45000FFF718FA054631462046FFF713FA04466F +:10B4600028462146C0F3C753C1F3C7529A1A1B2A74 +:10B4700006DD10F0004F14BF54485548BDE8F08772 +:10B4800012F11A0F17DA11F0004F06D010F0004F2A +:10B490000CBF50485048BDE8F08721462846FFF7CA +:10B4A00027FA0446FFF7D2FD042808BFFFF7E6FDA0 +:10B4B0002046BDE8F0874200B2EB410F25D910F0DD +:10B4C000004F19BF454F464E464F474E224685F026 +:10B4D000004415460A4680F0004110460A1A520000 +:10B4E000B2F1807F3ED248404049DFF804A110F01D +:10B4F000004F18D04FF03F483846FFF7BDF90746D8 +:10B5000051463046FFF7B8F917E011F0004F04BF7D +:10B5100000263746E2D010F0004F19BF354F364EA7 +:10B52000364F374EDAE74FF07C583846FFF752F97E +:10B53000074651463046FFF74DF906464146284634 +:10B54000FFF7A0F92146FFF745F98246214640461C +:10B55000FFF798F92946FFF792F95146FFF7C8F926 +:10B56000044604E021462846FFF7C2F90446014696 +:10B57000FFF788F980462349FFF784F92249FFF74E +:10B5800029F94146FFF77EF92049FFF723F94146A3 +:10B59000FFF778F91E49FFF71DF94146FFF772F9E9 +:10B5A0001C49FFF717F9054641462046FFF76AF99F +:10B5B0002946FFF767F93146FFF70CF92146FFF7F7 +:10B5C00009F93946BDE8F047FFF704B9DB0FC9BFF9 +:10B5D000DB0FC93FDB0F4940DB0F49C00000C9BF8B +:10B5E00022AAFDB90000C93F22AAFD390060ED3E44 +:10B5F000C30ACE37000049C022AA7DBA00004940E4 +:10B6000022AA7D3A2DAD65BD8FB8D53D0FB511BECF +:10B6100061C84C3EA8AAAABE2DE9F84304460246DA +:10B6200050486946B0EB420F09D94FF0E640B0EB05 +:10B63000420F94BF00204FF0FF30009034E04A4B9F +:10B6400022F0004083422BD948492046FFF71AF9DF +:10B65000FFF7A3FA8046FFF7A5F900F0030000907A +:10B6600043494046FFF70EF9054642494046FFF779 +:10B6700009F9064640494046FFF704F907463F49A5 +:10B680004046FFF7FFF82146FFF7F9F83946FFF784 +:10B69000F3F83146FFF7F0F82946FFF7EDF802E03E +:10B6A0001046FFF7F1FC04462546009C002C18DAF2 +:10B6B0006800B0F17F4F3CBF4FF07E50BDE8F8838B +:10B6C00009D14FF00100FFF79BFDBDE8F8430021D1 +:10B6D0000846FFF70DB92846BDE8F8430121FFF7FA +:10B6E00047B9294614F0010F08461CD0FFF7CAF8E5 +:10B6F00006462349FFF7C6F82249FFF7C0F831464E +:10B70000FFF7C0F82049FFF765F83146FFF7BAF8B0 +:10B710002946FFF7B7F82946FFF75CF814F0020F47 +:10B720001CD0BDE8F883FFF7ADF805461749FFF7D1 +:10B73000A9F81749FFF74EF82946FFF7A3F815496E +:10B74000FFF748F82946FFF79DF84FF07E51FFF7C5 +:10B7500041F814F0020F08BFBDE8F88380F0004004 +:10B76000BDE8F883B61F927E490E494683F9223F11 +:10B770001A61342C0020A23300A0FD390000C93F1B +:10B78000336D4C39DA82083CA0AA2ABEB93AB2BA63 +:10B79000CA9F2A3DDDFFFFBE70B50546FFF7C2FA1E +:10B7A00004464000801C0DD12846FFF7F6F90546F7 +:10B7B0002046FFF7E9F82946FFF722F91CBF0120D0 +:10B7C000FFF71EFD204670BD2DE9F04D0F460E46D9 +:10B7D000A0F50001804604464FF0007084B04FF0A1 +:10B7E0007E554FF0000B00EB47004FF07F4AB1F160 +:10B7F000FE4F04D2B0F1804F80F0018141E0B0F102 +:10B80000804F3ED304F1FF40B0F1FE4F1FD200BF86 +:10B8100028F00048C6F3C75044467F2809DB972824 +:10B820007DDAC0F19600012101FA00F0411E31429B +:10B8300009D00120FFF7E4FC04B00021BDE8F04D81 +:10B840000846FFF755B8304218BFFE4DD7E06000FC +:10B8500000281CBF4FF08070B0EB440F0BD91B21A8 +:10B860004046FFF785F8804604466FF01A0B10F04B +:10B87000004FCDD1C3E0A4F50000B0F1FE4F1BD2C4 +:10B88000BDE0B0F1007F11D300213846FFF7B8F8D2 +:10B8900006D16000002818BFBAEB440F71D8B1E799 +:10B8A00006F0004040F0FC563746ABE7B0F1807F31 +:10B8B00038BFA6F50007A5D324F000406FF0FF4283 +:10B8C000E14B8118994210D326F000410A449A4274 +:10B8D0000BD3B4F17E5F18BF5FEA460251D0B0F1DE +:10B8E000FF4F98BFB1F1FF4F06D904B0394640462B +:10B8F000BDE8F04DFEF76EBFB4F1FF4F10D0C6F3B8 +:10B90000C7507F2809DB972812DAC0F19600012181 +:10B9100001FA00F0411E314206D0002009E06EE03D +:10B9200016F0004F5DD127E0304218BF012000D152 +:10B93000022014F5000F13D024B3B4F1004F27D028 +:10B9400014F1814F56D04FF0FE40B0EB440F94BF3E +:10B9500001200020012101EBE671884241D10BE07A +:10B9600016F0004F02D001283FD03AE0012802BF74 +:10B97000B64804B0BDE8F08D4FF0FF4004B0BDE81C +:10B98000F08D37E016F000400ED104B0BDE8F08D28 +:10B99000B6F1FF4F25D016F5000F05D016F0004F79 +:10B9A00018D008B101280AD00220FFF729FC04B002 +:10B9B0000021BDE8F04D4FF07E50FEF799BF022008 +:10B9C000FFF71EFC04B04146BDE8F04D4FF07E503D +:10B9D000FEF78EBF002804BF04B0BDE8F08D01283B +:10B9E00003D004B00020BDE8F08D04B04FF000405B +:10B9F000BDE8F08D04B04FF07E50BDE8F08D944866 +:10BA00002044B0F5005F44D84046FFF7B1F900226A +:10BA1000904BFFF781F9FFF7BEF904466FF0010183 +:10BA2000FEF7A6FF8C49FEF72AFF2146FEF72AFF04 +:10BA30004FF07C51FEF723FF064621460846FEF7ED +:10BA400021FF80F000403146FEF71CFF804683490D +:10BA50002046FEF717FF064681494046FEF712FFD3 +:10BA6000804680492046FEF70DFF4146FEF7B2FEB4 +:10BA7000044601463046FEF7ADFE00F5006B6FF35D +:10BA80000B0B59463046FEF7F7FE2146FEF7A2FEA5 +:10BA9000D4E004F58020C00C00F00F06C0F30710BE +:10BAA0007F38A4EBC05483443046FEF76DFF6FF03F +:10BAB0000301FEF75DFF4FF07E51FEF78BFE01465E +:10BAC00002902046FEF7D8FE019020460299FEF72C +:10BAD00081FE00F500686FF30B0800904146029864 +:10BAE000FEF7CAFE2146FEF775FE02904FF07E502B +:10BAF0000099FEF7FDFE014600900198FEF7C2FE98 +:10BB000000F500646FF30B0420460299FEF7BAFEBD +:10BB1000029041462046FEF7B5FE0199FEF7AFFEC2 +:10BB20000299FEF7A9FE0099FEF7ACFE01460090CF +:10BB30002046FEF74FFE0146FEF7A4FE80464A4926 +:10BB4000FEF7A0FE4449FEF745FE4146FEF79AFE89 +:10BB5000804600212046FEF70BFF01902046009909 +:10BB6000FEF738FE4146FEF78DFE044600210098A0 +:10BB7000FEF7FEFE2146FEF72DFE804601460198A7 +:10BB8000FEF728FE00F500646FF30B0421460198D0 +:10BB9000FEF772FE4146FEF71DFE80463349204601 +:10BBA000FEF770FE009032494046FEF76BFE80467D +:10BBB00030492046FEF766FE4146FEF70BFE804602 +:10BBC00001460098FEF706FE00F500646FF30B04D3 +:10BBD00021460098FEF750FE4146FEF7FBFD8046E9 +:10BBE0002548784450F8361000EBC60001914668AD +:10BBF0004FEA0B10FEF7C8FE009031464046FEF7B4 +:10BC0000E9FD2146FEF7E6FD0199FEF7E3FD009907 +:10BC1000FEF7E0FD00F5006B6FF30B0B5846009943 +:10BC2000FEF72AFE0199FEF727FE2146FEF724FEC5 +:10BC30003146FEF721FE4146FEF721FE804607F51C +:10BC400000641BE0000080BFFFFF3F00000080FF9A +:10BC5000001080C00000F03FABAAAA3E00B0B8417F +:10BC60003BAAB841D49A38BB7EE24C3E00B0384281 +:10BC70003BAA3842D49AB8BB661400006FF30B0499 +:10BC800021463846FEF7F8FD074621465846FEF79E +:10BC9000F9FD064639462046FEF79CFD4146FEF773 +:10BCA000F1FD044639465846FEF7ECFD2146FEF705 +:10BCB00091FD074601463046FEF78CFD00F5006415 +:10BCC0006FF30B0421463046FEF7D6FD3946FEF7EA +:10BCD00081FD804601462046FEF77CFDFFF722F8F5 +:10BCE00007460611FEF750FE2146FEF7C8FD414605 +:10BCF000FEF770FD04463549FEF7C4FD3449FEF7F2 +:10BD000069FD2146FEF7BEFD3249FEF763FD21467F +:10BD1000FEF7B8FD0146304807F00F04784450F8AC +:10BD20002400FEF7AFFD2D49794451F82410FEF7A9 +:10BD300051FD2B49794451F82410FEF74BFD06F1D3 +:10BD40007D01FC2908D23146FEF712FE04B02946D7 +:10BD5000BDE8F04DFEF796BD06F1BF01B1F5BF7F1E +:10BD600016D83146FEF704FE2946FEF78BFD044641 +:10BD7000BAEB440F1AD060000CD02046FFF766F9EA +:10BD8000042808BFFFF77AF9204604B0BDE8F08D1B +:10BD9000002E0BDA0220FFF733FAFFF76FF90146A6 +:10BDA000284604B061F31E00BDE8F08D0220FFF7C5 +:10BDB00027FA61214FF0E040FEF7DAFD0146284600 +:10BDC00004B061F31E00BDE8F08D0000FC5963373C +:10BDD000C9FF753A1872313D2C140000E0130000C1 +:10BDE000941300002DE9F84304460246534869467F +:10BDF000B0EB420F09D94FF0E640B0EB420F94BFD1 +:10BE000000204FF0FF30009034E04D4B22F0004016 +:10BE100083422BD94B492046FEF734FDFEF7BDFE89 +:10BE20008046FEF7BFFD00F0030000904649404603 +:10BE3000FEF728FD054645494046FEF723FD064628 +:10BE400043494046FEF71EFD074642494046FEF77D +:10BE500019FD2146FEF713FD3946FEF70DFD31466B +:10BE6000FEF70AFD2946FEF707FD02E01046FFF740 +:10BE70000BF904462546009C002C1DDA6800B0F141 +:10BE80007F4F09D22846FFF7E1F8042808BFFFF7E3 +:10BE9000F5F82846BDE8F88308D10120FFF7B0F98E +:10BEA000BDE8F84300210846FEF722BD2846BDE85C +:10BEB000F8430121FEF75CBD294614F0010F084646 +:10BEC0001ED0FEF7DFFC05462349FEF7DBFC2349C5 +:10BED000FEF780FC2946FEF7D5FC2149FEF77AFCE7 +:10BEE0002946FEF7CFFC4FF07E51FEF773FC14F0AD +:10BEF000020F08BFBDE8F88380F00040BDE8F8837A +:10BF0000FEF7C0FC06461749FEF7BCFC1649FEF7D3 +:10BF1000B6FC3146FEF7B6FC1449FEF75BFC314631 +:10BF2000FEF7B0FC2946FEF7ADFC2946FEF752FCB1 +:10BF300014F0020FE0D1BDE8F8830000B61F927E36 +:10BF4000490E494683F9223F1A61342C0020A2335E +:10BF500000A0FD390000C93FB93AB2BACA9F2A3DD4 +:10BF6000DDFFFFBE336D4C39DA82083CA0AA2ABE41 +:10BF700070B50546FEF7E2FD044620F00040C0F132 +:10BF8000FF40C00F08D025F00040C0F1FF40C00FB7 +:10BF900004BF0120FFF734F9204670BDCDD2000860 +:10BFA0002AD3000888D30008CAD20008D1D20008DA +:10BFB00069D2000864D20008B8D2000859D200083B +:10BFC00082D300086CD200083BD3000897D3000846 +:10BFD00083D20008FBD2000894D2000852D2000895 +:10BFE000C4D200081DD3000863D3000856D300084C +:10BFF000F4D200080000000009D3000872D3000842 +:10C00000D8D200088ED3000830D3000877D30008B8 +:10C01000A0D20008AFD200086ED300087AD2000880 +:10C0200045D30008A1D300084BD300080DD3000866 +:10C0300077D20008E9D200080000000018D30008F9 +:10C0400073D2000813D3000890D2000845D300082B +:10C050006ED300088CD2000800000000D0D9000880 +:10C060005CD2000843D2000890D900084BD20008E7 +:10C07000F2D4000800000000ABD900083ED9000847 +:10C0800033030008A6D9000838D800088703000841 +:10C090008BD80008ECD80008A906000808D80008CA +:10C0A0001FD700085B070008B9D80008D0D90008DE +:10C0B000D10800081BD500088AD60008F10800083E +:10C0C00003D80008D0D90008BD090008FFD7000830 +:10C0D0000DD80008E909000846D8000809D9000869 +:10C0E000730C0008A3D4000834D20008F70C000831 +:10C0F00090D50008DCD80008AB080008B5D80008C7 +:10C100001CD90008310D0008AED80008A2D80008DC +:10C11000710E00085CD70008D0D900081B0F00087A +:10C12000E9D40008020000007804002000000000AC +:10C1300028230000B5D3000802000000800500207D +:10C14000B0040000A4060000D1D4000802000000E2 +:10C150003C05002000000000D0070000DDD40008EE +:10C16000020000003E05002000000000D007000093 +:10C1700053D4000802000000400500200000000029 +:10C18000D00700003AD60008020000008205002017 +:10C1900000000000D007000043D6000802000000A5 +:10C1A0008405002000000000D007000081D90008AD +:10C1B000020000004205002000000000D00700003F +:10C1C0000BD600080200000044050020000000001B +:10C1D000D0070000BBD30008020000004605002085 +:10C1E00000000000D0070000ABD4000802000000EF +:10C1F0004805002000000000D00700004AD50008D4 +:10C20000020000004A05002032000000F201000098 +:10C210003BD50008020000004C0500203200000061 +:10C22000F201000012D7000800000000860500207F +:10C2300000000000010000006BD5000804000000B1 +:10C240008C050020B004000000C2010067D5000882 +:10C25000040000009005002080250000004B000035 +:10C26000E4D3000800000000940500200000000056 +:10C2700001000000F7D4000800000000880500203D +:10C2800000000000030000007BD500080100000052 +:10C2900089050020FFFFFFFF0400000000D5000813 +:10C2A000000000007E0500200000000002000000E9 +:10C2B0005BD600080000000095050020000000008B +:10C2C0000100000099D40008000000007205002061 +:10C2D0000A000000C800000071D40008000000003F +:10C2E000730500200A000000320000005ED4000840 +:10C2F00000000000740500200A0000003200000069 +:10C300009ED6000800000000750500200000000017 +:10C3100009000000C3D70008000000004E050020FF +:10C320000000000008000000ABD30008000000007F +:10C330004F0500200000000008000000BBD50008E9 +:10C340000000000050050020000000000800000070 +:10C35000E5D6000803000000520500204CFFFFFF57 +:10C3600068010000DAD50008030000005405002031 +:10C370004CFFFFFF6801000065D9000803000000C2 +:10C38000560500204CFFFFFF6801000074D700082D +:10C390000100000058050020FFFFFFFF0100000022 +:10C3A0000ED5000800000000590500200000000024 +:10C3B0000500000000D40008000000006405002013 +:10C3C0000000000080000000B2D50008020000005C +:10C3D0005A05002000000000000100005BD80008A2 +:10C3E000020000005C05002064000000E80300007B +:10C3F0006CD80008020000005E0500206400000008 +:10C40000E803000029D8000800000000E807002029 +:10C4100000000000010000004AD4000800000000F5 +:10C420004E080020000000002000000047D4000853 +:10C43000000000004F080020000000006400000021 +:10C4400070D6000800000000500800200100000025 +:10C45000FA00000084D40008000000005108002009 +:10C46000000000000100000098D700080000000054 +:10C4700052080020000000006400000023D50008DE +:10C48000000000000708002000000000FA00000083 +:10C49000B2D70008000000000808002000000000DB +:10C4A00064000000F8D30008000000000908002024 +:10C4B0000000000064000000BAD70008000000007F +:10C4C0000A08002000000000FA0000002BD5000838 +:10C4D000000000000B0800200000000064000000C5 +:10C4E00088D50008000000000C08002000000000B3 +:10C4F00064000000AFD9000800000000940800208C +:10C5000000000000C8000000BED9000800000000C4 +:10C510009508002000000000C8000000BFD40008FB +:10C520000200000096080020E8030000D007000089 +:10C5300010D40008020000009808002064000000E9 +:10C54000D0070000B0D600080100000087050020D9 +:10C5500000000000040000008AD70008010000006D +:10C560009A080020FFFFFFFF01000000CED700085F +:10C57000010000009B0800200000000001000000F6 +:10C580007ED80008000000009C0800200000000089 +:10C59000FF0000004CD80008000000001408002034 +:10C5A00000000000FA0000002AD40008000000008B +:10C5B00016080020000000006400000039D40008C4 +:10C5C00000000000150800200000000064000000CA +:10C5D0004CD60008000000002408002000000000E5 +:10C5E00001000000F4D5000803000000120800203C +:10C5F000D4FEFFFF2C010000FDD600080300000060 +:10C6000010080020D4FEFFFF2C01000095D5000883 +:10C6100000000000170800200000000030000000AB +:10C62000A3D5000805000000180800200000000045 +:10C6300001000000C1D60008050000001C08002011 +:10C640000000000001000000C4D800080500000040 +:10C6500020080020000000000100000064D700084E +:10C66000030000000E080020B0B9FFFF5046000094 +:10C67000EBD7000800000000ED07002000000000DC +:10C68000C800000026D6000800000000F7070020C0 +:10C6900000000000C8000000D0D300080000000027 +:10C6A0000108002000000000C8000000E0D70008DA +:10C6B00000000000EE07002000000000C80000009D +:10C6C0001BD6000800000000F80700200000000052 +:10C6D000C8000000C5D300080000000002080020C8 +:10C6E00000000000C8000000F5D7000800000000AE +:10C6F000EF07002000000000C800000030D600084E +:10C7000000000000F907002000000000C800000041 +:10C71000DAD3000800000000030800200000000039 +:10C72000C800000094D80008020000009E08002005 +:10C7300000000000D0070000C5D500080000000080 +:10C74000A208002000000000010000004ED70008F1 +:10C7500002000000A40800200A000000D00700002A +:10C7600098D9000802000000A60800200A00000076 +:10C77000D007000059D5000800000000A1080020E3 +:10C78000000000006400000003D600080000000064 +:10C79000EA07002000000000C8000000ECD50008F7 +:10C7A00000000000F407002000000000C8000000A6 +:10C7B000E4D5000800000000FE0700200000000093 +:10C7C000C80000000BD7000800000000E9070020A7 +:10C7D00000000000C8000000F6D6000800000000BD +:10C7E000F307002000000000C8000000EFD600089A +:10C7F00000000000FD07002000000000C80000004D +:10C800007BD9000800000000EB07002000000000BA +:10C81000C800000075D9000800000000F5070020DE +:10C8200000000000C80000006FD9000800000000F0 +:10C83000FF07002000000000C8000000D6D8000854 +:10C8400000000000EC07002000000000C80000000D +:10C85000D0D8000800000000F6070020000000000B +:10C86000C8000000BED8000800000000000800203A +:10C8700000000000C8000000DDD600080000000035 +:10C88000F007002000000000C8000000D5D6000816 +:10C8900000000000FA07002000000000C8000000AF +:10C8A000CDD60008000000000408002000000000B1 +:10C8B000C8000000414552543132333400000000BA +:10C8C0000000803F00000000A8AAAA3F000000006E +:10C8D0000000803F000080BFB0AA2ABF0000000017 +:10C8E0000000803F0000803FB0AA2ABF0000000087 +:10C8F0000000803F000000000000803F000080BF7B +:10C900000000803F000080BF000000000000803F6A +:10C910000000803F0000803F000000000000803FDA +:10C920000000803F00000000000080BF000080BFCA +:10C930000000803F000080BF0000803F000080BFFB +:10C940000000803F000080BF000080BF0000803FEB +:10C950000000803F0000803F0000803F0000803FDB +:10C960000000803F0000803F000080BF000080BFCB +:10C970000000803F0000803F000000000000000039 +:10C980000000803F000080BF0000000000000000A9 +:10C990000000803F00000000A8AAAA3F0000803FDE +:10C9A0000000803F000080BFB0AA2ABF000080BF07 +:10C9B0000000803F0000803FB0AA2ABF000080BF77 +:10C9C0000000803F00000000A8AAAA3F000080BF2E +:10C9D0000000803F000080BFB0AA2ABF0000803F57 +:10C9E0000000803F0000803FB0AA2ABF0000803FC7 +:10C9F0000000803F000080BFD0B35D3F0000803F5B +:10CA00000000803F000080BFD0B35DBF000080BF4A +:10CA10000000803F0000803FD0B35D3F0000803FBA +:10CA20000000803F0000803FD0B35DBF000080BFAA +:10CA30000000803F00000000D0B35DBF0000803FD9 +:10CA40000000803F00000000D0B35D3F000080BFC9 +:10CA50000000803F000000000000803F000080BF19 +:10CA60000000803F000080BF000080BF0000000089 +:10CA70000000803F000000000000803F0000803F79 +:10CA80000000803F0000803F000080BF00000000E9 +:10CA90000000803FD0B35DBF0000803F0000803FBA +:10CAA0000000803FD0B35DBF000080BF0000803F2A +:10CAB0000000803FD0B35D3F0000803F000080BF9A +:10CAC0000000803FD0B35D3F000080BF000080BF0A +:10CAD0000000803FD0B35DBF00000000000080BFB9 +:10CAE0000000803FD0B35D3F000000000000803FA9 +:10CAF0000000803F000080BF0000803F000080BF3A +:10CB00000000803F000080BF000080BF0000803F29 +:10CB10000000803F0000803F0000803F0000803F19 +:10CB20000000803F0000803F000080BF000080BF09 +:10CB30000000803F000080BF0000803F0000803F79 +:10CB40000000803F000080BF000080BF000080BF69 +:10CB50000000803F0000803F0000803F000080BF59 +:10CB60000000803F0000803F000080BF0000803F49 +:10CB70000000803FF704353FF70435BF0000803FD9 +:10CB80000000803FF70435BFF70435BF0000803F49 +:10CB90000000803FF70435BFF704353F0000803FB9 +:10CBA0000000803FF704353FF704353F0000803F29 +:10CBB0000000803F00000000000080BF000080BF38 +:10CBC0000000803F000080BF00000000000080BF28 +:10CBD0000000803F000000000000803F000080BF98 +:10CBE0000000803F0000803F00000000000080BF88 +:10CBF0000000803F0000803F000000BF0000803F39 +:10CC00000000803F000000BF000080BF0000803FA8 +:10CC10000000803F000080BF0000003F0000803F18 +:10CC20000000803F0000003F0000803F0000803F88 +:10CC30000000803F0000003F000080BF000080BF78 +:10CC40000000803F000080BF000000BF000080BFE8 +:10CC50000000803F000000BF0000803F000080BF58 +:10CC60000000803F0000803F0000003F000080BFC8 +:10CC70000000803F000000000000803F0000803F77 +:10CC80000000803F000080BF000080BF0000000067 +:10CC90000000803F000000000000803F000080BFD7 +:10CCA0000000803F0000803F000080BF0000008047 +:10CCB0000000803F000080BF0000803F000080BF78 +:10CCC0000000803F000080BF000080BF0000803F68 +:10CCD0000000803F0000803F0000803F0000803F58 +:10CCE0000000803F0000803F000080BF000080BF48 +:10CCF0000000803F00000000000000000000000075 +:10CD00000000803F00000000000000000000000064 +:10CD10000000803F0000000000000000000080BF15 +:10CD20000000803F00000000000000000000803F85 +:10CD3000000000000000000003010000C0C800085F +:10CD400004000000F0C800080400000030C900081A +:10CD50000201000070C9000800010000000000008E +:10CD60000600000090C9000806000000F0C9000895 +:10CD700001010000000000000400000050CA00088B +:10CD80000600000090CA000808000000F0CA000871 +:10CD90000800000070CB000808000000F0CB00087D +:10CDA0000101000000000000000100000000000080 +:10CDB00000010000000000000400000070CC00082A +:10CDC00006000000B0CC00080001000000000000D8 +:10CDD0000201000010CD0008010100000000000069 +:10CDE0000000000000000000524F4C4C3B504954E2 +:10CDF00043483B5941573B414C543B506F733B5068 +:10CE00006F73523B4E6176523B4C4556454C3B4D01 +:10CE100041473B56454C3B0000C2010017DB000870 +:10CE20003ADB000800E10000F5DA0008E1DA00086A +:10CE300000960000ABDA0008CDDA0008004B0000D5 +:10CE400089DA000875DA000880250000D0D90008CA +:10CE5000D0D90008B56206010300F00500FF19B53E +:10CE60006206010300F00300FD15B5620601030030 +:10CE7000F00100FB11B56206010300F00000FA0F9B +:10CE8000B56206010300F00200FC13B5620601035F +:10CE900000F00400FE17B562060103000102010E56 +:10CEA00047B562060103000103010F49B56206019F +:10CEB0000300010601124FB56206010300011201D1 +:10CEC0001E67B5620616080003070300510800003C +:10CED0008A41B56206080600C80001000100DE6A4A +:10CEE0001048494A4B4C4D44454647FF20212223D8 +:10CEF0002425262748494A4B4C4DFF1048498A8B28 +:10CF00008C8D84858687FF2021222324252627488F +:10CF1000498A8B8C8DFF0000ECCE0008E0CE000823 +:10CF200007CF0008FBCE0008000C014008001002EB +:10CF3000000C014010001002000801400010140213 +:10CF40002D830008C9820008FD8200084B8200087A +:10CF5000E3820008000000400008014001000000DA +:10CF6000001C00000000004000080140020000001A +:10CF7000041C000000000040000801400400000004 +:10CF8000081C0000000000400008014008000000EC +:10CF90000C1C00000004004000080140400000009C +:10CFA000001D000000040040000801408000000057 +:10CFB000041D000000040040000C014001000000BE +:10CFC000081D000000040040000C014002000000A9 +:10CFD0000C1D0000002C0140000801400001000071 +:10CFE000001B0100002C0140000801400008000067 +:10CFF0000C1B010000080040000C01404000000034 +:10D00000001E000000080040000C014080000000ED +:10D01000041E000000080040000C01400001000058 +:10D02000081E000000080040000C01400002000043 +:10D030000C1E00000004080CAB9400086394000868 +:10D0400085940008C394000837930008000000008E +:10D05000000000000000B33FB2BE7D3A00002E4049 +:10D06000DFCF513800007E40BF51FABA00E0A44043 +:10D0700019DAC3BA00E0C840C2ED8AB90040EB40FB +:10D08000CD1F2CBA001006412AFFFABA00C0154184 +:10D09000DFCFD13700D024419A97703A0050334106 +:10D0A00089478E3600404141E75B9D3800B04E41D4 +:10D0B000C00A98B900A05B41558F943A003068418E +:10D0C000DA92C0BA0040744162B3C63A0000803FB1 +:10D0D00000A0853F00908B3F00C0913F0030983FFB +:10D0E00000F09E3F00F0A53F0050AD3F0000B53F6F +:10D0F0000000BD3F0060C53F0020CE3F0040D73F4D +:10D1000000C0E03F00C0EA3F0020F53F0000000003 +:10D110007D36AC397D3C3839EBDCF438320A7E3967 +:10D12000124C26399B6AED39A4EE83397F661E398D +:10D13000F6398A392B426539A48211395B991F3936 +:10D14000C3EECD39DDE7C637A5A22F390000803FF9 +:10D15000C3AA853FC2958B3FD3C3913FF037983F19 +:10D1600032F59E3FD7FEA53F3F58AD3FF304B53F94 +:10D17000A408BD3F2A67C53F8C24CE3FFD44D73F5E +:10D18000DFCCE03FC7C0EA3F7D25F53F004040408F +:10D19000404040404040414141414140404040408A +:10D1A0004040404040404040404040404005020236 +:10D1B00002020202020202020202020202202020F5 +:10D1C0002020202020202002020202020202909051 +:10D1D000909090901010101010101010101010104F +:10D1E00010101010101010100202020202028888A3 +:10D1F00088888888080808080808080808080808AF +:10D200000808080808080808020202024000000096 +:10D210008DD10008000000006E83F9A22915444E4C +:10D22000D15727FCC0DD34F5999562DB4190433C32 +:10D23000AB6351FE696E64657820283020746F20DE +:10D240003229004D50553630353000424D4132388C +:10D250003000565441494C34005934004144584C34 +:10D260003334350048455836005936004F43544F43 +:10D27000583800414343003344004641494C534130 +:10D28000464500414952504C414E45004750532BB2 +:10D290004D41470048454C495F39305F44454700A0 +:10D2A0004759524F5F534D4F4F5448494E47004CDA +:10D2B00045445F52494E4700464C59494E475F57D7 +:10D2C000494E4700484558364800424900545249A3 +:10D2D0000047494D42414C00494E464C494748544D +:10D2E0005F4143435F43414C00534F4654534552C3 +:10D2F00049414C00435553544F4D0048454C495FFC +:10D300003132305F4343504D0050504D0056415232 +:10D31000494F004241524F004759524F0050504D23 +:10D320005F544F5F534552564F0051554144500092 +:10D330004D4F544F525F53544F50004F43544F463C +:10D340004C41545000534F4E415200504F5745529C +:10D350004D455445520053494E474C45434F505458 +:10D360004552004455414C434F505445520047509C +:10D3700053005642415400534552564F5F54494C56 +:10D3800054004845583658005155414458005345BB +:10D390005249414C5258004F43544F464C41545807 +:10D3A0000054454C454D4554525900616C69676EB7 +:10D3B0005F616363006D69647263006E65757472AA +:10D3C000616C3364006770735F706F73725F6400C9 +:10D3D0006770735F706F735F64006770735F6E6117 +:10D3E000765F6400736F667473657269616C5F6900 +:10D3F0006E766572746564007468725F6D6964004E +:10D400006D6F726F6E5F7468726573686F6C6400C5 +:10D410006661696C736166655F6465746563745F9A +:10D420007468726573686F6C640061636378795FB8 +:10D430006465616462616E64006163637A5F646500 +:10D44000616462616E6400796177646561646261E0 +:10D450006E64006D696E636F6D6D616E64007662FF +:10D4600061746D696E63656C6C766F6C7461676511 +:10D4700000766261746D617863656C6C766F6C7454 +:10D4800061676500616C745F686F6C645F6661738F +:10D49000745F6368616E676500766261747363616F +:10D4A0006C650070726F66696C65006465616462CA +:10D4B000616E6433645F7468726F74746C65006667 +:10D4C00061696C736166655F7468726F74746C65B2 +:10D4D000006D696E7468726F74746C65006D61784C +:10D4E0007468726F74746C65006C6F6F7074696DC2 +:10D4F00065004E6F6E65006770735F7479706500CC +:10D5000073657269616C72785F74797065006163CC +:10D51000635F6861726477617265006665617475E6 +:10D5200072650072635F7261746500726F6C6C5F2C +:10D5300070697463685F7261746500736572766F99 +:10D540005F70776D5F72617465006D6F746F725F8D +:10D5500070776D5F72617465006E61765F736C6584 +:10D56000775F7261746500736F6674736572696169 +:10D570006C5F6261756472617465006770735F628D +:10D5800061756472617465007961777261746500B8 +:10D5900073617665006261726F5F7461625F736967 +:10D5A0007A65006261726F5F6E6F6973655F6C7040 +:10D5B00066006779726F5F6C706600616C69676E98 +:10D5C0005F6D6167006E61765F636F6E74726F6C22 +:10D5D000735F68656164696E6700616C69676E5F3F +:10D5E000626F6172645F706974636800695F70691B +:10D5F000746368006163635F7472696D5F706974FE +:10D60000636800705F706974636800646561646278 +:10D61000616E6433645F68696768006770735F7028 +:10D620006F73725F69006770735F706F735F69001B +:10D630006770735F6E61765F69006D696E636865C0 +:10D64000636B006D6178636865636B006163635F42 +:10D65000756E61726D656463616C0074656C656D97 +:10D66000657472795F736F667473657269616C005B +:10D67000616C745F686F6C645F7468726F74746CF3 +:10D68000655F6E65757472616C006C697374206F90 +:10D6900072202D76616C206F722076616C00706F45 +:10D6A0007765725F6164635F6368616E6E656C006D +:10D6B000727373695F6175785F6368616E6E656CC4 +:10D6C000006261726F5F63665F76656C00645F6CB9 +:10D6D0006576656C00695F6C6576656C00705F6C83 +:10D6E0006576656C00616C69676E5F626F6172641C +:10D6F0005F726F6C6C00695F726F6C6C006163636A +:10D700005F7472696D5F726F6C6C00705F726F6CCA +:10D710006C0072657461726465645F61726D007043 +:10D7200072696E7420636F6E666967757261626C90 +:10D73000652073657474696E677320696E2061205B +:10D740007061737461626C6520666F726D006E61EA +:10D75000765F73706565645F6D696E007665727380 +:10D76000696F6E006D61675F6465636C696E61749B +:10D77000696F6E007961775F636F6E74726F6C5F53 +:10D78000646972656374696F6E007961775F64695B +:10D7900072656374696F6E007468726F74746C651F +:10D7A0005F616E676C655F636F7272656374696FEA +:10D7B0006E0072635F6578706F007468725F657881 +:10D7C000706F00616C69676E5F6779726F00747269 +:10D7D000695F756E61726D65645F736572766F0007 +:10D7E0006770735F706F73725F70006770735F70E4 +:10D7F0006F735F70006770735F6E61765F70006D4E +:10D8000061700068656C700064756D70006D6170AA +:10D8100070696E67206F66207263206368616E6E48 +:10D82000656C206F72646572007069645F636F6E0F +:10D8300074726F6C6C65720064657369676E2063E7 +:10D840007573746F6D206D69786572006163635FD5 +:10D850006C70665F666163746F72006779726F5F88 +:10D86000636D70665F666163746F72006779726F73 +:10D870005F636D70666D5F666163746F7200676988 +:10D880006D62616C5F666C6167730064656661758B +:10D890006C7473006770735F77705F726164697531 +:10D8A000730073686F772073797374656D20737478 +:10D8B0006174757300736574006578697400645FE2 +:10D8C000616C74006261726F5F63665F616C7400AB +:10D8D000695F616C7400705F616C74007361766580 +:10D8E00020616E64207265626F6F7400726573658B +:10D8F0007420746F2064656661756C747320616E4A +:10D9000064207265626F6F74006D69786572206E55 +:10D91000616D65206F72206C697374006E616D6556 +:10D920003D76616C7565206F7220626C616E6B2054 +:10D930006F72202A20666F72206C697374006665AE +:10D9400061747572655F6E616D6520617578666C76 +:10D950006167206F7220626C616E6B20666F72204F +:10D960006C69737400616C69676E5F626F61726489 +:10D970005F79617700695F79617700705F796177BE +:10D98000006465616462616E6433645F6C6F77002C +:10D990004D4D4138343578006E61765F7370656542 +:10D9A000645F6D617800636D697800617578006609 +:10D9B00061696C736166655F64656C61790066615D +:10D9C000696C736166655F6F66665F64656C6179DB +:10D9D0000043414D535441423B0043414C49423B7B +:10D9E0000047505320484F4C443B00484541444673 +:10D9F0005245453B00414E474C453B004750532064 +:10DA0000484F4D453B004D41473B0043414D54522B +:10DA100049473B004845414441444A3B0041524D3F +:10DA20003B00484F52495A4F4E3B00564152494FD6 +:10DA30003B004241524F3B004245455045523B005E +:10DA4000474F5645524E4F523B004C4C4947485465 +:10DA5000533B0050415353544852553B004C4544AE +:10DA60004C4F573B004F53442053573B004C4544C9 +:10DA70004D41583B0024504D544B3235312C3139F7 +:10DA80003230302A32320D0A0024505542582C349C +:10DA9000312C312C303030332C303030312C313986 +:10DAA0003230302C302A32330D0A0024505542587F +:10DAB0002C34312C312C303030332C303030312C70 +:10DAC00033383430302C302A32360D0A0024504D91 +:10DAD000544B3235312C33383430302A32370D0A3A +:10DAE0000024504D544B3235312C35373630302AE6 +:10DAF00032430D0A0024505542582C34312C312C1D +:10DB0000303030332C303030312C35373630302C0B +:10DB1000302A32440D0A0024505542582C34312CFE +:10DB2000312C303030332C303030312C31313532F3 +:10DB300030302C302A31450D0A0024504D544B32E0 +:10DB400035312C3131353230302A31460D0A000062 +:10DB500070DB0008000000203C040000CEAF00088D +:10DB600060DC00083C0400202C250000F0B1000817 +:10DB70000196031E7A44CBDC0502A1023701138D06 +:10DB800031025C08021A030936B3914B1DDABC2935 +:10DB90004913F5D92A080832021A22182908297CC3 +:10DBA0001A320C290832041A2B0C290832051A06DD +:10DBB0000C3908311AEB3C290832071A14182908C5 +:10DBC00029591AD118290832091A0B182908320ABA +:10DBD0001AFC182908320B1AE10C2908320C1A53C6 +:10DBE000242908320D1A380C2908320E1A6D0C2916 +:10DBF00008320F1A5D0C290832101A4A0C29083213 +:10DC0000111ADA48290832121A4018290832131A50 +:10DC1000650C2908721402A7FF021001E2045203E6 +:10DC20008B803F0401165A03494AD931E91D12017C +:10DC30000A1C0285C208342C01401A408C1A401973 +:10DC40003A405B14A24A048B127A33380B02030465 +:10DC5000060708090204063B291069148100000028 :04000005080000ED02 :00000001FF diff --git a/src/serial.c b/src/serial.c index b5d61c7ef..d3524bc35 100755 --- a/src/serial.c +++ b/src/serial.c @@ -494,7 +494,7 @@ static void evaluateCommand(void) serialize8(availableBoxes[i]); break; case MSP_MISC: - headSerialReply(2 * 6 + 4 + 2 + 8 * 4); + headSerialReply(2 * 6 + 4 + 2 + 4); serialize16(0); // intPowerTrigger1 (aka useless trash) serialize16(mcfg.minthrottle); serialize16(mcfg.maxthrottle); From bd8b1a1c8f65b026e401249b2d01d56b33123c2e Mon Sep 17 00:00:00 2001 From: dongie Date: Sat, 2 Nov 2013 15:09:46 +0900 Subject: [PATCH 37/56] cleaned up cliMotor(), added MSP_SET_MOTORS and enabled CAP_DYNBALANCE so the motors can be controlled from GUI --- src/cli.c | 48 +++++++++++++++++++++++++++++------------------- src/mixer.c | 8 ++++++-- src/mw.h | 1 + src/serial.c | 11 +++++++++-- 4 files changed, 45 insertions(+), 23 deletions(-) diff --git a/src/cli.c b/src/cli.c index 34e2a3bdf..86f370907 100644 --- a/src/cli.c +++ b/src/cli.c @@ -602,6 +602,8 @@ static void cliExit(char *cmdline) *cliBuffer = '\0'; bufferIndex = 0; cliMode = 0; + // incase some idiot leaves a motor running during motortest, clear it here + mixerResetMotors(); // save and reboot... I think this makes the most sense cliSave(cmdline); } @@ -734,37 +736,45 @@ static void cliMixer(char *cmdline) static void cliMotor(char *cmdline) { - int motor_index; - int motor_value; - int len; - char *tmp = NULL; - char *sep = " "; + int motor_index = 0; + int motor_value = 0; + int len, index = 0; + char *pch = NULL; len = strlen(cmdline); - - tmp = strtok(cmdline, sep); - if (tmp == NULL) { - printf("Usage:\r\n"); - printf("motor [index] shows the output value of one motor\r\n"); - printf("motor [index] [value] sets the output value of one motor\r\n"); + if (len == 0) { + printf("Usage:\r\nmotor index [value] - show [or set] motor value\r\n"); return; } - motor_index = atoi(tmp); + + pch = strtok(cmdline, " "); + while (pch != NULL) { + switch (index) { + case 0: + motor_index = atoi(pch); + break; + case 1: + motor_value = atoi(pch); + break; + } + index++; + pch = strtok(NULL, " "); + } if (motor_index < 0 || motor_index >= MAX_MOTORS) { printf("No such motor, use a number [0, %d]\r\n", MAX_MOTORS); return; } - tmp = strtok(NULL, sep); - if (tmp == NULL) { - tmp = strtok(cmdline, sep); - motor_index = atoi(tmp); - printf("Motor %d is set at %d\r\n", motor_index, - motor_disarmed[motor_index]); + if (index < 2) { + printf("Motor %d is set at %d\r\n", motor_index, motor_disarmed[motor_index]); + return; + } + + if (motor_value < 1000 || motor_value > 2000) { + printf("Invalid motor value, 1000..2000\r\n"); return; } - motor_value = atoi(tmp); printf("Setting motor %d to %d\r\n", motor_index, motor_value); motor_disarmed[motor_index] = motor_value; diff --git a/src/mixer.c b/src/mixer.c index dfc520f67..4e4a892c7 100755 --- a/src/mixer.c +++ b/src/mixer.c @@ -211,11 +211,15 @@ void mixerInit(void) } } } + mixerResetMotors(); +} +void mixerResetMotors(void) +{ + int i; // set disarmed motor values - for (i = 0; i < MAX_MOTORS; i++) { + for (i = 0; i < MAX_MOTORS; i++) motor_disarmed[i] = feature(FEATURE_3D) ? mcfg.neutral3d : mcfg.mincommand; - } } void mixerLoadMix(int index) diff --git a/src/mw.h b/src/mw.h index 414b2e9fc..3cd460a54 100755 --- a/src/mw.h +++ b/src/mw.h @@ -412,6 +412,7 @@ void Sonar_update(void); // Output void mixerInit(void); +void mixerResetMotors(void); void mixerLoadMix(int index); void writeServos(void); void writeMotors(void); diff --git a/src/serial.c b/src/serial.c index d3524bc35..31f2d532f 100755 --- a/src/serial.c +++ b/src/serial.c @@ -3,7 +3,8 @@ // Multiwii Serial Protocol 0 #define MSP_VERSION 0 -#define PLATFORM_32BIT ((uint32_t)1 << 31) +#define CAP_PLATFORM_32BIT ((uint32_t)1 << 31) +#define CAP_DYNBALANCE ((uint32_t)1 << 2) #define MSP_IDENT 100 //out message multitype + multiwii version + protocol version + capability variable #define MSP_STATUS 101 //out message cycletime & errors_count & sensor present & box activation & current setting number @@ -89,6 +90,8 @@ struct box_t { static uint8_t availableBoxes[CHECKBOXITEMS]; // this is the number of filled indexes in above array static uint8_t numberBoxItems = 0; +// from mixer.c +extern int16_t motor_disarmed[MAX_MOTORS]; static const char pidnames[] = "ROLL;" @@ -328,6 +331,10 @@ static void evaluateCommand(void) read8(); // vbatlevel_crit (unused) headSerialReply(0); break; + case MSP_SET_MOTOR: + for (i = 0; i < 8; i++) + motor_disarmed[i] = read16(); + break; case MSP_SELECT_SETTING: if (!f.ARMED) { mcfg.current_profile = read8(); @@ -347,7 +354,7 @@ static void evaluateCommand(void) serialize8(VERSION); // multiwii version serialize8(mcfg.mixerConfiguration); // type of multicopter serialize8(MSP_VERSION); // MultiWii Serial Protocol Version - serialize32(PLATFORM_32BIT); // "capability" + serialize32(CAP_PLATFORM_32BIT | CAP_DYNBALANCE); // "capability" break; case MSP_STATUS: headSerialReply(11); From da0669ef22f6757ca381f5e7edc50f5caf705f80 Mon Sep 17 00:00:00 2001 From: Kemal Hadimli Date: Sat, 2 Nov 2013 08:55:27 +0200 Subject: [PATCH 38/56] increment state_position later, get rid of lte in favor of lt comparisons --- src/gps.c | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/src/gps.c b/src/gps.c index 4639385e1..10f30bcea 100644 --- a/src/gps.c +++ b/src/gps.c @@ -123,12 +123,13 @@ void gpsInitHardware(void) break; if (gpsData.state == GPS_INITIALIZING) { - gpsData.state_position++; - if (gpsData.state_position <= GPS_INIT_ENTRIES) { + if (gpsData.state_position < GPS_INIT_ENTRIES) { // try different speed to INIT - serialSetBaudRate(core.gpsport, gpsInitData[gpsData.state_position - 1].baudrate); + serialSetBaudRate(core.gpsport, gpsInitData[gpsData.state_position].baudrate); // but print our FIXED init string for the baudrate we want to be at serialPrint(core.gpsport, gpsInitData[mcfg.gps_baudrate].ubx); + + gpsData.state_position++; } else { // we're now (hopefully) at the correct rate, next state will switch to it gpsData.baudrateIndex = mcfg.gps_baudrate; @@ -140,10 +141,10 @@ void gpsInitHardware(void) if (gpsData.state_position == 0) serialSetBaudRate(core.gpsport, gpsInitData[gpsData.baudrateIndex].baudrate); - gpsData.state_position++; + if (gpsData.state_position < sizeof(ubloxInit)) { + serialWrite(core.gpsport, ubloxInit[gpsData.state_position]); // send ubx init binary - if (gpsData.state_position <= sizeof(ubloxInit)) { - serialWrite(core.gpsport, ubloxInit[gpsData.state_position - 1]); // send ubx init binary + gpsData.state_position++; } else { // ublox should be init'd, time to try receiving some junk gpsSetState(GPS_RECEIVINGDATA); From 29a9507c1597d36b630c21a5b60b2e7858a374ec Mon Sep 17 00:00:00 2001 From: dongie Date: Sat, 2 Nov 2013 16:22:30 +0900 Subject: [PATCH 39/56] adding untested (and probably non-working) airplane mixer from mwc 2.3 flaperons not implemented (too hacky) flaps should work --- src/cli.c | 1 + src/gps.c | 1 + src/mixer.c | 61 ++++++++++++++++++++++++++++++++++------------------ src/mw.h | 1 + src/serial.c | 3 ++- 5 files changed, 45 insertions(+), 22 deletions(-) diff --git a/src/cli.c b/src/cli.c index 86f370907..831822d68 100644 --- a/src/cli.c +++ b/src/cli.c @@ -121,6 +121,7 @@ const clivalue_t valueTable[] = { { "motor_pwm_rate", VAR_UINT16, &mcfg.motor_pwm_rate, 50, 498 }, { "servo_pwm_rate", VAR_UINT16, &mcfg.servo_pwm_rate, 50, 498 }, { "retarded_arm", VAR_UINT8, &mcfg.retarded_arm, 0, 1 }, + { "flaps_speed", VAR_UINT8, &mcfg.flaps_speed, 0, 100 }, { "serial_baudrate", VAR_UINT32, &mcfg.serial_baudrate, 1200, 115200 }, { "softserial_baudrate", VAR_UINT32, &mcfg.softserial_baudrate, 9600, 19200 }, { "softserial_inverted", VAR_UINT8, &mcfg.softserial_inverted, 0, 1 }, diff --git a/src/gps.c b/src/gps.c index 10f30bcea..0faa04f49 100644 --- a/src/gps.c +++ b/src/gps.c @@ -78,6 +78,7 @@ gpsData_t gpsData; static void gpsNewData(uint16_t c); static bool gpsNewFrameNMEA(char c); static bool gpsNewFrameUBLOX(uint8_t data); + static void gpsSetState(uint8_t state) { gpsData.state = state; diff --git a/src/mixer.c b/src/mixer.c index 4e4a892c7..d30158a68 100755 --- a/src/mixer.c +++ b/src/mixer.c @@ -321,19 +321,16 @@ void writeAllMotors(int16_t mc) static void airplaneMixer(void) { -#if 0 - uint16_t servomid[8]; - int16_t flaperons[2] = { 0, 0 }; - - for (i = 0; i < 8; i++) { - servomid[i] = 1500 + cfg.servotrim[i]; // servo center is 1500? - } + int16_t flapperons[2] = { 0, 0 }; + int i; if (!f.ARMED) - motor[0] = cfg.mincommand; // Kill throttle when disarmed + servo[7] = mcfg.mincommand; // Kill throttle when disarmed else - motor[0] = rcData[THROTTLE]; + servo[7] = constrain(rcCommand[THROTTLE], mcfg.minthrottle, mcfg.maxthrottle); + motor[0] = servo[7]; +#if 0 if (cfg.flaperons) { @@ -354,19 +351,41 @@ static void airplaneMixer(void) } servo[2] = servomid[2] + (slowFlaps * cfg.servoreverse[2]); } - - if (f.PASSTHRU_MODE) { // Direct passthru from RX - servo[3] = servomid[3] + ((rcCommand[ROLL] + flapperons[0]) * cfg.servoreverse[3]); // Wing 1 - servo[4] = servomid[4] + ((rcCommand[ROLL] + flapperons[1]) * cfg.servoreverse[4]); // Wing 2 - servo[5] = servomid[5] + (rcCommand[YAW] * cfg.servoreverse[5]); // Rudder - servo[6] = servomid[6] + (rcCommand[PITCH] * cfg.servoreverse[6]); // Elevator - } else { // Assisted modes (gyro only or gyro+acc according to AUX configuration in Gui - servo[3] = (servomid[3] + ((axisPID[ROLL] + flapperons[0]) * cfg.servoreverse[3])); // Wing 1 - servo[4] = (servomid[4] + ((axisPID[ROLL] + flapperons[1]) * cfg.servoreverse[4])); // Wing 2 - servo[5] = (servomid[5] + (axisPID[YAW] * cfg.servoreverse[5])); // Rudder - servo[6] = (servomid[6] + (axisPID[PITCH] * cfg.servoreverse[6])); // Elevator - } #endif + + if (mcfg.flaps_speed) { + // configure SERVO3 middle point in GUI to using an AUX channel for FLAPS control + // use servo min, servo max and servo rate for proper endpoints adjust + static int16_t slow_LFlaps; + int16_t lFlap = servoMiddle(2); + + lFlap = constrain(lFlap, cfg.servoConf[2].min, cfg.servoConf[2].max); + lFlap = mcfg.midrc - lFlap; // shouldn't this be servoConf[2].middle? + if (slow_LFlaps < lFlap) + slow_LFlaps += mcfg.flaps_speed; + else if (slow_LFlaps > lFlap) + slow_LFlaps -= mcfg.flaps_speed; + + servo[2] = ((int32_t)cfg.servoConf[2].rate * slow_LFlaps) / 100L; + servo[2] += mcfg.midrc; + } + + if (f.PASSTHRU_MODE) { // Direct passthru from RX + servo[3] = rcCommand[ROLL] + flapperons[0]; // Wing 1 + servo[4] = rcCommand[ROLL] + flapperons[1]; // Wing 2 + servo[5] = rcCommand[YAW]; // Rudder + servo[6] = rcCommand[PITCH]; // Elevator + } else { + // Assisted modes (gyro only or gyro+acc according to AUX configuration in Gui + servo[3] = axisPID[ROLL] + flapperons[0]; // Wing 1 + servo[4] = axisPID[ROLL] + flapperons[1]; // Wing 2 + servo[5] = axisPID[YAW]; // Rudder + servo[6] = axisPID[PITCH]; // Elevator + } + for (i = 3; i < 7; i++) { + servo[i] = ((int32_t)cfg.servoConf[i].rate * servo[i]) / 100L; // servo rates + servo[i] += servoMiddle(i); + } } void mixTable(void) diff --git a/src/mw.h b/src/mw.h index 3cd460a54..7f9d7d7e0 100755 --- a/src/mw.h +++ b/src/mw.h @@ -264,6 +264,7 @@ typedef struct master_t { uint16_t mincheck; // minimum rc end uint16_t maxcheck; // maximum rc end uint8_t retarded_arm; // allow disarsm/arm on throttle down + roll left/right + uint8_t flaps_speed; // airplane mode flaps, 0 = no flaps, > 0 = flap speed, larger = faster uint8_t rssi_aux_channel; // Read rssi from channel. 1+ = AUX1+, 0 to disable. diff --git a/src/serial.c b/src/serial.c index 31f2d532f..001ac6f17 100755 --- a/src/serial.c +++ b/src/serial.c @@ -5,6 +5,7 @@ #define MSP_VERSION 0 #define CAP_PLATFORM_32BIT ((uint32_t)1 << 31) #define CAP_DYNBALANCE ((uint32_t)1 << 2) +#define CAP_FLAPS ((uint32_t)1 << 3) #define MSP_IDENT 100 //out message multitype + multiwii version + protocol version + capability variable #define MSP_STATUS 101 //out message cycletime & errors_count & sensor present & box activation & current setting number @@ -354,7 +355,7 @@ static void evaluateCommand(void) serialize8(VERSION); // multiwii version serialize8(mcfg.mixerConfiguration); // type of multicopter serialize8(MSP_VERSION); // MultiWii Serial Protocol Version - serialize32(CAP_PLATFORM_32BIT | CAP_DYNBALANCE); // "capability" + serialize32(CAP_PLATFORM_32BIT | CAP_DYNBALANCE | (mcfg.flaps_speed ? CAP_FLAPS : 0)); // "capability" break; case MSP_STATUS: headSerialReply(11); From 33de2191df4b9b797e986da7463a2358c2e8cfdc Mon Sep 17 00:00:00 2001 From: dongie Date: Sat, 2 Nov 2013 16:59:32 +0900 Subject: [PATCH 40/56] fuck git --- src/mixer.c | 16 ---------------- 1 file changed, 16 deletions(-) diff --git a/src/mixer.c b/src/mixer.c index d30158a68..9af75496a 100755 --- a/src/mixer.c +++ b/src/mixer.c @@ -335,22 +335,6 @@ static void airplaneMixer(void) } - - if (cfg.flaps) { - int16_t flap = 1500 - constrain(rcData[cfg.flaps], cfg.servoendpoint_low[2], cfg.servoendpoint_high[2]); - static int16_t slowFlaps = flap; - - if (cfg.flapspeed) { - if (slowFlaps < flap) { - slowFlaps += cfg.flapspeed; - } else if (slowFlaps > flap) { - slowFlaps -= cfg.flapspeed; - } - } else { - slowFlaps = flap; - } - servo[2] = servomid[2] + (slowFlaps * cfg.servoreverse[2]); - } #endif if (mcfg.flaps_speed) { From 05a61e9cdaaa3b8750be02bb9ca83c35b3c9ba55 Mon Sep 17 00:00:00 2001 From: dongie Date: Sat, 2 Nov 2013 22:48:44 +0900 Subject: [PATCH 41/56] more ignores added --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index bb41fd5b6..262bce188 100644 --- a/.gitignore +++ b/.gitignore @@ -4,3 +4,4 @@ *.dep *.bak *.uvgui.* +obj/ From bff260c7c601b6adf67d654387a49ab9bd07d34b Mon Sep 17 00:00:00 2001 From: dongie Date: Sat, 2 Nov 2013 22:51:56 +0900 Subject: [PATCH 42/56] logic and whitespace fixes in gps passthrough --- src/cli.c | 7 +++---- src/gps.c | 7 +++---- 2 files changed, 6 insertions(+), 8 deletions(-) diff --git a/src/cli.c b/src/cli.c index 234d5b9b2..f42e25a6a 100644 --- a/src/cli.c +++ b/src/cli.c @@ -669,11 +669,10 @@ static void cliFeature(char *cmdline) static void cliGpsPassthrough(char *cmdline) { - cliPrint("Enabling GPS passthrough..."); - - if (gpsSetPassthrough() == -1) { + if (gpsSetPassthrough() == -1) cliPrint("Error: Enable and plug in GPS first\r\n"); - } + else + cliPrint("Enabling GPS passthrough...\r\n"); } static void cliHelp(char *cmdline) diff --git a/src/gps.c b/src/gps.c index e976f554f..4df644d50 100644 --- a/src/gps.c +++ b/src/gps.c @@ -542,7 +542,7 @@ int8_t gpsSetPassthrough(void) if (gpsData.state != GPS_RECEIVINGDATA) return -1; -// get rid of callback + // get rid of callback core.gpsport->callback = NULL; LED0_OFF; @@ -553,16 +553,15 @@ int8_t gpsSetPassthrough(void) LED0_ON; serialWrite(core.mainport, serialRead(core.gpsport)); LED0_OFF; - } + } if (serialTotalBytesWaiting(core.mainport)) { LED1_ON; serialWrite(core.gpsport, serialRead(core.mainport)); LED1_OFF; - } } + } } - // OK here is the onboard GPS code //////////////////////////////////////////////////////////////////////////////////// From b996b26cbb2d535f7d25531307ee37218b4f9a0b Mon Sep 17 00:00:00 2001 From: Lukas S Date: Sun, 3 Nov 2013 03:40:16 +0100 Subject: [PATCH 43/56] new Baseflight PID full gyro scale is used now and a new pid with float calculations was added based on PIDrewrite eeprom size was also increased from 1kB to 2kB --- src/cli.c | 13 ++++++- src/config.c | 17 +++++++-- src/drv_l3g4200d.c | 8 ++--- src/drv_mpu3050.c | 8 ++--- src/drv_mpu6050.c | 8 ++--- src/imu.c | 4 ++- src/mw.c | 88 ++++++++++++++++++++++++++++++++++++++++++---- src/mw.h | 8 ++++- src/serial.c | 58 +++++++++++++++++++++++++----- src/utils.c | 10 ++++++ src/utils.h | 1 + 11 files changed, 192 insertions(+), 31 deletions(-) diff --git a/src/cli.c b/src/cli.c index f42e25a6a..40457bc86 100644 --- a/src/cli.c +++ b/src/cli.c @@ -147,7 +147,7 @@ const clivalue_t valueTable[] = { { "gyro_lpf", VAR_UINT16, &mcfg.gyro_lpf, 0, 256 }, { "gyro_cmpf_factor", VAR_UINT16, &mcfg.gyro_cmpf_factor, 100, 1000 }, { "gyro_cmpfm_factor", VAR_UINT16, &mcfg.gyro_cmpfm_factor, 100, 1000 }, - { "pid_controller", VAR_UINT8, &cfg.pidController, 0, 1 }, + { "pid_controller", VAR_UINT8, &cfg.pidController, 0, 2 }, { "deadband", VAR_UINT8, &cfg.deadband, 0, 32 }, { "yawdeadband", VAR_UINT8, &cfg.yawdeadband, 0, 100 }, { "alt_hold_throttle_neutral", VAR_UINT8, &cfg.alt_hold_throttle_neutral, 1, 250 }, @@ -201,6 +201,17 @@ const clivalue_t valueTable[] = { { "p_yaw", VAR_UINT8, &cfg.P8[YAW], 0, 200 }, { "i_yaw", VAR_UINT8, &cfg.I8[YAW], 0, 200 }, { "d_yaw", VAR_UINT8, &cfg.D8[YAW], 0, 200 }, + { "Ppitchf", VAR_FLOAT, &cfg.P_f[PITCH], 0, 100 }, + { "Ipitchf", VAR_FLOAT, &cfg.I_f[PITCH], 0, 100 }, + { "Dpitchf", VAR_FLOAT, &cfg.D_f[PITCH], 0, 100 }, + { "Prollf", VAR_FLOAT, &cfg.P_f[ROLL], 0, 100 }, + { "Irollf", VAR_FLOAT, &cfg.I_f[ROLL], 0, 100 }, + { "Drollf", VAR_FLOAT, &cfg.D_f[ROLL], 0, 100 }, + { "Pyawf", VAR_FLOAT, &cfg.P_f[YAW], 0, 100 }, + { "Iyawf", VAR_FLOAT, &cfg.I_f[YAW], 0, 100 }, + { "Dyawf", VAR_FLOAT, &cfg.D_f[YAW], 0, 100 }, + { "level_horizon", VAR_FLOAT, &cfg.H_level, 0, 10 }, + { "level_angle", VAR_FLOAT, &cfg.A_level, 0, 10 }, { "p_alt", VAR_UINT8, &cfg.P8[PIDALT], 0, 200 }, { "i_alt", VAR_UINT8, &cfg.I8[PIDALT], 0, 200 }, { "d_alt", VAR_UINT8, &cfg.D8[PIDALT], 0, 200 }, diff --git a/src/config.c b/src/config.c index 7e715675a..7b42523c6 100755 --- a/src/config.c +++ b/src/config.c @@ -7,7 +7,7 @@ #endif #define FLASH_PAGE_SIZE ((uint16_t)0x400) -#define FLASH_WRITE_ADDR (0x08000000 + (uint32_t)FLASH_PAGE_SIZE * (FLASH_PAGE_COUNT - 1)) // use the last KB for storage +#define FLASH_WRITE_ADDR (0x08000000 + (uint32_t)FLASH_PAGE_SIZE * (FLASH_PAGE_COUNT - 2)) // use the last 2 KB for storage master_t mcfg; // master config struct with data independent from profiles config_t cfg; // profile config struct @@ -118,7 +118,7 @@ retry: FLASH_Unlock(); FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR); - if (FLASH_ErasePage(FLASH_WRITE_ADDR) == FLASH_COMPLETE) { + if (FLASH_ErasePage(FLASH_WRITE_ADDR) == FLASH_COMPLETE && FLASH_ErasePage(FLASH_WRITE_ADDR + FLASH_PAGE_SIZE) == FLASH_COMPLETE) { for (i = 0; i < sizeof(master_t); i += 4) { status = FLASH_ProgramWord(FLASH_WRITE_ADDR + i, *(uint32_t *) ((char *)&mcfg + i)); if (status != FLASH_COMPLETE) { @@ -246,6 +246,19 @@ static void resetConf(void) cfg.P8[PIDVEL] = 0; cfg.I8[PIDVEL] = 0; cfg.D8[PIDVEL] = 0; + + cfg.P_f[ROLL] = 2.5f; // new PID with preliminary defaults test carefully + cfg.I_f[ROLL] = 0.3f; + cfg.D_f[ROLL] = 0.06f; + cfg.P_f[PITCH] = 2.5f; + cfg.I_f[PITCH] = 0.3f; + cfg.D_f[PITCH] = 0.06f; + cfg.P_f[YAW] = 8.0f; + cfg.I_f[YAW] = 0.5f; + cfg.D_f[YAW] = 0.05f; + cfg.A_level = 5.0f; + cfg.H_level = 3.0f; + cfg.rcRate8 = 90; cfg.rcExpo8 = 65; cfg.rollPitchRate = 0; diff --git a/src/drv_l3g4200d.c b/src/drv_l3g4200d.c index 4c8e2af62..658acd662 100644 --- a/src/drv_l3g4200d.c +++ b/src/drv_l3g4200d.c @@ -44,7 +44,7 @@ bool l3g4200dDetect(sensor_t *gyro, uint16_t lpf) gyro->read = l3g4200dRead; // 14.2857dps/lsb scalefactor - gyro->scale = (((32767.0f / 14.2857f) * M_PI) / ((32767.0f / 4.0f) * 180.0f * 1000000.0f)); + gyro->scale = 1.0f / 14.2857f; // default LPF is set to 32Hz switch (lpf) { @@ -89,9 +89,9 @@ static void l3g4200dRead(int16_t *gyroData) int16_t data[3]; i2cRead(L3G4200D_ADDRESS, L3G4200D_AUTOINCR | L3G4200D_GYRO_OUT, 6, buf); - data[X] = (int16_t)((buf[0] << 8) | buf[1]) / 4; - data[Y] = (int16_t)((buf[2] << 8) | buf[3]) / 4; - data[Z] = (int16_t)((buf[4] << 8) | buf[5]) / 4; + data[X] = (int16_t)((buf[0] << 8) | buf[1]); + data[Y] = (int16_t)((buf[2] << 8) | buf[3]); + data[Z] = (int16_t)((buf[4] << 8) | buf[5]); alignSensors(data, gyroData, gyroAlign); } diff --git a/src/drv_mpu3050.c b/src/drv_mpu3050.c index 133ab7b10..5ac3d4623 100755 --- a/src/drv_mpu3050.c +++ b/src/drv_mpu3050.c @@ -45,7 +45,7 @@ bool mpu3050Detect(sensor_t *gyro, uint16_t lpf) gyro->read = mpu3050Read; gyro->temperature = mpu3050ReadTemp; // 16.4 dps/lsb scalefactor - gyro->scale = (((32767.0f / 16.4f) * M_PI) / ((32767.0f / 4.0f) * 180.0f * 1000000.0f)); + gyro->scale = 1.0f / 16.4f; // default lpf is 42Hz switch (lpf) { @@ -99,9 +99,9 @@ static void mpu3050Read(int16_t *gyroData) int16_t data[3]; i2cRead(MPU3050_ADDRESS, MPU3050_GYRO_OUT, 6, buf); - data[0] = (int16_t)((buf[0] << 8) | buf[1]) / 4; - data[1] = (int16_t)((buf[2] << 8) | buf[3]) / 4; - data[2] = (int16_t)((buf[4] << 8) | buf[5]) / 4; + data[0] = (int16_t)((buf[0] << 8) | buf[1]); + data[1] = (int16_t)((buf[2] << 8) | buf[3]); + data[2] = (int16_t)((buf[4] << 8) | buf[5]); alignSensors(data, gyroData, gyroAlign); } diff --git a/src/drv_mpu6050.c b/src/drv_mpu6050.c index 94bfc79d8..1637afb7c 100644 --- a/src/drv_mpu6050.c +++ b/src/drv_mpu6050.c @@ -167,7 +167,7 @@ bool mpu6050Detect(sensor_t *acc, sensor_t *gyro, uint16_t lpf, uint8_t *scale) gyro->read = mpu6050GyroRead; // 16.4 dps/lsb scalefactor - gyro->scale = (4.0f / 16.4f) * (M_PI / 180.0f) * 0.000001f; + gyro->scale = 1.0f / 16.4f; // give halfacc (old revision) back to system if (scale) @@ -261,9 +261,9 @@ static void mpu6050GyroRead(int16_t *gyroData) int16_t data[3]; i2cRead(MPU6050_ADDRESS, MPU_RA_GYRO_XOUT_H, 6, buf); - data[0] = (int16_t)((buf[0] << 8) | buf[1]) / 4; - data[1] = (int16_t)((buf[2] << 8) | buf[3]) / 4; - data[2] = (int16_t)((buf[4] << 8) | buf[5]) / 4; + data[0] = (int16_t)((buf[0] << 8) | buf[1]); + data[1] = (int16_t)((buf[2] << 8) | buf[3]); + data[2] = (int16_t)((buf[4] << 8) | buf[5]); alignSensors(data, gyroData, gyroAlign); } diff --git a/src/imu.c b/src/imu.c index d4a738006..ad64da3e8 100755 --- a/src/imu.c +++ b/src/imu.c @@ -19,6 +19,7 @@ int32_t vario = 0; // variometer in cm/s int16_t throttleAngleCorrection = 0; // correction of throttle in lateral wind, float magneticDeclination = 0.0f; // calculated at startup from config float accVelScale; +float gyroScaleRad; // ************** // gyro+acc IMU @@ -34,6 +35,7 @@ void imuInit(void) { accZ_25deg = acc_1G * cosf(RAD * 25.0f); accVelScale = 9.80665f / acc_1G / 10000.0f; + gyroScaleRad = gyro.scale * (M_PI / 180.0f) * 0.000001f; #ifdef MAG // if mag sensor is enabled, use it @@ -261,7 +263,7 @@ static void getEstimatedAttitude(void) uint32_t deltaT; float scale, deltaGyroAngle[3]; deltaT = currentT - previousT; - scale = deltaT * gyro.scale; + scale = deltaT * gyroScaleRad; previousT = currentT; // Initialization diff --git a/src/mw.c b/src/mw.c index 968788476..551c46742 100755 --- a/src/mw.c +++ b/src/mw.c @@ -25,6 +25,7 @@ rcReadRawDataPtr rcReadRawFunc = NULL; // receive data from default (pwm/ppm) o static void pidMultiWii(void); static void pidRewrite(void); +static void pidBaseflight(void); pidControllerFuncPtr pid_controller = pidMultiWii; // which pid controller are we using, defaultMultiWii uint8_t dynP8[3], dynI8[3], dynD8[3]; @@ -278,8 +279,78 @@ static void mwVario(void) } static int32_t errorGyroI[3] = { 0, 0, 0 }; +static float errorGyroIf[3] = { 0.0f, 0.0f, 0.0f }; static int32_t errorAngleI[2] = { 0, 0 }; +static void pidBaseflight() +{ + float RateError, errorAngle, AngleRate, gyroRate; + float ITerm,PTerm,DTerm; + static float lastGyroRate[3]; + static float delta1[3], delta2[3]; + float delta, deltaSum; + float dT; + int axis; + + dT = (float)cycleTime * 0.000001f; + + // ----------PID controller---------- + for (axis = 0; axis < 3; axis++) { + // -----Get the desired angle rate depending on flight mode + if ((f.ANGLE_MODE || f.HORIZON_MODE) && axis < 2 ) { // MODE relying on ACC + // calculate error and limit the angle to 50 degrees max inclination + errorAngle = (constrain(rcCommand[axis] + GPS_angle[axis], -500, +500) - angle[axis] + cfg.angleTrim[axis]) / 10.0f; // 16 bits is ok here + } + if (axis == 2) { // YAW is always gyro-controlled (MAG correction is applied to rcCommand) 100dps to 1100dps max yaw rate + AngleRate = (float)((cfg.yawRate + 10) * rcCommand[YAW]) / 50.0f; + } else { + if (!f.ANGLE_MODE) { //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID + AngleRate = (float)((cfg.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 + AngleRate += errorAngle * cfg.H_level; + } + } else { // it's the ANGLE mode - control is angle based, so control loop is needed + AngleRate = errorAngle * cfg.A_level; + } + } + + gyroRate = gyroData[axis] * gyro.scale; // gyro output scaled to dps + + // --------low-level gyro-based PID. ---------- + // Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes + // -----calculate scaled error.AngleRates + // multiplication of rcCommand corresponds to changing the sticks scaling here + RateError = AngleRate - gyroRate; + + // -----calculate P component + PTerm = RateError * cfg.P_f[axis]; + // -----calculate I component + errorGyroIf[axis] = constrainf(errorGyroIf[axis] + RateError * dT * cfg.I_f[axis], -250.0f, 250.0f); + + // limit maximum integrator value to prevent WindUp - accumulating extreme values when system is saturated. + // I coefficient (I8) moved before integration to make limiting independent from PID settings + ITerm = errorGyroIf[axis]; + + //-----calculate D-term + delta = gyroRate - lastGyroRate[axis]; // 16 bits is ok here, the dif between 2 consecutive gyro reads is limited to 800 + lastGyroRate[axis] = gyroRate; + + // Correct difference by cycle time. Cycle time is jittery (can be different 2 times), so calculated difference + // would be scaled by different dt each time. Division by dT fixes that. + delta *= (1.0f / dT); + // add moving average here to reduce noise + deltaSum = delta1[axis] + delta2[axis] + delta; + delta2[axis] = delta1[axis]; + delta1[axis] = delta; + DTerm = constrainf((deltaSum / 3.0f) * cfg.D_f[axis], -300.0f, 300.0f); + + // -----calculate total PID output + axisPID[axis] = constrain(lrintf(PTerm + ITerm - DTerm), -1000, 1000); + } + +} + static void pidMultiWii(void) { int axis, prop; @@ -304,14 +375,14 @@ static void pidMultiWii(void) } if (!f.ANGLE_MODE || f.HORIZON_MODE || axis == 2) { // MODE relying on GYRO or YAW axis error = (int32_t)rcCommand[axis] * 10 * 8 / cfg.P8[axis]; - error -= gyroData[axis]; + error -= gyroData[axis] / 4; PTermGYRO = rcCommand[axis]; errorGyroI[axis] = constrain(errorGyroI[axis] + error, -16000, +16000); // WindUp - if (abs(gyroData[axis]) > 640) + if (abs(gyroData[axis]) > 2560) errorGyroI[axis] = 0; - ITermGYRO = (errorGyroI[axis] / 125 * cfg.I8[axis]) >> 6; + ITermGYRO = (errorGyroI[axis] / 125 * cfg.I8[axis]) / 64; } if (f.HORIZON_MODE && axis < 2) { PTerm = (PTermACC * (500 - prop) + PTermGYRO * prop) / 500; @@ -326,8 +397,8 @@ static void pidMultiWii(void) } } - PTerm -= (int32_t)gyroData[axis] * dynP8[axis] / 10 / 8; // 32 bits is needed for calculation - delta = gyroData[axis] - lastGyro[axis]; + PTerm -= ((int32_t)gyroData[axis] / 4) * dynP8[axis] / 10 / 8; // 32 bits is needed for calculation + delta = (gyroData[axis] - lastGyro[axis]) / 4; lastGyro[axis] = gyroData[axis]; deltaSum = delta1[axis] + delta2[axis] + delta; delta2[axis] = delta1[axis]; @@ -374,7 +445,7 @@ static void pidRewrite(void) // Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes // -----calculate scaled error.AngleRates // multiplication of rcCommand corresponds to changing the sticks scaling here - RateError = AngleRateTmp - gyroData[axis]; + RateError = AngleRateTmp - (gyroData[axis] / 4); // -----calculate P component PTerm = (RateError * cfg.P8[axis]) >> 7; @@ -418,6 +489,8 @@ void setPIDController(int type) case 1: pid_controller = pidRewrite; break; + case 2: + pid_controller = pidBaseflight; } } @@ -514,6 +587,9 @@ void loop(void) errorGyroI[ROLL] = 0; errorGyroI[PITCH] = 0; errorGyroI[YAW] = 0; + errorGyroIf[ROLL] = 0; + errorGyroIf[PITCH] = 0; + errorGyroIf[YAW] = 0; errorAngleI[ROLL] = 0; errorAngleI[PITCH] = 0; if (cfg.activate[BOXARM] > 0) { // Arming/Disarming via ARM BOX diff --git a/src/mw.h b/src/mw.h index f9efeee58..59cc54729 100755 --- a/src/mw.h +++ b/src/mw.h @@ -150,10 +150,16 @@ enum { #define CALIBRATING_BARO_CYCLES 200 typedef struct config_t { - uint8_t pidController; // 0 = multiwii original, 1 = rewrite from http://www.multiwii.com/forum/viewtopic.php?f=8&t=3671 + uint8_t pidController; // 0 = multiwii original, 1 = rewrite from http://www.multiwii.com/forum/viewtopic.php?f=8&t=3671, 2 = Luggi09s new baseflight pid uint8_t P8[PIDITEMS]; uint8_t I8[PIDITEMS]; uint8_t D8[PIDITEMS]; + + float P_f[3]; // float p i and d factors for the new baseflight pid + float I_f[3]; + float D_f[3]; + float A_level; + float H_level; uint8_t rcRate8; uint8_t rcExpo8; diff --git a/src/serial.c b/src/serial.c index 001ac6f17..13182400c 100755 --- a/src/serial.c +++ b/src/serial.c @@ -296,10 +296,31 @@ static void evaluateCommand(void) headSerialReply(0); break; case MSP_SET_PID: - for (i = 0; i < PIDITEMS; i++) { - cfg.P8[i] = read8(); - cfg.I8[i] = read8(); - cfg.D8[i] = read8(); + if (cfg.pidController == 2) { + for (i = 0; i < 3; i++) { + cfg.P_f[i] = (float)read8() / 10.0f; + cfg.I_f[i] = (float)read8() / 100.0f; + cfg.D_f[i] = (float)read8() / 1000.0f; + } + for (i = 3; i < PIDITEMS; i++) { + if(i == PIDLEVEL) { + cfg.A_level = (float)read8() / 10.0f; + cfg.H_level = (float)read8() / 10.0f; + read8(); + } + else { + cfg.P8[i] = read8(); + cfg.I8[i] = read8(); + cfg.D8[i] = read8(); + } + } + } + else { + for (i = 0; i < PIDITEMS; i++) { + cfg.P8[i] = read8(); + cfg.I8[i] = read8(); + cfg.D8[i] = read8(); + } } headSerialReply(0); break; @@ -477,10 +498,31 @@ static void evaluateCommand(void) break; case MSP_PID: headSerialReply(3 * PIDITEMS); - for (i = 0; i < PIDITEMS; i++) { - serialize8(cfg.P8[i]); - serialize8(cfg.I8[i]); - serialize8(cfg.D8[i]); + if (cfg.pidController == 2) { // convert float stuff into uint8_t to keep backwards compatability with all 8-bit shit with new pid + for (i = 0; i < 3; i++) { + serialize8(constrain(lrintf(cfg.P_f[i] * 10.0f) ,0 ,250)); + serialize8(constrain(lrintf(cfg.I_f[i] * 100.0f) ,0 ,250)); + serialize8(constrain(lrintf(cfg.D_f[i] * 1000.0f) ,0 ,100)); + } + for (i = 3; i < PIDITEMS; i++) { + if (i == PIDLEVEL) { + serialize8(constrain(lrintf(cfg.A_level * 10.0f) ,0 ,250)); + serialize8(constrain(lrintf(cfg.H_level * 10.0f) ,0 ,250)); + serialize8(0); + } + else { + serialize8(cfg.P8[i]); + serialize8(cfg.I8[i]); + serialize8(cfg.D8[i]); + } + } + } + else { + for (i = 0; i < PIDITEMS; i++) { + serialize8(cfg.P8[i]); + serialize8(cfg.I8[i]); + serialize8(cfg.D8[i]); + } } break; case MSP_PIDNAMES: diff --git a/src/utils.c b/src/utils.c index 0b31b002e..d4873cb42 100644 --- a/src/utils.c +++ b/src/utils.c @@ -14,6 +14,16 @@ int constrain(int amt, int low, int high) return amt; } +float constrainf(float amt, float low, float high) +{ + if (amt < low) + return low; + else if (amt > high) + return high; + else + return amt; +} + void initBoardAlignment(void) { float roll, pitch, yaw; diff --git a/src/utils.h b/src/utils.h index c6ef6b8cb..934dfe369 100644 --- a/src/utils.h +++ b/src/utils.h @@ -1,6 +1,7 @@ #pragma once int constrain(int amt, int low, int high); +float constrainf(float amt, float low, float high); // sensor orientation void alignSensors(int16_t *src, int16_t *dest, uint8_t rotation); void initBoardAlignment(void); From c14e7cf59fa8f65b8d3ea66f06ccb5ed89a56341 Mon Sep 17 00:00:00 2001 From: dongie Date: Sun, 3 Nov 2013 12:21:22 +0900 Subject: [PATCH 44/56] whitespace and formatting cleanups from latest commit --- src/config.c | 4 ++-- src/serial.c | 28 ++++++++++++---------------- 2 files changed, 14 insertions(+), 18 deletions(-) diff --git a/src/config.c b/src/config.c index 7b42523c6..73d85c919 100755 --- a/src/config.c +++ b/src/config.c @@ -246,7 +246,7 @@ static void resetConf(void) cfg.P8[PIDVEL] = 0; cfg.I8[PIDVEL] = 0; cfg.D8[PIDVEL] = 0; - + cfg.P_f[ROLL] = 2.5f; // new PID with preliminary defaults test carefully cfg.I_f[ROLL] = 0.3f; cfg.D_f[ROLL] = 0.06f; @@ -258,7 +258,7 @@ static void resetConf(void) cfg.D_f[YAW] = 0.05f; cfg.A_level = 5.0f; cfg.H_level = 3.0f; - + cfg.rcRate8 = 90; cfg.rcExpo8 = 65; cfg.rollPitchRate = 0; diff --git a/src/serial.c b/src/serial.c index 13182400c..87a7580a7 100755 --- a/src/serial.c +++ b/src/serial.c @@ -259,7 +259,7 @@ void serialInit(uint32_t baudrate) availableBoxes[idx++] = BOXGPSHOME; availableBoxes[idx++] = BOXGPSHOLD; } - if (mcfg.mixerConfiguration == MULTITYPE_FLYING_WING || mcfg.mixerConfiguration == MULTITYPE_AIRPLANE) + if (mcfg.mixerConfiguration == MULTITYPE_FLYING_WING || mcfg.mixerConfiguration == MULTITYPE_AIRPLANE) availableBoxes[idx++] = BOXPASSTHRU; availableBoxes[idx++] = BOXBEEPERON; if (feature(FEATURE_INFLIGHT_ACC_CAL)) @@ -303,19 +303,17 @@ static void evaluateCommand(void) cfg.D_f[i] = (float)read8() / 1000.0f; } for (i = 3; i < PIDITEMS; i++) { - if(i == PIDLEVEL) { + if (i == PIDLEVEL) { cfg.A_level = (float)read8() / 10.0f; cfg.H_level = (float)read8() / 10.0f; read8(); - } - else { + } else { cfg.P8[i] = read8(); cfg.I8[i] = read8(); cfg.D8[i] = read8(); } } - } - else { + } else { for (i = 0; i < PIDITEMS; i++) { cfg.P8[i] = read8(); cfg.I8[i] = read8(); @@ -500,24 +498,22 @@ static void evaluateCommand(void) headSerialReply(3 * PIDITEMS); if (cfg.pidController == 2) { // convert float stuff into uint8_t to keep backwards compatability with all 8-bit shit with new pid for (i = 0; i < 3; i++) { - serialize8(constrain(lrintf(cfg.P_f[i] * 10.0f) ,0 ,250)); - serialize8(constrain(lrintf(cfg.I_f[i] * 100.0f) ,0 ,250)); - serialize8(constrain(lrintf(cfg.D_f[i] * 1000.0f) ,0 ,100)); + serialize8(constrain(lrintf(cfg.P_f[i] * 10.0f), 0, 250)); + serialize8(constrain(lrintf(cfg.I_f[i] * 100.0f), 0, 250)); + serialize8(constrain(lrintf(cfg.D_f[i] * 1000.0f), 0, 100)); } for (i = 3; i < PIDITEMS; i++) { if (i == PIDLEVEL) { - serialize8(constrain(lrintf(cfg.A_level * 10.0f) ,0 ,250)); - serialize8(constrain(lrintf(cfg.H_level * 10.0f) ,0 ,250)); - serialize8(0); - } - else { + serialize8(constrain(lrintf(cfg.A_level * 10.0f), 0, 250)); + serialize8(constrain(lrintf(cfg.H_level * 10.0f), 0, 250)); + serialize8(0); + } else { serialize8(cfg.P8[i]); serialize8(cfg.I8[i]); serialize8(cfg.D8[i]); } } - } - else { + } else { for (i = 0; i < PIDITEMS; i++) { serialize8(cfg.P8[i]); serialize8(cfg.I8[i]); From 2d029105a556e18024da6cef23719ea56b059eaa Mon Sep 17 00:00:00 2001 From: Lukas S Date: Mon, 4 Nov 2013 00:23:29 +0100 Subject: [PATCH 45/56] fixed rotation fail --- src/utils.c | 43 +++++++++++++++++++++++++++++-------------- 1 file changed, 29 insertions(+), 14 deletions(-) diff --git a/src/utils.c b/src/utils.c index d4873cb42..cf86fabc1 100644 --- a/src/utils.c +++ b/src/utils.c @@ -27,6 +27,8 @@ float constrainf(float amt, float low, float high) void initBoardAlignment(void) { float roll, pitch, yaw; + float cosx, sinx, cosy, siny, cosz, sinz; + float coszcosx, coszcosy, sinzcosx, coszsinx, sinzsinx; // standard alignment, nothing to calculate if (!mcfg.board_align_roll && !mcfg.board_align_pitch && !mcfg.board_align_yaw) @@ -38,19 +40,32 @@ void initBoardAlignment(void) roll = mcfg.board_align_roll * M_PI / 180.0f; pitch = mcfg.board_align_pitch * M_PI / 180.0f; yaw = mcfg.board_align_yaw * M_PI / 180.0f; + + cosx = cosf(roll); + sinx = sinf(roll); + cosy = cosf(pitch); + siny = sinf(pitch); + cosz = cosf(yaw); + sinz = sinf(yaw); + + coszcosx = cosz * cosx; + coszcosy = cosz * cosy; + sinzcosx = sinz * cosx; + coszsinx = sinx * cosz; + sinzsinx = sinx * sinz; // define rotation matrix - boardRotation[0][0] = cosf(roll) * cosf(pitch); - boardRotation[0][1] = cosf(roll) * sinf(pitch) * sinf(yaw) - sinf(roll) * cosf(yaw); - boardRotation[0][2] = cosf(roll) * sinf(pitch) * cosf(yaw) + sinf(roll) * sinf(yaw); - - boardRotation[1][0] = sinf(roll) * cosf(pitch); - boardRotation[1][1] = sinf(roll) * sinf(pitch) * sinf(yaw) + cosf(roll) * cosf(yaw); - boardRotation[1][2] = sinf(roll) * sinf(pitch) * cosf(yaw) - cosf(roll) * sinf(yaw); - - boardRotation[2][0] = -sinf(pitch); - boardRotation[2][1] = cosf(pitch) * sinf(yaw); - boardRotation[2][2] = cosf(pitch) * cosf(yaw); + boardRotation[0][0] = coszcosy; + boardRotation[0][1] = -cosy * sinz; + boardRotation[0][2] = siny; + + boardRotation[1][0] = sinzcosx + (coszsinx * siny); + boardRotation[1][1] = coszcosx - (sinzsinx * siny); + boardRotation[1][2] = -sinx * cosy; + + boardRotation[2][0] = (sinzsinx) - (coszcosx * siny); + boardRotation[2][1] = (coszsinx) + (sinzcosx * siny); + boardRotation[2][2] = cosy * cosx; } void alignBoard(int16_t *vec) @@ -59,9 +74,9 @@ void alignBoard(int16_t *vec) int16_t y = vec[Y]; int16_t z = vec[Z]; - vec[X] = boardRotation[0][0] * x + boardRotation[0][1] * y + boardRotation[0][2] * z; - vec[Y] = boardRotation[1][0] * x + boardRotation[1][1] * y + boardRotation[1][2] * z; - vec[Z] = boardRotation[2][0] * x + boardRotation[2][1] * y + boardRotation[2][2] * z; + vec[X] = lrintf(boardRotation[0][0] * x + boardRotation[1][0] * y + boardRotation[2][0] * z); + vec[Y] = lrintf(boardRotation[0][1] * x + boardRotation[1][1] * y + boardRotation[2][1] * z); + vec[Z] = lrintf(boardRotation[0][2] * x + boardRotation[1][2] * y + boardRotation[2][2] * z); } void alignSensors(int16_t *src, int16_t *dest, uint8_t rotation) From 733f1ef51bf7c69382fa3cb4bd4f469074f6c4b8 Mon Sep 17 00:00:00 2001 From: Johannes Kasberger Date: Thu, 7 Nov 2013 11:04:45 +0100 Subject: [PATCH 46/56] fixed compiler warning in cliset Warning was warning: dereferencing type-punned pointer will break strict-aliasing rules --- src/cli.c | 30 +++++++++++++++++++++++------- 1 file changed, 23 insertions(+), 7 deletions(-) diff --git a/src/cli.c b/src/cli.c index 40457bc86..888fb6d71 100644 --- a/src/cli.c +++ b/src/cli.c @@ -222,7 +222,13 @@ const clivalue_t valueTable[] = { #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t)) -static void cliSetVar(const clivalue_t *var, const int32_t value); + +typedef union { + int32_t int_value; + float float_value; +} int_float_value_t; + +static void cliSetVar(const clivalue_t *var, const int_float_value_t value); static void cliPrintVar(const clivalue_t *var, uint32_t full); static void cliPrint(const char *str); static void cliWrite(uint8_t ch); @@ -880,25 +886,28 @@ static void cliPrintVar(const clivalue_t *var, uint32_t full) printf(" %d %d", var->min, var->max); } -static void cliSetVar(const clivalue_t *var, const int32_t value) + + + +static void cliSetVar(const clivalue_t *var, const int_float_value_t value) { switch (var->type) { case VAR_UINT8: case VAR_INT8: - *(char *)var->ptr = (char)value; + *(char *)var->ptr = (char)value.int_value; break; case VAR_UINT16: case VAR_INT16: - *(short *)var->ptr = (short)value; + *(short *)var->ptr = (short)value.int_value; break; case VAR_UINT32: - *(int *)var->ptr = (int)value; + *(int *)var->ptr = (int)value.int_value; break; case VAR_FLOAT: - *(float *)var->ptr = *(float *)&value; + *(float *)var->ptr = (float)value.float_value; break; } } @@ -932,7 +941,14 @@ static void cliSet(char *cmdline) val = &valueTable[i]; if (strncasecmp(cmdline, valueTable[i].name, strlen(valueTable[i].name)) == 0) { if (valuef >= valueTable[i].min && valuef <= valueTable[i].max) { // here we compare the float value since... it should work, RIGHT? - cliSetVar(val, valueTable[i].type == VAR_FLOAT ? *(uint32_t *)&valuef : value); // this is a silly dirty hack. please fix me later. + int_float_value_t tmp; + + if (valueTable[i].type == VAR_FLOAT) + tmp.float_value = valuef; + else + tmp.int_value = value; + + cliSetVar(val, tmp); printf("%s set to ", valueTable[i].name); cliPrintVar(val, 0); } else { From 6ab48fc4385132df8be0bd3f0ac14b3c8139e695 Mon Sep 17 00:00:00 2001 From: fiendie Date: Thu, 7 Nov 2013 13:15:31 +0100 Subject: [PATCH 47/56] Revert new PID stuff and move it to a separate branch for now. --- src/cli.c | 13 +------ src/config.c | 15 +------- src/drv_l3g4200d.c | 8 ++--- src/drv_mpu3050.c | 8 ++--- src/drv_mpu6050.c | 8 ++--- src/imu.c | 4 +-- src/mw.c | 88 ++++------------------------------------------ src/mw.h | 8 +---- src/serial.c | 54 +++++----------------------- src/utils.c | 10 ------ src/utils.h | 1 - 11 files changed, 30 insertions(+), 187 deletions(-) diff --git a/src/cli.c b/src/cli.c index 40457bc86..f42e25a6a 100644 --- a/src/cli.c +++ b/src/cli.c @@ -147,7 +147,7 @@ const clivalue_t valueTable[] = { { "gyro_lpf", VAR_UINT16, &mcfg.gyro_lpf, 0, 256 }, { "gyro_cmpf_factor", VAR_UINT16, &mcfg.gyro_cmpf_factor, 100, 1000 }, { "gyro_cmpfm_factor", VAR_UINT16, &mcfg.gyro_cmpfm_factor, 100, 1000 }, - { "pid_controller", VAR_UINT8, &cfg.pidController, 0, 2 }, + { "pid_controller", VAR_UINT8, &cfg.pidController, 0, 1 }, { "deadband", VAR_UINT8, &cfg.deadband, 0, 32 }, { "yawdeadband", VAR_UINT8, &cfg.yawdeadband, 0, 100 }, { "alt_hold_throttle_neutral", VAR_UINT8, &cfg.alt_hold_throttle_neutral, 1, 250 }, @@ -201,17 +201,6 @@ const clivalue_t valueTable[] = { { "p_yaw", VAR_UINT8, &cfg.P8[YAW], 0, 200 }, { "i_yaw", VAR_UINT8, &cfg.I8[YAW], 0, 200 }, { "d_yaw", VAR_UINT8, &cfg.D8[YAW], 0, 200 }, - { "Ppitchf", VAR_FLOAT, &cfg.P_f[PITCH], 0, 100 }, - { "Ipitchf", VAR_FLOAT, &cfg.I_f[PITCH], 0, 100 }, - { "Dpitchf", VAR_FLOAT, &cfg.D_f[PITCH], 0, 100 }, - { "Prollf", VAR_FLOAT, &cfg.P_f[ROLL], 0, 100 }, - { "Irollf", VAR_FLOAT, &cfg.I_f[ROLL], 0, 100 }, - { "Drollf", VAR_FLOAT, &cfg.D_f[ROLL], 0, 100 }, - { "Pyawf", VAR_FLOAT, &cfg.P_f[YAW], 0, 100 }, - { "Iyawf", VAR_FLOAT, &cfg.I_f[YAW], 0, 100 }, - { "Dyawf", VAR_FLOAT, &cfg.D_f[YAW], 0, 100 }, - { "level_horizon", VAR_FLOAT, &cfg.H_level, 0, 10 }, - { "level_angle", VAR_FLOAT, &cfg.A_level, 0, 10 }, { "p_alt", VAR_UINT8, &cfg.P8[PIDALT], 0, 200 }, { "i_alt", VAR_UINT8, &cfg.I8[PIDALT], 0, 200 }, { "d_alt", VAR_UINT8, &cfg.D8[PIDALT], 0, 200 }, diff --git a/src/config.c b/src/config.c index 73d85c919..8fd69b79e 100755 --- a/src/config.c +++ b/src/config.c @@ -118,7 +118,7 @@ retry: FLASH_Unlock(); FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR); - if (FLASH_ErasePage(FLASH_WRITE_ADDR) == FLASH_COMPLETE && FLASH_ErasePage(FLASH_WRITE_ADDR + FLASH_PAGE_SIZE) == FLASH_COMPLETE) { + if (FLASH_ErasePage(FLASH_WRITE_ADDR) == FLASH_COMPLETE) { for (i = 0; i < sizeof(master_t); i += 4) { status = FLASH_ProgramWord(FLASH_WRITE_ADDR + i, *(uint32_t *) ((char *)&mcfg + i)); if (status != FLASH_COMPLETE) { @@ -246,19 +246,6 @@ static void resetConf(void) cfg.P8[PIDVEL] = 0; cfg.I8[PIDVEL] = 0; cfg.D8[PIDVEL] = 0; - - cfg.P_f[ROLL] = 2.5f; // new PID with preliminary defaults test carefully - cfg.I_f[ROLL] = 0.3f; - cfg.D_f[ROLL] = 0.06f; - cfg.P_f[PITCH] = 2.5f; - cfg.I_f[PITCH] = 0.3f; - cfg.D_f[PITCH] = 0.06f; - cfg.P_f[YAW] = 8.0f; - cfg.I_f[YAW] = 0.5f; - cfg.D_f[YAW] = 0.05f; - cfg.A_level = 5.0f; - cfg.H_level = 3.0f; - cfg.rcRate8 = 90; cfg.rcExpo8 = 65; cfg.rollPitchRate = 0; diff --git a/src/drv_l3g4200d.c b/src/drv_l3g4200d.c index 658acd662..4c8e2af62 100644 --- a/src/drv_l3g4200d.c +++ b/src/drv_l3g4200d.c @@ -44,7 +44,7 @@ bool l3g4200dDetect(sensor_t *gyro, uint16_t lpf) gyro->read = l3g4200dRead; // 14.2857dps/lsb scalefactor - gyro->scale = 1.0f / 14.2857f; + gyro->scale = (((32767.0f / 14.2857f) * M_PI) / ((32767.0f / 4.0f) * 180.0f * 1000000.0f)); // default LPF is set to 32Hz switch (lpf) { @@ -89,9 +89,9 @@ static void l3g4200dRead(int16_t *gyroData) int16_t data[3]; i2cRead(L3G4200D_ADDRESS, L3G4200D_AUTOINCR | L3G4200D_GYRO_OUT, 6, buf); - data[X] = (int16_t)((buf[0] << 8) | buf[1]); - data[Y] = (int16_t)((buf[2] << 8) | buf[3]); - data[Z] = (int16_t)((buf[4] << 8) | buf[5]); + data[X] = (int16_t)((buf[0] << 8) | buf[1]) / 4; + data[Y] = (int16_t)((buf[2] << 8) | buf[3]) / 4; + data[Z] = (int16_t)((buf[4] << 8) | buf[5]) / 4; alignSensors(data, gyroData, gyroAlign); } diff --git a/src/drv_mpu3050.c b/src/drv_mpu3050.c index 5ac3d4623..133ab7b10 100755 --- a/src/drv_mpu3050.c +++ b/src/drv_mpu3050.c @@ -45,7 +45,7 @@ bool mpu3050Detect(sensor_t *gyro, uint16_t lpf) gyro->read = mpu3050Read; gyro->temperature = mpu3050ReadTemp; // 16.4 dps/lsb scalefactor - gyro->scale = 1.0f / 16.4f; + gyro->scale = (((32767.0f / 16.4f) * M_PI) / ((32767.0f / 4.0f) * 180.0f * 1000000.0f)); // default lpf is 42Hz switch (lpf) { @@ -99,9 +99,9 @@ static void mpu3050Read(int16_t *gyroData) int16_t data[3]; i2cRead(MPU3050_ADDRESS, MPU3050_GYRO_OUT, 6, buf); - data[0] = (int16_t)((buf[0] << 8) | buf[1]); - data[1] = (int16_t)((buf[2] << 8) | buf[3]); - data[2] = (int16_t)((buf[4] << 8) | buf[5]); + data[0] = (int16_t)((buf[0] << 8) | buf[1]) / 4; + data[1] = (int16_t)((buf[2] << 8) | buf[3]) / 4; + data[2] = (int16_t)((buf[4] << 8) | buf[5]) / 4; alignSensors(data, gyroData, gyroAlign); } diff --git a/src/drv_mpu6050.c b/src/drv_mpu6050.c index 1637afb7c..94bfc79d8 100644 --- a/src/drv_mpu6050.c +++ b/src/drv_mpu6050.c @@ -167,7 +167,7 @@ bool mpu6050Detect(sensor_t *acc, sensor_t *gyro, uint16_t lpf, uint8_t *scale) gyro->read = mpu6050GyroRead; // 16.4 dps/lsb scalefactor - gyro->scale = 1.0f / 16.4f; + gyro->scale = (4.0f / 16.4f) * (M_PI / 180.0f) * 0.000001f; // give halfacc (old revision) back to system if (scale) @@ -261,9 +261,9 @@ static void mpu6050GyroRead(int16_t *gyroData) int16_t data[3]; i2cRead(MPU6050_ADDRESS, MPU_RA_GYRO_XOUT_H, 6, buf); - data[0] = (int16_t)((buf[0] << 8) | buf[1]); - data[1] = (int16_t)((buf[2] << 8) | buf[3]); - data[2] = (int16_t)((buf[4] << 8) | buf[5]); + data[0] = (int16_t)((buf[0] << 8) | buf[1]) / 4; + data[1] = (int16_t)((buf[2] << 8) | buf[3]) / 4; + data[2] = (int16_t)((buf[4] << 8) | buf[5]) / 4; alignSensors(data, gyroData, gyroAlign); } diff --git a/src/imu.c b/src/imu.c index ad64da3e8..d4a738006 100755 --- a/src/imu.c +++ b/src/imu.c @@ -19,7 +19,6 @@ int32_t vario = 0; // variometer in cm/s int16_t throttleAngleCorrection = 0; // correction of throttle in lateral wind, float magneticDeclination = 0.0f; // calculated at startup from config float accVelScale; -float gyroScaleRad; // ************** // gyro+acc IMU @@ -35,7 +34,6 @@ void imuInit(void) { accZ_25deg = acc_1G * cosf(RAD * 25.0f); accVelScale = 9.80665f / acc_1G / 10000.0f; - gyroScaleRad = gyro.scale * (M_PI / 180.0f) * 0.000001f; #ifdef MAG // if mag sensor is enabled, use it @@ -263,7 +261,7 @@ static void getEstimatedAttitude(void) uint32_t deltaT; float scale, deltaGyroAngle[3]; deltaT = currentT - previousT; - scale = deltaT * gyroScaleRad; + scale = deltaT * gyro.scale; previousT = currentT; // Initialization diff --git a/src/mw.c b/src/mw.c index 551c46742..968788476 100755 --- a/src/mw.c +++ b/src/mw.c @@ -25,7 +25,6 @@ rcReadRawDataPtr rcReadRawFunc = NULL; // receive data from default (pwm/ppm) o static void pidMultiWii(void); static void pidRewrite(void); -static void pidBaseflight(void); pidControllerFuncPtr pid_controller = pidMultiWii; // which pid controller are we using, defaultMultiWii uint8_t dynP8[3], dynI8[3], dynD8[3]; @@ -279,78 +278,8 @@ static void mwVario(void) } static int32_t errorGyroI[3] = { 0, 0, 0 }; -static float errorGyroIf[3] = { 0.0f, 0.0f, 0.0f }; static int32_t errorAngleI[2] = { 0, 0 }; -static void pidBaseflight() -{ - float RateError, errorAngle, AngleRate, gyroRate; - float ITerm,PTerm,DTerm; - static float lastGyroRate[3]; - static float delta1[3], delta2[3]; - float delta, deltaSum; - float dT; - int axis; - - dT = (float)cycleTime * 0.000001f; - - // ----------PID controller---------- - for (axis = 0; axis < 3; axis++) { - // -----Get the desired angle rate depending on flight mode - if ((f.ANGLE_MODE || f.HORIZON_MODE) && axis < 2 ) { // MODE relying on ACC - // calculate error and limit the angle to 50 degrees max inclination - errorAngle = (constrain(rcCommand[axis] + GPS_angle[axis], -500, +500) - angle[axis] + cfg.angleTrim[axis]) / 10.0f; // 16 bits is ok here - } - if (axis == 2) { // YAW is always gyro-controlled (MAG correction is applied to rcCommand) 100dps to 1100dps max yaw rate - AngleRate = (float)((cfg.yawRate + 10) * rcCommand[YAW]) / 50.0f; - } else { - if (!f.ANGLE_MODE) { //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID - AngleRate = (float)((cfg.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 - AngleRate += errorAngle * cfg.H_level; - } - } else { // it's the ANGLE mode - control is angle based, so control loop is needed - AngleRate = errorAngle * cfg.A_level; - } - } - - gyroRate = gyroData[axis] * gyro.scale; // gyro output scaled to dps - - // --------low-level gyro-based PID. ---------- - // Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes - // -----calculate scaled error.AngleRates - // multiplication of rcCommand corresponds to changing the sticks scaling here - RateError = AngleRate - gyroRate; - - // -----calculate P component - PTerm = RateError * cfg.P_f[axis]; - // -----calculate I component - errorGyroIf[axis] = constrainf(errorGyroIf[axis] + RateError * dT * cfg.I_f[axis], -250.0f, 250.0f); - - // limit maximum integrator value to prevent WindUp - accumulating extreme values when system is saturated. - // I coefficient (I8) moved before integration to make limiting independent from PID settings - ITerm = errorGyroIf[axis]; - - //-----calculate D-term - delta = gyroRate - lastGyroRate[axis]; // 16 bits is ok here, the dif between 2 consecutive gyro reads is limited to 800 - lastGyroRate[axis] = gyroRate; - - // Correct difference by cycle time. Cycle time is jittery (can be different 2 times), so calculated difference - // would be scaled by different dt each time. Division by dT fixes that. - delta *= (1.0f / dT); - // add moving average here to reduce noise - deltaSum = delta1[axis] + delta2[axis] + delta; - delta2[axis] = delta1[axis]; - delta1[axis] = delta; - DTerm = constrainf((deltaSum / 3.0f) * cfg.D_f[axis], -300.0f, 300.0f); - - // -----calculate total PID output - axisPID[axis] = constrain(lrintf(PTerm + ITerm - DTerm), -1000, 1000); - } - -} - static void pidMultiWii(void) { int axis, prop; @@ -375,14 +304,14 @@ static void pidMultiWii(void) } if (!f.ANGLE_MODE || f.HORIZON_MODE || axis == 2) { // MODE relying on GYRO or YAW axis error = (int32_t)rcCommand[axis] * 10 * 8 / cfg.P8[axis]; - error -= gyroData[axis] / 4; + error -= gyroData[axis]; PTermGYRO = rcCommand[axis]; errorGyroI[axis] = constrain(errorGyroI[axis] + error, -16000, +16000); // WindUp - if (abs(gyroData[axis]) > 2560) + if (abs(gyroData[axis]) > 640) errorGyroI[axis] = 0; - ITermGYRO = (errorGyroI[axis] / 125 * cfg.I8[axis]) / 64; + ITermGYRO = (errorGyroI[axis] / 125 * cfg.I8[axis]) >> 6; } if (f.HORIZON_MODE && axis < 2) { PTerm = (PTermACC * (500 - prop) + PTermGYRO * prop) / 500; @@ -397,8 +326,8 @@ static void pidMultiWii(void) } } - PTerm -= ((int32_t)gyroData[axis] / 4) * dynP8[axis] / 10 / 8; // 32 bits is needed for calculation - delta = (gyroData[axis] - lastGyro[axis]) / 4; + PTerm -= (int32_t)gyroData[axis] * dynP8[axis] / 10 / 8; // 32 bits is needed for calculation + delta = gyroData[axis] - lastGyro[axis]; lastGyro[axis] = gyroData[axis]; deltaSum = delta1[axis] + delta2[axis] + delta; delta2[axis] = delta1[axis]; @@ -445,7 +374,7 @@ static void pidRewrite(void) // Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes // -----calculate scaled error.AngleRates // multiplication of rcCommand corresponds to changing the sticks scaling here - RateError = AngleRateTmp - (gyroData[axis] / 4); + RateError = AngleRateTmp - gyroData[axis]; // -----calculate P component PTerm = (RateError * cfg.P8[axis]) >> 7; @@ -489,8 +418,6 @@ void setPIDController(int type) case 1: pid_controller = pidRewrite; break; - case 2: - pid_controller = pidBaseflight; } } @@ -587,9 +514,6 @@ void loop(void) errorGyroI[ROLL] = 0; errorGyroI[PITCH] = 0; errorGyroI[YAW] = 0; - errorGyroIf[ROLL] = 0; - errorGyroIf[PITCH] = 0; - errorGyroIf[YAW] = 0; errorAngleI[ROLL] = 0; errorAngleI[PITCH] = 0; if (cfg.activate[BOXARM] > 0) { // Arming/Disarming via ARM BOX diff --git a/src/mw.h b/src/mw.h index 59cc54729..f9efeee58 100755 --- a/src/mw.h +++ b/src/mw.h @@ -150,16 +150,10 @@ enum { #define CALIBRATING_BARO_CYCLES 200 typedef struct config_t { - uint8_t pidController; // 0 = multiwii original, 1 = rewrite from http://www.multiwii.com/forum/viewtopic.php?f=8&t=3671, 2 = Luggi09s new baseflight pid + uint8_t pidController; // 0 = multiwii original, 1 = rewrite from http://www.multiwii.com/forum/viewtopic.php?f=8&t=3671 uint8_t P8[PIDITEMS]; uint8_t I8[PIDITEMS]; uint8_t D8[PIDITEMS]; - - float P_f[3]; // float p i and d factors for the new baseflight pid - float I_f[3]; - float D_f[3]; - float A_level; - float H_level; uint8_t rcRate8; uint8_t rcExpo8; diff --git a/src/serial.c b/src/serial.c index 87a7580a7..55553000b 100755 --- a/src/serial.c +++ b/src/serial.c @@ -296,29 +296,10 @@ static void evaluateCommand(void) headSerialReply(0); break; case MSP_SET_PID: - if (cfg.pidController == 2) { - for (i = 0; i < 3; i++) { - cfg.P_f[i] = (float)read8() / 10.0f; - cfg.I_f[i] = (float)read8() / 100.0f; - cfg.D_f[i] = (float)read8() / 1000.0f; - } - for (i = 3; i < PIDITEMS; i++) { - if (i == PIDLEVEL) { - cfg.A_level = (float)read8() / 10.0f; - cfg.H_level = (float)read8() / 10.0f; - read8(); - } else { - cfg.P8[i] = read8(); - cfg.I8[i] = read8(); - cfg.D8[i] = read8(); - } - } - } else { - for (i = 0; i < PIDITEMS; i++) { - cfg.P8[i] = read8(); - cfg.I8[i] = read8(); - cfg.D8[i] = read8(); - } + for (i = 0; i < PIDITEMS; i++) { + cfg.P8[i] = read8(); + cfg.I8[i] = read8(); + cfg.D8[i] = read8(); } headSerialReply(0); break; @@ -496,29 +477,10 @@ static void evaluateCommand(void) break; case MSP_PID: headSerialReply(3 * PIDITEMS); - if (cfg.pidController == 2) { // convert float stuff into uint8_t to keep backwards compatability with all 8-bit shit with new pid - for (i = 0; i < 3; i++) { - serialize8(constrain(lrintf(cfg.P_f[i] * 10.0f), 0, 250)); - serialize8(constrain(lrintf(cfg.I_f[i] * 100.0f), 0, 250)); - serialize8(constrain(lrintf(cfg.D_f[i] * 1000.0f), 0, 100)); - } - for (i = 3; i < PIDITEMS; i++) { - if (i == PIDLEVEL) { - serialize8(constrain(lrintf(cfg.A_level * 10.0f), 0, 250)); - serialize8(constrain(lrintf(cfg.H_level * 10.0f), 0, 250)); - serialize8(0); - } else { - serialize8(cfg.P8[i]); - serialize8(cfg.I8[i]); - serialize8(cfg.D8[i]); - } - } - } else { - for (i = 0; i < PIDITEMS; i++) { - serialize8(cfg.P8[i]); - serialize8(cfg.I8[i]); - serialize8(cfg.D8[i]); - } + for (i = 0; i < PIDITEMS; i++) { + serialize8(cfg.P8[i]); + serialize8(cfg.I8[i]); + serialize8(cfg.D8[i]); } break; case MSP_PIDNAMES: diff --git a/src/utils.c b/src/utils.c index cf86fabc1..db0b2697d 100644 --- a/src/utils.c +++ b/src/utils.c @@ -14,16 +14,6 @@ int constrain(int amt, int low, int high) return amt; } -float constrainf(float amt, float low, float high) -{ - if (amt < low) - return low; - else if (amt > high) - return high; - else - return amt; -} - void initBoardAlignment(void) { float roll, pitch, yaw; diff --git a/src/utils.h b/src/utils.h index 934dfe369..c6ef6b8cb 100644 --- a/src/utils.h +++ b/src/utils.h @@ -1,7 +1,6 @@ #pragma once int constrain(int amt, int low, int high); -float constrainf(float amt, float low, float high); // sensor orientation void alignSensors(int16_t *src, int16_t *dest, uint8_t rotation); void initBoardAlignment(void); From b2f163d2ac9aaa2ae892949a573a751dd08513c7 Mon Sep 17 00:00:00 2001 From: dongie Date: Thu, 7 Nov 2013 22:12:28 +0900 Subject: [PATCH 48/56] whitespace fixes in previous commit --- src/cli.c | 5 ----- 1 file changed, 5 deletions(-) diff --git a/src/cli.c b/src/cli.c index 1c8215e8c..6d6be6355 100644 --- a/src/cli.c +++ b/src/cli.c @@ -875,9 +875,6 @@ static void cliPrintVar(const clivalue_t *var, uint32_t full) printf(" %d %d", var->min, var->max); } - - - static void cliSetVar(const clivalue_t *var, const int_float_value_t value) { switch (var->type) { @@ -931,12 +928,10 @@ static void cliSet(char *cmdline) if (strncasecmp(cmdline, valueTable[i].name, strlen(valueTable[i].name)) == 0) { if (valuef >= valueTable[i].min && valuef <= valueTable[i].max) { // here we compare the float value since... it should work, RIGHT? int_float_value_t tmp; - if (valueTable[i].type == VAR_FLOAT) tmp.float_value = valuef; else tmp.int_value = value; - cliSetVar(val, tmp); printf("%s set to ", valueTable[i].name); cliPrintVar(val, 0); From 26aa644999055b280f2e48b908409a598c3a2169 Mon Sep 17 00:00:00 2001 From: Johannes Kasberger Date: Thu, 7 Nov 2013 16:59:36 +0100 Subject: [PATCH 49/56] Fixes array out of bound access for lookupPitchRollRC and lookupThrottleRC. --- src/config.c | 8 ++++---- src/mw.c | 4 ++-- src/mw.h | 7 +++++-- 3 files changed, 11 insertions(+), 8 deletions(-) diff --git a/src/config.c b/src/config.c index 8fd69b79e..3be24b835 100755 --- a/src/config.c +++ b/src/config.c @@ -69,18 +69,18 @@ void readEEPROM(void) mcfg.current_profile = 0; memcpy(&cfg, &mcfg.profile[mcfg.current_profile], sizeof(config_t)); - for (i = 0; i < 6; i++) + for (i = 0; i < PITCH_LOOKUP_LENGTH; i++) lookupPitchRollRC[i] = (2500 + cfg.rcExpo8 * (i * i - 25)) * i * (int32_t) cfg.rcRate8 / 2500; - for (i = 0; i < 11; i++) { + for (i = 0; i < THROTTLE_LOOKUP_LENGTH; i++) { int16_t tmp = 10 * i - cfg.thrMid8; uint8_t y = 1; if (tmp > 0) y = 100 - cfg.thrMid8; if (tmp < 0) y = cfg.thrMid8; - lookupThrottleRC[i] = 10 * cfg.thrMid8 + tmp * (100 - cfg.thrExpo8 + (int32_t) cfg.thrExpo8 * (tmp * tmp) / (y * y)) / 10; // [0;1000] - lookupThrottleRC[i] = mcfg.minthrottle + (int32_t) (mcfg.maxthrottle - mcfg.minthrottle) * lookupThrottleRC[i] / 1000; // [0;1000] -> [MINTHROTTLE;MAXTHROTTLE] + lookupThrottleRC[i] = 10 * cfg.thrMid8 + tmp * (100 - cfg.thrExpo8 + (int32_t) cfg.thrExpo8 * (tmp * tmp) / (y * y)) / 10; + lookupThrottleRC[i] = mcfg.minthrottle + (int32_t) (mcfg.maxthrottle - mcfg.minthrottle) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE] } setPIDController(cfg.pidController); diff --git a/src/mw.c b/src/mw.c index 968788476..1248bff6c 100755 --- a/src/mw.c +++ b/src/mw.c @@ -18,8 +18,8 @@ int16_t failsafeCnt = 0; int16_t failsafeEvents = 0; int16_t rcData[RC_CHANS]; // interval [1000;2000] int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW -int16_t lookupPitchRollRC[6]; // lookup table for expo & RC rate PITCH+ROLL -int16_t lookupThrottleRC[11]; // lookup table for expo & mid THROTTLE +int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL +int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE uint16_t rssi; // range: [0;1023] rcReadRawDataPtr rcReadRawFunc = NULL; // receive data from default (pwm/ppm) or additional (spek/sbus/?? receiver drivers) diff --git a/src/mw.h b/src/mw.h index f9efeee58..eb1dbbb08 100755 --- a/src/mw.h +++ b/src/mw.h @@ -356,10 +356,13 @@ extern int16_t rcData[RC_CHANS]; extern uint16_t rssi; // range: [0;1023] extern uint8_t vbat; extern int16_t telemTemperature1; // gyro sensor temperature -extern int16_t lookupPitchRollRC[6]; // lookup table for expo & RC rate PITCH+ROLL -extern int16_t lookupThrottleRC[11]; // lookup table for expo & mid THROTTLE extern uint8_t toggleBeep; +#define PITCH_LOOKUP_LENGTH 7 +#define THROTTLE_LOOKUP_LENGTH 12 +extern int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL +extern int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE + // GPS stuff extern int32_t GPS_coord[2]; extern int32_t GPS_home[2]; From 7a4cdec0e521c38f5f23bf2f10080491eed0361f Mon Sep 17 00:00:00 2001 From: dongie Date: Sat, 9 Nov 2013 08:29:29 +0900 Subject: [PATCH 50/56] limit thr_expo to 100 for previous commit --- src/cli.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/cli.c b/src/cli.c index 6d6be6355..535d41311 100644 --- a/src/cli.c +++ b/src/cli.c @@ -156,7 +156,7 @@ const clivalue_t valueTable[] = { { "rc_rate", VAR_UINT8, &cfg.rcRate8, 0, 250 }, { "rc_expo", VAR_UINT8, &cfg.rcExpo8, 0, 100 }, { "thr_mid", VAR_UINT8, &cfg.thrMid8, 0, 100 }, - { "thr_expo", VAR_UINT8, &cfg.thrExpo8, 0, 250 }, + { "thr_expo", VAR_UINT8, &cfg.thrExpo8, 0, 100 }, { "roll_pitch_rate", VAR_UINT8, &cfg.rollPitchRate, 0, 100 }, { "yawrate", VAR_UINT8, &cfg.yawRate, 0, 100 }, { "failsafe_delay", VAR_UINT8, &cfg.failsafe_delay, 0, 200 }, From 1cbbe0b110870678ab5702a90c52283dc43b06eb Mon Sep 17 00:00:00 2001 From: dongie Date: Thu, 14 Nov 2013 20:28:33 +0900 Subject: [PATCH 51/56] airplane mixer will now actually output servo data --- obj/baseflight.hex | 7021 ++++++++++++++++++++++---------------------- src/mixer.c | 5 +- 2 files changed, 3542 insertions(+), 3484 deletions(-) diff --git a/obj/baseflight.hex b/obj/baseflight.hex index c187666dd..dc203401f 100644 --- a/obj/baseflight.hex +++ b/obj/baseflight.hex @@ -1,20 +1,20 @@ :020000040800F2 -:10000000682900203DA500087DA500086F2500088F -:1000100081A5000883A5000885A500080000000050 -:1000200000000000000000000000000087A500089C -:1000300089A50008000000008BA500089D7D000830 -:100040008FA500088FA500088FA500088FA50008C0 -:100050008FA500088FA500088FA50008E788000875 -:100060008FA500088FA500088FA500088FA50008A0 -:100070008FA500088FA500085D8300088FA50008E4 -:100080008FA500088FA500088FA500088FA5000880 -:100090008FA500088FA500088FA50008E988000833 -:1000A0008FA500088FA500088FA500086D91000896 -:1000B00071910008779100087B9100080D77000886 -:1000C000EB740008117700080F7700088FA500086F -:1000D0008FA5000889830008BD8300088FA500084C -:1000E000296E00088FA500088FA50008DFF80CD046 -:1000F0000AF06EFE004800473123000868290020FE +:100000009029002041A8000881A800081F270008A7 +:1000100085A8000887A8000889A80008000000003B +:100020000000000000000000000000008BA8000895 +:100030008DA80008000000008FA80008A18000081B +:1000400093A8000893A8000893A8000893A80008A4 +:1000500093A8000893A8000893A80008EB8B000859 +:1000600093A8000893A8000893A8000893A8000884 +:1000700093A8000893A800086186000893A80008C8 +:1000800093A8000893A8000893A8000893A8000864 +:1000900093A8000893A8000893A80008ED8B000817 +:1000A00093A8000893A8000893A80008719400087A +:1000B000759400087B9400087F940008117A00086A +:1000C000EF770008157A0008137A000893A8000853 +:1000D00093A800088D860008C186000893A8000830 +:1000E0002D71000893A8000893A80008DFF80CD031 +:1000F0000BF012F800480047E12400089029002086 :1001000070B51546B0FBF5F40646A84203D3204669 :10011000FFF7F6FF014605FB1460FCA2105C0870B7 :10012000481C70BD70B50C46911E232900D30A22CD @@ -23,71 +23,71 @@ :10015000044600E0641C20782028FBD00928F9D050 :100160004FF07E58C1B247462D2902D02B2801D02E :1001700001E0F04F641C0026DFF8BC930CE000BFE8 -:100180000AF002FC0546494630460AF07BFB294648 -:100190000AF020FB0646641C207830380928EFD985 -:1001A00020782E2815D14D460EE000BF0AF0ECFB5A -:1001B00029460AF09DFB31460AF00CFB06464946EB -:1001C00028460AF05FFB054614F8010F303809286D +:100180000AF0A6FD0546494630460AF01FFD2946FD +:100190000AF0C4FC0646641C207830380928EFD9E0 +:1001A00020782E2815D14D460EE000BF0AF090FDB4 +:1001B00029460AF041FD31460AF0B0FC06464946A0 +:1001C00028460AF003FD054614F8010F30380928C7 :1001D000ECD921784046652901D0452935D114F85C :1001E000011F4FF000082D2902D02B2902D002E078 :1001F0004FF00108641C00256FF02F0206E000BFDD :1002000005EB850302EB4303CD18641C2178A1F1B3 :100210003003092BF4D94FF49A718D4204D90D465D -:10022000C6490AF02FFB083D082DF9D203E04946E4 -:100230000AF028FB6D1E002DF9D1B8F1000F04D093 -:10024000014630460AF054FB03E0014630460AF00E -:1002500019FB3946BDE8F0470AF014BBF0B587B08A +:10022000C6490AF0D3FC083D082DF9D203E049463F +:100230000AF0CCFC6D1E002DF9D1B8F1000F04D0EE +:10024000014630460AF0F8FC03E0014630460AF069 +:10025000BDFC3946BDE8F0470AF0B8BCF0B587B040 :1002600000260D46B74900960196B5A70296B0F54F -:10027000000F02DB0AF0AEFA01E00AF0FDFAB24923 -:100280000AF000FB0AF08EFB041E00DC60420A222A +:10027000000F02DB0AF052FC01E00AF0A1FCB249D7 +:100280000AF0A4FC0AF032FD041E00DC60420A22DF :1002900003A9FFF747FF002C01DB202000E02D2001 -:1002A0008DF8000003A80AF068FA302401280AD06B -:1002B00003A80AF062FA02280CD003A80AF05DFA3B +:1002A0008DF8000003A80AF0EAFB302401280AD0E8 +:1002B00003A80AF0E4FB02280CD003A80AF0DFFB35 :1002C00003280CD00DE08DF801408DF802408DF828 :1002D000034006E08DF801408DF8024001E08DF802 -:1002E000014003A968460AF014FA68460AF045FA84 -:1002F000C01EC4B22246694628460AF028FA2E5586 -:10030000394628460AF005FA0DEB040128460AF0A2 -:1003100000FA07B02846F0BD70B505460C460868DF -:100320000AF02BFA024621682868BDE870400AF0FE -:100330002BBA70B506460AF020FA844D10F0FF0F74 -:100340000FD030460AF039FA0446142815DA202175 -:1003500030460AF008FA0AF030FA05EB4401C88783 -:1003600070BD002405EB44002146C28F78A00AF03E -:100370005DFE641C142CF5DB70BDBDE870401421DB -:1003800076A00AF053BE2DE9F041002588B007465B -:100390002E460AF0F2F97B4C10F0FF0FA84652D01F -:1003A000052279A138460AF0EFF900287ED0042210 -:1003B00077A138460AF0E8F9002878D038460AF0E4 -:1003C000FCF9461E0C2E73DA202138460AF0CBF9D0 +:1002E000014003A968460AF096FB68460AF0C7FB7E +:1002F000C01EC4B22246694628460AF0AAFB2E5503 +:10030000394628460AF087FB0DEB040128460AF01F +:1003100082FB07B02846F0BD70B505460C4608685C +:100320000AF0ADFB024621682868BDE870400AF07B +:10033000CFBB70B506460AF0A2FB844D10F0FF0F4C +:100340000FD030460AF0DDFB0446142815DA2021D0 +:1003500030460AF08AFB0AF0D4FB05EB4401C8875B +:1003600070BD002405EB44002146C28F78A00BF03D +:1003700001F8641C142CF5DB70BDBDE8704014213D +:1003800076A00AF0F7BF2DE9F041002588B00746B6 +:100390002E460AF074FB7B4C10F0FF0FA84652D09B +:1003A000052279A138460AF093FB00287ED004226A +:1003B00077A138460AF08CFB002878D038460AF03E +:1003C000A0FB461E0C2E73DA202138460AF04DFBA6 :1003D000070007D0781C0746FFF7B8FE04EB0611AC -:1003E00001250861202138460AF0BDF9070007D031 +:1003E00001250861202138460AF03FFB070007D0AD :1003F000471C3846FFF7AAFE04EB06116D1C486146 -:10040000202138460AF0AFF9070007D0471C3846CC +:10040000202138460AF031FB070007D0471C384648 :10041000FFF79CFE04EB06116D1C88612021384615 -:100420000AF0A1F930B1401CFFF790FE04EB061171 -:100430006D1CC861042D67D057A000BF00F070FF8D -:1004400008B0BDE8F08163A000F06AFF5FF000052E +:100420000AF023FB30B1401CFFF790FE04EB0611ED +:100430006D1CC861042D67D057A000BF01F045F8BE +:1004400008B0BDE8F08163A001F03FF85FF000055F :1004500004EB0517386910F0FF4F2BD0761C691C90 -:1004600067A00AF0E3FD03A93869FFF7F7FE01462C -:1004700065A00AF0DBFD03A97869FFF7EFFE0146EE -:1004800061A00AF0D3FD03A9B869FFF7E7FE0146B2 -:100490005DA00AF0CBFD03A9F869FFF7DFFE014676 -:1004A0005AA00AF0C3FD6D1C0C2D02E0C8E0D0E09C +:1004600067A00AF087FF03A93869FFF7F7FE014686 +:1004700065A00AF07FFF03A97869FFF7EFFE014648 +:1004800061A00AF077FF03A9B869FFF7E7FE01460C +:100490005DA00AF06FFF03A9F869FFF7DFFE0146D0 +:1004A0005AA00AF067FF6D1C0C2D02E0C8E0D0E0F6 :1004B000F5E0CDDBCDF80880CDF804800025CDF83F -:1004C000008011E004EB0517009879690AF082F9C1 -:1004D0000090B96901980AF07DF90190F9690298D4 -:1004E0000AF078F96D1C0290B542EBDB49A000F0F0 -:1004F00017FF4C4E00246D4655F8240020F00040B4 +:1004C000008011E004EB0517009879690AF026FB1B +:1004D0000090B96901980AF021FB0190F96902982E +:1004E0000AF01CFB6D1C0290B542EBDB49A000F04A +:1004F000ECFF4C4E00246D4655F8240020F00040DF :10050000B04202DD48A092E0C4E08FE030313233E7 :100510003435363738394142434445464748494ADD :100520004B4C4D4E4F505152535455565758595AA3 :1005300000000000000080BF0000204120BCBE4C35 -:100540002E0000006F12033A00007A44E8070020F2 +:100540002E0000006F12033A00007A44EC070020EE :100550006175782025752025750D0A00496E766134 :100560006C6964204665617475726520696E6465A6 :10057000783A206D757374206265203C2025750DD6 -:100580000A0000006C0400207265736574000000AE +:100580000A000000700400207265736574000000AA :100590006C6F61640000000057726F6E67206E75AB :1005A0006D626572206F6620617267756D656E742D :1005B000732C206E6565647320696478207468729A @@ -97,3433 +97,3494 @@ :1005F0006C6C095069746368095961770D0A0000D1 :100600002325643A090000002573090025730D0AAB :100610000000000053616E69747920636865636B44 -:100620003A0900000AD7233C4E470900FDA000F01C -:1006300077FE641C032CFFF65FAFAFF24000FDE6CF +:100620003A0900000AD7233C4E470900FEA000F01B +:100630004CFF641C032CFFF65FAFAFF24000FDE6F9 :100640000020414604EB0012401C11610C28F9DB2C -:10065000F6E6202138460AF086F80028F8D0401C3B -:1006600006460AF08AF8F04DC7B2002455F8241067 -:1006700031B13A4630460AF087F818B1641CF5E704 -:10068000EAA0DBE6204602F015F855F82410EDA0AC -:100690000AF0CCFCAFF26810FFF775FED0E60C2133 -:1006A000EDA00AF0C3FCCBE610B5F5A000F038FED3 -:1006B000012001F0DAF8F9A000F032FE0A2007F07C -:1006C0009BFBBDE81040002007F061BC7CB50446F0 +:10065000F6E6202138460AF008FA0028F8D0401CB7 +:1006600006460AF00CFAF14DC7B2002455F82410E2 +:1006700031B13A4630460AF02BFA18B1641CF5E75E +:10068000EBA0DBE6204602F006F955F82410EEA0B8 +:100690000AF070FEAFF26810FFF775FED0E60C218D +:1006A000EEA00AF067FECBE610B5F6A000F00DFF55 +:1006B000012001F0B2F9FAA000F007FF0A2007F0CC +:1006C0001DFDBDE81040002007F0E3BD7CB50446E9 :1006D0000D4600790021062814D2DFE800F0030659 :1006E0000A0D111EA06801780CE0A06890F90010B6 :1006F00008E0A068018805E0A068B0F9001001E0FA -:10070000A0680168E9A00AF091FC002D04D0D4E9AA -:100710000312E7A00AF08AFC7CBDA0686946006865 -:10072000FFF79CFD0146E4A00AF080FC002DF3D009 -:10073000E0680AF029F96946FFF790FD0146DFA05D -:100740000AF074FC20690AF01FF96946FFF786FD7C -:100750000146DAA00AF06AFC7CBD2DE9FF47D8A06B -:100760000AF064FCD0A0FFF7E4FDE14DAE496879E2 -:1007700001EB800050F8041CDEA00AF057FC286949 -:1007800010F0FF4F4CD0DFF878A3002405EB0410E5 +:10070000A0680168EAA00AF035FE002D04D0D4E903 +:100710000312E8A00AF02EFE7CBDA06869460068BE +:10072000FFF79CFD0146E5A00AF024FE002DF3D062 +:10073000E0680AF0CDFA6946FFF790FD0146E0A0B7 +:100740000AF018FE20690AF0C3FA6946FFF786FD31 +:100750000146DBA00AF00EFE7CBD2DE9FF47D9A0C3 +:100760000AF008FED1A0FFF7E4FDE24DAF49687939 +:1007700001EB800050F8041CDFA00AF0FBFD2869A3 +:1007800010F0FF4F4CD0DFF87CA3002405EB0410E1 :10079000066916F0FF4F3FD0D0E90598C769611C84 -:1007A000D8A00AF043FC564502D3D8A00AF03EFC7C -:1007B00069463046FFF752FD0146BFA00AF036FCFD -:1007C0005646B14502D3D1A00AF030FC69464846EE -:1007D000FFF744FD0146B8A00AF028FCB04502D35B -:1007E000CAA00AF023FC69464046FFF737FD0146E0 -:1007F000B1A00AF01BFCB74202D3C4A00AF016FC59 +:1007A000D9A00AF0E7FD564502D3D9A00AF0E2FD30 +:1007B00069463046FFF752FD0146C0A00AF0DAFD57 +:1007C0005646B14502D3D2A00AF0D4FD6946484648 +:1007D000FFF744FD0146B9A00AF0CCFDB04502D3B5 +:1007E000CBA00AF0C7FD69464046FFF737FD01463A +:1007F000B2A00AF0BFFDB74202D3C5A00AF0BAFD0D :1008000069463846FFF72AFD0146AFF200200AF09C -:100810000DFC641C0C2CB9DB611CBDA00AF006FCAD -:1008200001F054F8804E002407465C3656F8241038 -:1008300021B1BCA00AF0FAFB641CF7E700244FF0DA +:10081000B1FD641C0C2CB9DB611CBEA00AF0AAFD62 +:1008200001F02CF9814E002407465C3656F824105E +:1008300021B1BDA00AF09EFD641CF7E700244FF033 :10084000010800BF56F8241041B108FA04F03842FC -:1008500002D0B8A00AF0EAFB641CF3E7B94A002012 +:1008500002D0B9A00AF08EFD641CF3E7BA4A00206A :1008600069462C18135C94F80A41401C08280B5563 -:10087000F7DB00220A54B4A00AF0D8FBB54D0024DF -:1008800004EB840005EB800655F82010B2A00AF0B6 -:10089000CDFB00213046FFF719FF6EA000F040FDB0 -:1008A000641C612CECD3BDE8FF8710B5ADA000F04F -:1008B00037FD0121002000F022FEADA000F030FD48 -:1008C0000A2007F099FABDE81040002007F05FBB4E -:1008D00010B50446AAA000F023FDAF480021017026 -:1008E000AE480160AE4801702046BDE81040DCE72C -:1008F0002DE9F047064609F040FF054600F0E6FF07 -:10090000DFF8248107464FF0010908F15C0855B172 -:100910002A46A4A1304609F037FFC8B13078002735 -:100920002D2824D026E0A1A000F0FAFC00244D469A -:100930004FEA080656F8241041B105FA04F038428F -:1009400002D09FA00AF072FB641CF3E741A01EE0F6 -:100950009CA000F0E5FC00244FEA080555F824109F -:100960000029F3D096A00AF061FB641CF6E701278A -:10097000761C6D1E5FF0000458F8241031B12A4631 -:10098000304609F001FF30B1641CF5E793A0BDE8E3 -:10099000F04700F0C5BC09FA04F01FB100F091FF68 -:1009A00095A002E000F00CFE96A000F0B9FC58F80B -:1009B0002410BDE8F04761A00AF038BB70B50024F0 -:1009C00093A000F0ADFC634DB5F1A80504EB440025 -:1009D00005EB80014A6855F8201093A00AF026FB29 -:1009E000641C0E2CF2D370BD3EB5054609F0C5FE61 -:1009F000082815D10024285D09F03EFE2855641C06 -:100A0000082CF8D300244F48295D09F0ACFE28B12A -:100A10002819295D401C09F0A6FE00B108E10BE190 -:100A200011E100004F4B09009CBF0008496E766140 -:100A30006C6964206D6978657220747970652E2EFA -:100A40002E0D0A004C6F61646564202573206D696A -:100A5000782E2E2E0D0A00004D6F746F72206E7569 -:100A60006D626572206D75737420626520626574B5 -:100A70007765656E203120616E642025640D0A0063 -:100A8000526573657474696E6720746F206465665F -:100A900061756C74732E2E2E0D0A00005265626F04 -:100AA0006F74696E672E2E2E000000002564000012 -:100AB0002025642025640000257300002025730094 -:100AC00043757272656E7420436F6E6669673A2073 -:100AD000436F70792065766572797468696E6720F6 -:100AE00062656C6F7720686572652E2E2E0D0A0088 -:100AF0006C0400206D697865722025730D0A000072 -:100B000000008080636D697820256400200000006B -:100B1000636D697820256420302030203020300D2E -:100B20000A00000066656174757265202D25730DDD -:100B30000A000000666561747572652025730D0AF0 -:100B400000000000B4C800086D61702025730D0A14 -:100B50000000000020C10008736574202573203D4B -:100B600020000000536176696E672E2E2E00000073 -:100B70000D0A5265626F6F74696E672E2E2E00002B -:100B80000D0A4C656176696E6720434C49206D6F94 -:100B900064652E2E2E0D0A003C040020000000206B -:100BA000B50100206C69737400000000456E61623D -:100BB0006C65642066656174757265733A20000027 -:100BC00025732000417661696C61626C6520666501 -:100BD0006174757265733A2000000000496E766199 -:100BE0006C69642066656174757265206E616D65FF -:100BF0002E2E2E0D0A00000044697361626C65643C -:100C000020000000456E61626C65642000000000F9 -:100C1000417661696C61626C6520636F6D6D616EB8 -:100C200064733A0D0A00000025730925730D0A004C -:100C3000F7A000F075FB3EBD641C082CFFF4E3AE8A -:100C4000284600F0A7FBFAA000F06AFBFE4BFF4A23 -:100C50000020694615181C5C95F80A51401C0828AC -:100C60004C55F7D300220A54AFF230100AF0DEF9E7 -:100C70003EBD2DE9F041804609F07FFDF34FF44D74 -:100C8000060011D00246AFF2E401404609F07CFDB7 -:100C900088B1002455F82410F1B13246404609F0DD -:100CA00073FDF8B1641CF5E7787905EB800050F826 -:100CB000041CE8A01BE0ECA000F032FB5FF0000495 -:100CC00055F8241029B1AFF208100AF0AFF9641CEE -:100CD000F6E7AFF2802001E0AFF2B020BDE8F041CE -:100CE00000F01EBB601C787155F82410E3A0BDE82D -:100CF000F0410AF09BB970B5054609F03EFDD34CB2 -:100D000010F0FF0F0CD0284609F057FD02280ED82E -:100D100084F878030021084600F0F1FBC9A0EBE756 -:100D200094F87813BDE87040D9A00AF07FB970BD7F -:100D30002DE9F047814609F020FDDB4D060029D062 -:100D4000012E03D199F800002A2823D0D7A14846C4 -:100D500009F0EBFC00286ED0401C044609F02DFD84 -:100D600082462046FFF7F2F98046002606EB86070A -:100D700005EB870455F8270009F0FFFC024655F8FB -:100D80002710484609F000FDF8B1761C612EEDD31E -:100D9000C7A04CE0CEA000F0C3FA002404EB84000E -:100DA00005EB800755F82010AFF250200AF03EF90D -:100DB00031463846FFF78AFCAFF2683000F0B0FAEF -:100DC000641C612CEAD3BDE8F08706EB860605EBD0 -:100DD0008607F86809F0D8FD414609F011FE25D8CC -:100DE000386909F0D1FD414609F014FE1ED8397961 -:100DF000052907D0504606290ED2DFE801F0050587 -:100E000008080B0B4046F6E7A168087004E0A168EB -:100E1000088001E0A168086055F82610B2A00AF029 -:100E200005F92046BDE8F04700214FE4B1A0BDE838 -:100E3000F04700F075BA002404EB8406494655F8E3 -:100E4000260009F072FC78B155F8261005EB8607EC -:100E5000AFF2F8200AF0EAF800213846FFF736FC36 -:100E6000AFF210400AF0E2F8641C612CE4D3AAE768 -:100E70002DE9F04106F0B1FF4FF47A71B0FBF1F1CA -:100E8000A6480378A6480278A6A00AF0CFF800F09A -:100E90000DFD0646B348B4490068B0FBF1F1B3A0BC -:100EA0000AF0C4F86A4F00240125A03757F824102F -:100EB00051B105FA04F0304203D0AFF2FC200AF041 -:100EC000B5F8641CE4B2F1E7022000F0DDFCA0B14B -:100ED000AE4C5F482178C03050F82110ACA00AF029 -:100EE000A5F82078022808D1AC48007C08B16F2111 -:100EF00000E06E21AAA00AF099F8AFF2A84000F035 -:100F00000FFA06F07EFC0246A6484FF45F73018894 -:100F1000BDE8F041A4A00AF089B8B0A000F000BA82 -:100F20002DE9FF5FDFF8E49299F8000038B901215C -:100F300089F80010B6A000F0F3F900F0FDF9DFF831 -:100F400008B3DFF858A25446DAF8000008F03EFB78 -:100F500000285AD0206808F03CFB092807D03F2819 -:100F600005D0DBF800105C4600294FD076E1002464 -:100F70004D4F2546A83FDFF83081DBF800600BE0DD -:100F8000DBF8002022B1B148396809F0FDFB10B947 -:100F900004B93C463D460C374745F1D394B1AB4FBD -:100FA0005946226808682B68125C1B5C9A4209D17A -:100FB00092B92E2810D220223A54401C0021CBF89E -:100FC00000003954DBF800005F4608B1AC4213D092 -:100FD0009FA000F0A5F90AE03A54401C0860E0E741 -:100FE000206800F09DF9092000F0A8F90C34AC420B -:100FF000F6D900F0A1F90026944C38688642A2D2B6 -:10100000A05D00F09BF9761CF7E787E124E1000082 -:101010004D75737420626520616E79206F7264650E -:1010200072206F662041455452313233340D0A002C -:1010300043757272656E742061737369676E6D6556 -:101040006E743A2000000000B4C800086C04002050 -:101050009CBF000843757272656E74206D69786577 -:10106000723A2025730D0A00417661696C61626CE9 -:1010700065206D69786572733A2000004D69786566 -:10108000722073657420746F2025730D0A000000B0 -:1010900043757272656E742070726F66696C653A22 -:1010A0002025640D0A00000020C100083D0000005A -:1010B0004552523A20556E6B6E6F776E2076617294 -:1010C0006961626C65206E616D650D0A000000004B -:1010D00043757272656E742073657474696E67739C -:1010E0003A200D0A000000002573207365742074F7 -:1010F0006F2000004552523A2056616C75652061A0 -:10110000737369676E6D656E74206F7574206F669A -:101110002072616E67650D0A000000006801002002 -:10112000D200002053797374656D20557074696D19 -:10113000653A202564207365636F6E64732C2056B6 -:101140006F6C746167653A202564202A20302E3147 -:101150005620282564532062617474657279290DC4 -:101160000A0000000804002040420F0043505520B0 -:1011700025644D487A2C2064657465637465642029 -:1011800073656E736F72733A200000007C0100205B -:1011900041434348573A202573000000DC080020F3 -:1011A0002E256300D40000204379636C65205469C8 -:1011B0006D653A2025642C20493243204572726FB8 -:1011C00072733A2025642C20636F6E666967207302 -:1011D000697A653A2025640D0A0000004166726F45 -:1011E000333220434C492076657273696F6E20322A -:1011F0002E32204E6F762020322032303133202F95 -:101200002031323A33393A3236000000B50100203D -:101210000D0A456E746572696E6720434C49204D16 -:101220006F64652C20747970652027657869742750 -:1012300020746F2072657475726E2C206F72202777 -:1012400068656C70270D0A00000000203C04002037 -:101250000D1B5B4B00000000042813D00C2817D096 -:1012600019B10A2818D00D2816D07F2840D030296F -:10127000BFF469AE2028FFF466AE7E283FF663AE69 -:10128000A9B343E004B03048BDE8F05FFFF720BBEE -:101290002EA000F045F827E0AFF6480000F040F837 -:1012A000294E206800250C2335542B48CDE9000633 -:1012B0000E222A49029501A809F0E4F9070007D097 -:1012C000386809F05AFA3044B968401C884702E08F -:1012D00023A000F025F830211B4809F00FFA256003 -:1012E00099F80000002819D000F026F82BE60BE052 -:1012F0000029FBD0144A491E0020CBF8001050549E -:1013000020A000F00DF81EE62028EFD00E4A505421 -:10131000491CCBF8001000F011F814E6BDE8FF9F5F -:1013200070B50446184D03E0641C286806F0FEFF03 -:1013300021780029F8D170BD14A0F1E701461248C8 -:10134000006806F0F3BF00003C0400201B5B324A3B -:101350001B5B313B314800001903000878C00008CE -:101360004552523A20556E6B6E6F776E20636F6DEB -:101370006D616E642C20747279202768656C70270B -:101380000000000008200800DC0800200D0A2320CF -:10139000000000002DE9F04105460446FD4EFE4FD9 -:1013A00009E0FC4809F0DFF920B1611B801B3844DB -:1013B00080F80A11641C21780029F2D1BDE8F0817F -:1013C000F64800210278372A12D14288B2F55F7FB1 -:1013D0000ED10279BE2A0BD190F87923EF2A07D1DA -:1013E00000F55F7210F8013B59409042FAD309B101 -:1013F00000207047012070472DE9F05FFFF7E0FF04 -:1014000010B90A2006F0A2FD4FF45F72E349E248EA -:1014100009F05BF9E04C94F87803022802D9002027 -:1014200084F87803C0B200EB001101EB401004EB2C -:10143000800101F59671C422D94809F046F9D84ACD -:10144000D84F002092F8201092F81F5040F6C41692 -:1014500000FB00F3193B4B4303F6C41343436B43B8 -:1014600093FBF6F327F81030401CC0B20628EFD3E8 -:1014700092F8211092F822509146B4F8D220B4F894 -:10148000D080DFF824A300204FF00A0E4FF47A7BBF -:10149000C5F1640701EB8106A2EB080400EB8002B2 -:1014A000C1EB42030122002B03DDC1F16402D2B281 -:1014B00001E000DA0A4603FB03FC05FB0CFC02FB1F -:1014C00002F29CFBF2F23A4402FB03F292FBFEF2C0 -:1014D00002EB460212B204FB02F292FBFBF2424420 -:1014E0002AF8102000F10100C0B20B28D6D399F8D9 -:1014F000000001F0E3FFBDE8F05F04F0F3BB2DE96D -:10150000F047A54D8146372028704FF45F740027BF -:101510006C80BE202871EF2085F879033E4685F85F -:101520007A7369B195F87803C42200EB001101EBDE -:10153000401005EB800000F59670994909F0C5F858 -:101540009548974903E000BF10F8012B57408842A7 -:10155000FAD385F87A73914F4FEA040808F076FFC2 -:10156000342008F0E1FF384608F09EFF04280FD130 -:101570000024E019295908F0B3FF042805D008F029 -:101580006BFF761C032EE9DB02E0241D4445F0D3FB -:1015900008F062FF032E02D0FFF712FF10B90A20F5 -:1015A00006F0D4FCFFF728FFB9F1000F06D0BDE824 -:1015B000F047012214210F2001F078BBBDE8F0872D -:1015C00075498A6802438A6070472DE9FC5F77A1FC -:1015D000D1E90001CDE900014FF45F716E4809F0D7 -:1015E0008DF8C4216E4809F089F86B4B372000252F -:1015F00018700320587102209D60FFF7E1FF83F807 -:1016000078534FF41670A3F8F000FA20A3F8F20014 -:10161000D0332A20D8835D859D85DD859D74DD745A -:101620001D75DD821D835D831C334FF001095D70E4 -:1016300083F80090202018735E4898606E2098769A -:101640002B20D876212018775D7783F82650283311 -:1016500040F2DC505D75188040F24C405880443BAD -:1016600040F26C70A3F8480083F84A5040F27E4084 -:10167000188040F23A7058804FF47A70988040F2A7 -:101680007E50D88040F2EA50188140F2B450588120 -:101690003220C1009881D981188283F84C5083F898 -:1016A0004D504FF4E13119654FF49641596583F877 -:1016B000585040F6AC513A4C23F8C41C83F84B50B8 -:1016C0002826257066701E27E77217216175A6709F -:1016D0002773A1755521E1702D226273E57526717E -:1016E0001921A1733C2121760B216171E573657687 -:1016F0004FF0140B84F806B008232374A2760E2250 -:10170000E27184F811B05021E1765A2121724FF034 -:101710000A0884F812804FF0640A84F81CA06672EC -:10172000A5722575A577E177412184F8201084F80A -:10173000235084F8245084F8255084F8210084F83C -:10174000225025856585E584042084F82C0084F8E2 -:101750002D6084F82E60152084F82F001648206331 -:10176000164860631648A063012084F83C0015A069 -:10177000FFF710FE84F8665084F8675084F86860BC -:10178000012084F8690084F86A5004F8AC8FC823FB -:1017900063701DE0B4C800086C04002000FC010860 -:1017A000E8070020A40A0020B00A00201E1E64647E -:1017B00064646464031414009A99193F52B87E3F1C -:1017C0003333733F4145545231323334000000000B -:1017D0004FF49660608040F2D930A0803D480021EF -:1017E000EE4640F2DC544FF47F754FF4FA6C00BFC4 -:1017F00000EBC10222F86C5FA2F802C094801EF8D0 -:101800000180491C82F806800829F1DB00F8B29FAC -:101810004FF4967180F8019080F80290838080F8F0 -:1018200006B0C77180F80890A0F80AA08181C6812F -:101830000020294D014600BF05EB0012401C11613C -:101840000C28F9DB5FF0000404EB041000EB4410FB -:1018500005EB800000F59670C4221E4908F035FFA4 -:10186000641C032CF0DBBDE8FC9F10B50446FFF7B9 -:10187000A7FD641E204206D1FFF7A7FE0021BDE8A8 -:10188000104008463BE610BD14490968014201D0EA -:10189000012070470020704710490A6802430A601F -:1018A00070470E490A6882430A6070470B48006817 -:1018B000704709498968014201D001207047002022 -:1018C000704705498A6882438A6070470248806889 -:1018D00070470000E80700206C040020040000208E -:1018E00070B5FE4809F098FE0446FD48008809F0EE -:1018F00054F80546214608F0C5FF09F053F8F94CA5 -:1019000029462080F84808F0F3FFF84908F0F0FF76 -:10191000E0650820FFF7B8FF002803D0BDE870405D -:1019200002F05ABD70BD002801DD024600E04242CF -:101930008A4201DA00207047002802DDA0EB010096 -:101940007047FDDA084470472DE9F04F91B0D0E9B7 -:101950000045814686688846086809F05DFE049067 -:10196000D8F800000AF03EFA0590D8F8040009F013 -:1019700053FE0190D8F804000AF034FA0746D8F86C -:10198000080009F049FE8246D8F808000AF02AFA51 -:1019900083465046049908F075FF07905046019918 -:1019A00008F070FF80465846049908F06BFF0690D7 -:1019B0005146059808F066FF08905946059808F0CA -:1019C00061FF03900198594680F0004008F05AFFEB -:1019D00082463946089808F055FF069908F0FAFE45 -:1019E00010903946039808F04DFF079908F047FF1B -:1019F0000E900598019980F0004008F043FF059093 -:101A00003946079808F03EFF039908F038FF029026 -:101A10003946069808F036FF089908F0DBFE834641 -:101A20000499019808F02EFF04903046029908F0BE -:101A300029FF01902846109908F024FF00904146A4 -:101A4000204608F01FFF009908F0C4FE019908F035 -:101A5000C1FEC9F800005946304608F013FF83461E -:101A600028460E9908F00EFF80465146204608F0A1 -:101A700009FF414608F0AEFE594608F0ABFEC9F832 -:101A800004003046049908F0FDFE064628460599F4 -:101A900008F0F8FE05463946204608F0F3FE2946D0 -:101AA00008F098FE314608F095FEC9F8080011B01C -:101AB000BDE8F08F2DE9F04380468A4887B0843036 -:101AC000016881F000410391406880F0004004907B -:101AD0008748B0F9000008F057FF864908F0D2FEA9 -:101AE000804C05907834B4F9000008F04DFF009068 -:101AF000B4F9020008F048FF0190B4F9040008F0BE -:101B000043FF029003A96846FFF71EFF7A4D783C19 -:101B100095F83C00012804D07148008808F03DFF8A -:101B200017E0764840780028206B0CD1C11700EBF5 -:101B30009161A0EBA11008F027FF029908F04AFE7E -:101B400008F030FF2063C11700EB9160801108F0AE -:101B50001BFF029908F093FE0290616B894608F022 -:101B60008BFE0746404608F018FF0646644908F019 -:101B700031FE0146304608F0BBFE394608F082FED1 -:101B8000494608F027FE606309F006FE15F82D1F90 -:101B9000FFF7C9FE08F0F8FE0290009809F0FCFD7E -:101BA0006978FFF7C0FE08F0EFFE0090019809F099 -:101BB000F3FD6978FFF7B7FE08F0E6FE0190E168F3 -:101BC00001EB0800E0602069401C2061009809F0EA -:101BD000E3FD4C4C216808442060019809F0DCFDCD -:101BE000616808446060029809F0D6FDA168084465 -:101BF000A06007B0BDE8F0832DE9F05F394D0446E1 -:101C00008435286809F008FD834628680AF0EAF858 -:101C10008246686809F000FD814668680AF0E2F8CB -:101C20000546D4F808802946404608F02BFE594660 -:101C300008F028FE676806465146384608F022FE3E -:101C4000294608F01FFE05464946206808F01AFE9E -:101C5000294608F0BFFD314608F0BCFD0446514658 -:101C6000404608F00FFE05465946384608F00AFE81 -:101C7000294608F001FE214609F0A4FB224908F09C -:101C800001FE224908F034FE1649896A08F0A2FDD7 -:101C90001F4908F02DFE09F07FFD00B2002802DA8E -:101CA00000F5B47000B2BDE8F09F2DE9F04F8DB0A3 -:101CB000002606F078F8DFF82CB005465C46DBF825 -:101CC0003800281A099008F068FE1249C96808F01F -:101CD000D9FD0490A56300241EE00000F366DF3EFA -:101CE00082010020080000200AE81C4100401C4638 -:101CF000B001002035FA8EBCE8070020700A0020F1 -:101D00003661023CC40800200000E144DB0F49407A -:101D1000000020414C0C00200BF1720A0AF106056C -:101D20004FF07E58FE4890F82C70FE4830F91400B1 -:101D300008F02AFE049908F0A5FD06A941F8240040 -:101D400017B3384608F029FE0146404608F0D0FD9A -:101D500081460B903AF9140008F016FE494608F047 -:101D600091FD814641460B9808F089FDEE4951F8F6 -:101D7000241008F087FD494608F02CFDEA4941F897 -:101D8000240008F00FFE01E03AF8140025F81400D2 -:101D900035F91400641C00FB0066032CC5D3DFF882 -:101DA0008CA364204643BAF8000006A9404396FB82 -:101DB000F0F4DD481830FFF7C7FD0820FFF764FD99 -:101DC00006A910B1D8480C3801E0D6482030FFF7FA -:101DD000BBFDA0B24938DFF858933C2827D2002435 -:101DE000B9F8F00008F0D9FD45464146059008F0E5 -:101DF000F1FC0146284608F07BFDCB4E054618361F -:101E0000C8480C3030F9140008F0BEFD074656F8FB -:101E10002410059808F036FD394608F0DBFC294609 -:101E200008F030FD46F82400641C032CE8D3082099 -:101E3000FFF72AFD48B34546BB4EDFF8E882002491 -:101E40000C3E08F11208B9F8F20008F0A6FD814630 -:101E5000294608F0BFFC0146284608F049FD054622 -:101E600038F9140008F090FD0746484656F824104B -:101E700008F008FD394608F0ADFC294608F002FDDF -:101E800046F82400641C032CEAD35E46BBF900002C -:101E900008F07AFDA44C1834A16808F0B1FD01D215 -:101EA000012100E00021A3484173D4E9010109F0B8 -:101EB00089FA9C4D18352860A068014608F0E2FCBC -:101EC00007466068014608F0DDFC394608F082FCF0 -:101ED0000AF04EF80146206880F0004009F072FADE -:101EE000DFF8548268604146286808F0CBFC09F0AE -:101EF00053FCA5F1580741463880686808F0C2FCD9 -:101F000009F04AFC78800820FFF7BEFC8B4D10B129 -:101F100085480C3801E083482030FFF76DFE2880AB -:101F20000998FFF7C7FD7E4D95F86A0000281BD081 -:101F3000BAF8000008F031FD0146A06808F0D8FCAE -:101F40007F4908F09FFC08F02DFDC0F16400642279 -:101F5000002104F0FBFB95F86A104843C11700EB21 -:101F6000517040F3CF0070800DB0A1E52DE9F04134 -:101F700002F029FA0220FFF787FC20B102F026F9CF -:101F8000FFF793FE05E067480021801D0180418036 -:101F900081804020FFF78DFC624B654CA3F10C0162 -:101FA00018B3A1F15A02107830B9D4F8F400040C37 -:101FB0001470040A547090705A4C0020B4F1060456 -:101FC000155C33F9106034F91070A5F1010C07FBB2 -:101FD0000C66761C96FBF5F521F8105024F810508D -:101FE000401C0328ECD3BDE8F0816079012809D0BA -:101FF0005FF0000033F8102021F81020401C032867 -:10200000F8D3F0E7474AB3F904006C3AB2F9044058 -:1020100000EB4400032490FBF4F088809080188843 -:10202000088058884880DEE73F4900200C3108606E -:10203000486088603B496C390861C86070472DE989 -:10204000F84F05F0B0FE374C46F2A8126C3CE16B3D -:10205000A0EB0108904502D20020BDE8F88F394F6F -:10206000E0632F4D3888DFF8E090DFF8E0A0DFF87C -:10207000E0B04FF07E5640B3206D6269C11700EBAF -:102080005171A0EBE10095F82F10491EB2FBF1F160 -:102090000844C117206500EB5170C01008F074FCB3 -:1020A000494608F025FC514609F08EFB314608F000 -:1020B000E6FB594608F0E6FB08F074FCE0640020FB -:1020C000206460643888401E388095F82F0061696C -:1020D000401EB1FBF0F008F060FC494608F008FC37 -:1020E000514609F071FB4FF07E5108F0C8FB59468C -:1020F00008F0C8FB09F050FBE16C2F6B461A39461B -:102100004FF07E5008F0B8FB8146304608F03CFCAA -:10211000494608F0B7FB0646A06908F035FC19E00F -:10212000E807002074000020B80800208201002089 -:102130006C040020700A00204C3D0F44B0010020C8 -:102140000000C842AE01002080E6C547B1DC423E37 -:10215000D048874A394608F095FB314608F03AFBEB -:1021600009F01AFB8346A061E06808F016FC0746F8 -:10217000654908F087FB0646206908F005FC8146A2 -:102180006248806808F000FCE16D08F07BFB39468E -:1021900008F078FB494608F0ABFB0746206C314657 -:1021A000009008F06FFB81464FF0FF31384608F091 -:1021B000DFFB314608F066FB494608F00BFB616C1B -:1021C00008F008FBD5F83890824649464FF07E501B -:1021D00008F052FB0646584608F0D6FB314608F098 -:1021E00051FB06464946504608F04CFB314608F084 -:1021F000F1FA606408F0D6FB60653946009808F093 -:10220000E9FA2064FFF710FFD4E915104FF4967730 -:10221000401AC7F100093A46494604F097FA0A21E4 -:10222000FFF781FB297906467143C81701EB50601F -:10223000C822C011514204F089FAE061A97B4CF236 -:1022400050327143C81701EB9060216A01EBA01076 -:102250005142206204F07AFAC117206200EBD1509B -:10226000E16901EB6020E061404608F096FB8046A2 -:10227000A669A06C301A08F087FB254908F002FB1C -:10228000414608F035FB08F08DFB3A464946A66406 -:1022900004F05CFA0A21FFF746FB6F6B8046394673 -:1022A0004FF07E5008F0E8FA0646404608F06CFB16 -:1022B000314608F0E7FA06463946206C08F0E2FAA3 -:1022C000314608F087FA206408F06CFB4FF47A720C -:1022D000514204F03BFA08F057FB206409F05CFA25 -:1022E0000521FFF720FB6062297E96224143C81733 -:1022F00001EB107000116FF0950104F027FAE1690D -:10230000081AE0610120A8E6BD378635C408002020 -:102310000024744970B5994D0446286807F05FF9A8 -:102320000028FAD0E1B2286807F040F9204670BDD5 -:1023300086B005F081FD0020FFF797FAFFF75CF803 -:102340008F4C002594F8090118B101281ED00928E6 -:102350001CD08DF8105084F8095104A804F022FC18 -:1023600004F0FCF90E20FFF797FA00F039F96079D4 -:1023700001260E280DD008280BD08DF8065000BF7E -:102380004FF48070FFF795FA50B905E08DF8100012 -:10239000E3E78DF80660F3E70820FFF78AFA00B15B -:1023A00001208DF802004FF4004B5846FFF781FAE8 -:1023B0008DF803000120FFF77CFA8DF8010008205A -:1023C000FFF777FADFF8B48180F001008DF80000A4 -:1023D0006C4F98F812008DF8040097F8B400C0F321 -:1023E00080008DF80500B4F8DE00ADF80800B4F800 -:1023F000E000ADF80A004FF48040FFF75AFA08B148 -:10240000B4F8DA00ADF80C00B7F8B000ADF80E0083 -:1024100094F80901012823D0092824D08DF8075009 -:10242000684605F0BBFB5849002040F2DE5200BF71 -:1024300021F81020401CC0B21228F9D35449534847 -:102440000827086088F811703846FFF732FAB0B1F3 -:1024500094F8120158B1012809D002281CD10AE0D1 -:102460008DF80760DCE707208DF80700D8E74848BB -:1024700003F060FE10E0464804F02BFB0CE094F8FB -:102480001C0128B194F91D01002801DA84F81D51BE -:1024900094F81D0103F06FFC0120FFF70AFA30B138 -:1024A0004FF48060FFF705FA08B102F019F83949D6 -:1024B0004FF0100AC1F800A0A1F10409B846C9F80C -:1024C00000700025A9F10407386880F0100038601A -:1024D000386880F008003860192005F08DFC012074 -:1024E00005F095FC192005F087FC002005F08FFC15 -:1024F0006D1CEDB20A2DE7D3C9F80080C9F800A021 -:1025000001F0A6FCFFF7ECF90220FFF7D2F908B1C1 -:1025100001F06AFDD4F8200102F013F95846FFF7E4 -:10252000C8F928B194F82811D4F8240106F05CFF0A -:102530004FF40060FFF7BDF908B103F0A9FF05F003 -:1025400032FC154908606079052803D113494FF41E -:10255000C870088012494FF47A7008801149C82069 -:102560000880114880F80D6000F0B0FFFCE70448D7 -:10257000B0F9D40000F029F9FEE70000DC080020E3 -:102580006C040020E8070020800A00207F3000084B -:1025900004010020140C0140000100207E010020F5 -:1025A00080010020AE010020700A00200146F6489C -:1025B00000EBC100B0F97000122804DA082902DA31 -:1025C000F24931F910007047EF4A02EBC00090F970 -:1025D0007200084202D04FF0FF3070470120704770 -:1025E0002DE9F041EA4EEB4F707907EBC0004078DF -:1025F00000B10120E84CA0742020FFF75AF908B17F -:102600000120A0747079E54CE54D162808D017F824 -:10261000301007EBC0002170426842B3002024E074 -:102620005FF0000006EB00110A6912F0FF4F1ED0A8 -:10263000D1E9057C05EB0013C969401CC3E902C15F -:10264000C3E900272178491C21700C28EADB0EE041 -:1026500002EB001305EB0016D3E9007CD3E90283FB -:10266000C6E90283C6E9007C401C8842F0DB4FF4D7 -:102670008040FFF71EF900281AD02778012F17D9BC -:10268000002613E005EB06144FF0FF384146A06822 -:1026900008F06EF9A0604146606808F069F9606072 -:1026A0004146E06808F064F9761CE060BE42E9DB70 -:1026B000BDE8F081F0B5401C0021B54A0B4600BFD3 -:1026C00002EB0114491C23610C29F9DBB14B03EB2C -:1026D000C0014C68002C11D0002113F830000BE031 -:1026E00004EB011302EB011593E8C010DB68491CF1 -:1026F000C5E906C3C5E904678842F1DCF0BDA64818 -:1027000010B5807C00284DD0A44CA148A41C42796F -:10271000E0882189082A27D006DC012A15D0042A5E -:1027200029D0052A06D10AE00E2A3BD0142A22D04D -:10273000152A25D02020FFF7BCF8002832D02188A8 -:10274000002005F0BBFA618813E094498E48891C8B -:1027500090F8B300498908B100201FE09148407803 -:102760000028F9D10021F7E70146002005F0A6FA7C -:102770002189012012E0002005F0A0FA6189F8E724 -:102780000146002005F09AFA2189012005F096FA09 -:102790006189022005F092FAA1890320BDE810406A -:1027A00005F08CBA10BD70B57D4E0024183E7B4DEF -:1027B00007E000BF36F81410204605F074FA641CD8 -:1027C000E4B228788442F5D370BD744A744B00217A -:1027D0001278183B04E000BF23F81100491CC9B26D -:1027E0009142F9D3DFE72DE9FC5F6C4C6E4E6F4DE3 -:1027F0002078032814D9B6F904004142002801DDED -:10280000024600E00A4602F1640200DC08466FF06E -:102810006301A1EB0001B5F9040003F097FFA88064 -:102820005E48DFF87C91DFF860A10078A9F1180913 -:10283000012839D90024804634E000BF9AF9B2005B -:10284000B5F904104042484308F09EF8544901EBA2 -:102850000417F96808F016F80190B5F9000008F0BF -:1028600093F8796808F00EF80090B5F9020008F0C6 -:102870008BF8B96808F006F88346B6F9060008F048 -:1028800083F8396807F0FEFF594607F0A3FF009967 -:1028900007F0A0FF019907F09DFF08F083F829F8E1 -:1028A0001400641C4445C9D3DFF8E4803B4CDFF8D6 -:1028B00000B198F80500A41C08287DD006DC01288A -:1028C00037D0042809D0052840D140E00E283DD05B -:1028D000142870D01528F7D1EAE00420FFF766FE2F -:1028E000034602210420FFF76FFEB5F9041000FB38 -:1028F00001F601210420FFF767FEB5F9021000FB85 -:102900000160184420810520FFF750FE0346022194 -:102910000520FFF759FEB5F9041000FB01F601216F -:102920000520FFF751FEB5F9021000FB01601844C5 -:102930000BE00520FFF73AFE034601210520FFF7D3 -:1029400043FEB5F9041000FB01306081D4E09AF930 -:102950007200BBF902103225484390FBF5F60AF1EC -:1029600072025B460020FFF721FE3044208092F97E -:102970000800B3F90010484390FBF5F20120FFF77F -:1029800015FE10446080B7E0E8070020800A0020B0 -:102990006C04002030CD0008DC080020B4000020CA -:1029A00008090020700A00204401002036010020A0 -:1029B0003400002000E063E0B84F787878B3B8F8CE -:1029C000D220B8F8D010B6F9060003F0BFFEE081BF -:1029D000A9F80000B87A4FF0010100284FF0030079 -:1029E00021D0FFF7F1FDB6F9021000FB01F302213F -:1029F0000320FFF7E9FDB6F9001000FB0130E0808D -:102A000001210420FFF7E0FDB6F9021000FB01F3FD -:102A100002210420FFF7D8FDB6F9001020E0FFE7FF -:102A2000B8F8D400D3E7FFF7CFFDB5F9021000FBEB -:102A300001F302210320FFF7C7FDB5F9001000FBE9 -:102A40000130E08001210420FFF7BEFDB5F902103E -:102A500000FB01F302210420FFF7B6FDB5F90010D9 -:102A600000FB013020810320FFF7A0FDE18808442E -:102A7000E0800420FFF79AFD2189084420813BE093 -:102A8000042301211846FFF79FFDC3F1050135F826 -:102A90001110484324F813001846FFF787FD34F857 -:102AA0001310084424F813005B1C062BE9D323E021 -:102AB000032302211846FFF787FDB5F9041000FB38 -:102AC00001F701211846FFF77FFDC3F1060121F050 -:102AD0000101695E01FB007024F813001846FFF73E -:102AE00065FD34F81310084424F813005B1C072B11 -:102AF000DFD3F188A9F800102020FEF7DAFEC0B37A -:102B00000020FFF753FD20800120FFF74FFD6449AF -:102B10006080097A69B39AF8B4205146920715D5B6 -:102B200091F972209AF97A105542BBF90220BBF94B -:102B3000003055433222594395FBF2F591FBF2F1F7 -:102B40006A1A238829449A1A228010E09AF972306E -:102B5000BBF90220268803FB02F5322295FBF2F531 -:102B600035442580BBF900104B4393FBF2F1084438 -:102B7000608000254FEA0A0606EBC5006C30B0F90C -:102B80000220B0F9001034F9150003F0DFFD24F83D -:102B900015006D1C082DEFD396F8B400DFF804A1E2 -:102BA000400711D500252020FEF783FE00B1022545 -:102BB0000024564606EB440001896019C0B205F0B6 -:102BC0007DF8641C042CF5D337494C46B9F90070E4 -:102BD00001200B7806E000BF34F91020BA4200DD76 -:102BE0001746401C9842F7D300254FF4804B894686 -:102BF0004DE0B8F8D2004646B84205DA34F8151070 -:102C0000381A081A24F815005846FEF752FE98B1F3 -:102C1000BAF9060040F2DC51884204DDB6F8D22051 -:102C2000B6F8D81003E0B6F8D620B6F8D41034F9C8 -:102C3000150003F08BFD15E0B6F8D220B6F8D010E1 -:102C400034F9150003F082FD24F81500BAF90600E6 -:102C5000B6F81611884207DA1020FEF72AFE38B1BE -:102C6000B6F8D40024F815000C48407818B10DE0EF -:102C7000B6F8D000F6E75846FEF71BFE10B1B6F8DE -:102C8000DA0001E0B6F8D40024F815006D1C99F8BC -:102C900000008542ADD3BDE8FC9F0000700A002013 -:102CA000C60A0020800A0020B40000202DE9F04769 -:102CB0001746894606460025DFF83C841AE00024C2 -:102CC00011E000BFD8F8001081F00801C8F800102A -:102CD000012005F09CF8484605F08EF8002005F02C -:102CE00096F8641CE4B2B442ECD33C2005F084F8BE -:102CF0006D1CEDB2BD42E2D3BDE8F0872DE9FC5F6B -:102D0000FE4C002540F2DC51B4F90600FC4E4FF4B5 -:102D1000FA73884201DA64210CE0F949B0F5FA6FE0 -:102D200091F8251004DAA0F2DC52514391FBF3F143 -:102D3000C1F164018946F34996F866E096F867B0F8 -:102D4000B1F814410022B246EC49EE4B40F2E63CA9 -:102D500031F91260311B01F2F317674503D80029DE -:102D600003DCA11B01E04FF4FA71022A34D0BEF15A -:102D7000000F05D08E4502DAA1EB0E0100E0002124 -:102D8000642391FBF3F3DD4F6FF01808243707EB52 -:102D9000430C37F91370BCF902C003FB08F3ACEB2A -:102DA000070C01EB83030CFB03FC64239CFBF3F394 -:102DB0003B44D54F27F812309AF823304B434FF459 -:102DC000FA7193FBF1F1C1F1640189B201FB09F1E0 -:102DD000642391FBF3F11CE0BBF1000F05D08B45A0 -:102DE00002DAA1EB0B0100E0002193F9EC30DFF8EF -:102DF00018C35B424B43ACF804309AF824300029E6 -:102E000000DC49424B434FF4FA7193FBF1F1C1F1FD -:102E100064010AEB0207642397F801C0DFF8E88237 -:102E20000CFB01FC9CFBF3FCA8F1540808F802C061 -:102E300097F80BC008F103080CFB01FC9CFBF3FCAA -:102E400008F802C07F7D4F4397FBF3F108F10303BD -:102E5000A642995405DAAC4931F812305B4221F8A8 -:102E60001230521C032AFFF66FAFDFF898A24FF41E -:102E7000FA625446BAF8161103F068FCB4F8161159 -:102E80004FF47A72401A5043C1F5FA61B0FBF1F188 -:102E9000642291FBF2F0994B6FF01806303303EB8C -:102EA000400433F910307043B4F9024001EB800064 -:102EB000E41A444394FBF2F0DFF84C828F4E18443E -:102EC000103EA8F80600707AA8F17C04E8B38F4899 -:102ED000B4F91E10B0F90000401A07F055FD8C49F6 -:102EE00007F0D0FC8B4907F003FD074608F094FB80 -:102EF0000190384608F076FF00904746B8F9000088 -:102F000007F042FD8346009907F0BCFC8046B7F904 -:102F1000020007F039FD8146019907F0B3FC4146F4 -:102F200007F058FC07F03EFD80464846009907F040 -:102F3000A9FC81465846019907F0A4FC494607F0D0 -:102F40009BFC07F02FFD388000E001E0A7F802802D -:102F50000220FEF7AEFC002750B3E078401CC0B260 -:102F60000621B0FBF1F2E07001FB1200B8B90020BD -:102F700003F08AFE2179614A01F00703AC3A491C4B -:102F800022F813002171002032F81010401C29444F -:102F90008DB20828F8DBE80801F00EF8A072A07ADC -:102FA000E18C884203D89AF80811814201D9A770B0 -:102FB00001E00420A070A07803F05FF956484E4D60 -:102FC000008818B10220FEF75FFC10B95348008852 -:102FD00020B1286880F00800286011E0B17808204E -:102FE00011B14549091D0860717811B14249083194 -:102FF00008604FF40060FEF75CFC08B103F05DFA76 -:103000008020FEF756FC48B1E16C606B411A05D494 -:103010004CF250310844E06405F010FAA16C606B8A -:10302000411A03D4717BF9B10120B07002F011F89C -:103030002020FEF729FC68B1216D606B411A09D48C -:10304000E17A052906D3364908442065286880F0CE -:10305000100028603348816800290ED002B02A4849 -:10306000BDE8F05F5C380847B770296881F0080157 -:1030700029602D490844A064D8E7BDE8FC9F10B53D -:10308000204C204490F80A0104F022FEA0F2EE2128 -:1030900040F2DD52914201D3B4F8140110BD2DE984 -:1030A000F047194EDFF854807C3EA8F19C087079F7 -:1030B000124F401C00247071A14608F14005F16BCD -:1030C00020468847727908EBC40102F0030221F818 -:1030D000120025F81490002035F8143031F8102033 -:1030E000401C1A44C0B225F814200428F4D335F942 -:1030F0001400801CC11719E00C0C0140800A00204C -:10310000E80700206C04002044010020B0010020EA -:10311000DB0F4940000034437E0100208001002085 -:10312000F04902004C0C002020A1070000EB917038 -:10313000801025F8140037F91410C91E884202DAED -:10314000811C27F8141037F91410C91C884202DDBD -:10315000801E27F81400641CE4B2082CAFD3CBE522 -:10316000FE480288FE48417852B9827842B100296F -:1031700005D101214170FB48FB490088C883704795 -:103180000029FCD10122FF2102208FE52DE9FC5FFF -:103190000020F54982467C31054607460190B1F989 -:1031A00002004342002801DD044600E01C468B4635 -:1031B000B1F900104A42002901DD0E4600E0164632 -:1031C000B44203DD002806DC184604E0002901DDD6 -:1031D000084600E01046DFF8949300240090E04E8B -:1031E000F07808B93079E8B3022C3FDADE484FF4C2 -:1031F000FA72443030F914103BF9140001EB40002E -:10320000514203F0A3FADA49DFF868A331F9141048 -:10321000411A0AEB4400B0F9280001EB00089AF8C3 -:103220000810642001FB08F191FBF0F09AF81C10E3 -:1032300001EB8102494201EB810103F087FA019021 -:10324000C94842F21072743050F8241001EB0800A3 -:10325000514203F07BFAC449743141F824009AF8D2 -:10326000121000E008E048434FEA203AF07818B125 -:10327000307908B9022C48D13BF91450B84F05EB0E -:1032800085000101BB48A83F00EB04084FF47A52C7 -:1032900098F8010091FBF0F039F91410401A57F832 -:1032A00024100844514203F051FA47F8240039F938 -:1032B000140000F52070B0F5A06F02D857F8240074 -:1032C00002E0002047F824007D2190FBF1F098F8FF -:1032D0000B10484387113079A8B1022C13DA0098FB -:1032E000009AC0F5FA710198009B484305FB020063 -:1032F0004FF4FA7201FB0AF107FB031190FBF2F0A5 -:1033000091FBF2F608E0F07820B1022C02DA564682 -:10331000019801E028463E46934A39F914102832B4 -:103320005023125DDFF838824A4392FBF3F28E4B52 -:10333000821A6833A8F13C0833F9140023F81410FA -:10334000081A08F10C0158F8243051F824C041F84B -:1033500024309C44844448F8240083482E30005D87 -:1033600000FB0CF0C11700EBD1609119A1EB6010CC -:103370007D496E3121F81400641C032CFFF62FAF39 -:103380007BE62DE9F05F764E4FF0000BDFF8E4A10D -:10339000DFF8D4915C46A83E714DE87808B92879E9 -:1033A000D0B1022C18DA70484FF4FA72443030F978 -:1033B0001410383030F9140001EB4000514203F092 -:1033C000C5F96B4931F91410411A0AEB4400B0F900 -:1033D000280001EB000B01E0022C52D0E878E0B3AA -:1033E0009AF8080000FB0BF0001160490AEB040793 -:1033F00031F91410FA7A451A787856F8241068438F -:103400004FEAE018B9F80C006843C01200FB021044 -:103410004FF4001246F82400514203F097F946F8A1 -:10342000240043134E480C3850F8241040F8245020 -:10343000B9F80C00691A02094FF6FF70B0FBF2F000 -:10344000484347498011243901F10C0251F824C046 -:1034500052F824506544054400E01CE042F824C0C2 -:1034600041F82400787D6843011208EB030008440A -:103470003D496E3121F81400641C032C8CDBBDE83F -:10348000F09F9AF8240038491B307C31B1F90410C0 -:1034900048434011A9E7344A9AF823007C321B3094 -:1034A00032F9142050432A790011002A9DD09AF84D -:1034B000121001FB0BF100EB212096E72A490128AD -:1034C00001D02D4800E02D48086470472DE9F84FE1 -:1034D0000027B946B8460820FEF7EBF9DFF8A0B0A0 -:1034E00068B19BF8120120B1012802D0022806D150 -:1034F00002E002F042FE01E003F00AFB8046DFF842 -:1035000068A0174C4FF00005DAF83410DAF85400D0 -:103510004FF00106081A02D5B8F1000F7DD044F62D -:1035200020621144CAF85410FFF7B9FD4FF48040EF -:10353000FEF7BFF928B10A485630007808B900F004 -:103540007DFC9BF81B0168B305494FF47A7210317A -:1035500001EB40000021B0F9060013E080010020DB -:10356000700A0020B0010020C80000206800002080 -:1035700034000020E80700208D3100088333000864 -:103580006C040020A0F57A7003F0E0F807F0FCF975 -:10359000FE4907F0ADF9FE4907F074F907F01BFA90 -:1035A000AAF822004FF40070FEF783F9B0B3DFF8F9 -:1035B000E483BAF90E2098F8ACC00CEB8C01914270 -:1035C0001DDA6078D8B1BBF91431F349002000BF8F -:1035D00021F81030401C0328FADBB8F8AE30CB805D -:1035E00098F8AD00604400EB8000904202DA00F0F1 -:1035F00025FC2570BAF81010491CAAF8101098F88C -:10360000AC0000EB8001BAF90E00814204DA607868 -:1036100010B900F013FC257001E068E204E0BAF88C -:103620000E10491CAAF80E10BBF816C1BBF81821E1 -:10363000DFF864830020BF0838F91030634501DDEE -:1036400047F08007934201DA47F04007401C042806 -:10365000F1DB9AF8071050468F4205D18179FA299B -:1036600003D2491C817100E085718AF807704FF41C -:1036700080473846FEF71DF958B1BBF81411BBF866 -:10368000DC00B8F906200B1A934202DA0844904293 -:1036900009DC3846FEF70DF9E8B9B8F90610BBF8B1 -:1036A0001601814217DABC48B8380560456085606C -:1036B000BA4805604560B748C08F60B1B64846302B -:1036C000007820B1207810B1FFF74AFD03E0607860 -:1036D00008B100F0B3FB9AF80600142817D16078FF -:1036E000B0B1AC4FF88F28B99AF807005F2801D124 -:1036F00000F0A4FB9BF81A01002808D0F88F0028DE -:1037000005D19AF807007D2801D100F097FB8FE0E2 -:103710009AF80700572809D00420FEF7CAF8E8B144 -:103720009AF8071050465A2921D017E09C494FF4C7 -:103730007A7008804FF48070FEF7BBF808B101F092 -:1037400068FF0420FEF7A0F810B196490A2008800F -:103750000820FEF799F808B9934805809AF8070001 -:103760005D2817D05B2817D05E2817D023E0818A08 -:1037700019B18582AAF816601DE0818C21B1002163 -:10378000818419B1022102E00121F9E703218AF8BD -:10379000001010E0012702E0022700E00327781E56 -:1037A0008BF8780300210846FDF7A9FE3A46282148 -:1037B0000220FFF77BFA774FF88F18B99AF80710B5 -:1037C0006F290ED09BF81A1121B118B99AF8070089 -:1037D0007E2806D09AF80700972805D0A72808D099 -:1037E00008E0FFF7BDFC05E070494FF4C8700880A1 -:1037F00000E0A6739AF80700BB2806D0B72807D0C8 -:10380000BE2809D0BD280AD012E0788D801C01E0C6 -:10381000788D801E788505E0388D801C01E0388D1C -:10382000801E388501210846FDF769FE8AF806509A -:103830000420FEF73EF820B3BAF824205046322187 -:103840006AB162785AB1B8F90630BBF816219342D2 -:1038500005DD514A463212780AB9418285844E4AC2 -:103860004632527C32B1028B838A1A4309D1AAF8BC -:10387000121006E0818A21B1617811B98582AAF817 -:1038800016600020C64640F2A46700BF0EEB400160 -:10389000B1F9082040F214518A4201DA012300E014 -:1038A000002300EB40018B40A2F2155CBCF5C77F02 -:1038B00002D84FF0010C01E04FF0000C01F10108BB -:1038C0000CFA08FC43EA0C03BA4201DD012200E0D5 -:1038D0000022891C8A40134343EA0903401C1FFA53 -:1038E00083F90428D2DB2C4F00204637294901EB0D -:1038F0004001C98F11EA090100D001213954401C4F -:103900001428F3DB787840B9224890F8AC0000EB3B -:103910008001BAF90E0081420ADA0220FDF7B4FFF5 -:1039200030B1E07828B91D4805604560E67000E0D8 -:10393000E570B87838B1E570207928B91748056086 -:103940004560267100E025713878B84600B92670C8 -:10395000E178102009B9217909B1154901E014492C -:10396000091F08600420FDF78FFF70B198F803006D -:10397000474650B3A07938BB0E48A67101680E487F -:10398000016006480830C18818E02BE000007A4446 -:1039900000C07F44E8070020800A00203C0100208E -:1039A00080010020AE010020B00100207E01002037 -:1039B000140C01405C00002060000020FF48AAF8C1 -:1039C0001A100560FE48056000E0A5714FF4005034 -:1039D000FDF76FFF30B1387918B1E07B10B9E673AD -:1039E00000E0E5730220FDF74FFF18B90820FDF74E -:1039F0004BFFD0B198F80510404639B1617931B923 -:103A0000F04966710A88F0490A8000E065718179A1 -:103A100019B1617A11B9667200E0657298F8070011 -:103A200018B1E8480188AAF81E102020FDF72CFFE5 -:103A3000F0B3E07AE8B39AF80B005746052844D370 -:103A400098F80A1059B1E07990BBE671DF49257208 -:103A50003D72081F02F09BFA0220787039E0E57190 -:103A600098F80B0030B3D94A143AB2F90000002894 -:103A700000DC4042D649B1F8C01088421DDAB2F9E4 -:103A80000200002800DC4042884216DA207A78B929 -:103A9000CE4826720C383D7200F1100102680A60AF -:103AA000406841F8040FC948001D02F070FA02E0B6 -:103AB0000FE00AE001E07E700BE02572387A40B931 -:103AC0008AF8086002F038FA03E0E57125728AF896 -:103AD000015098F80C0008B1A67200E0A5729BF89E -:103AE0000500082801D00E2843D1657241E0DAF8BC -:103AF0005C005746042801DD401FF865052838D2D0 -:103B0000DFE800F0030B151F2A000820FE65FDF713 -:103B1000BBFE10B100F06DFC58BBF86D401CF865A1 -:103B20000420FDF7B1FE10B100F073FB08BBF86D87 -:103B3000401CF8650420FDF7A7FE10B1FEF77FFAE0 -:103B4000B8B9F86D401CF8654FF48070FDF7B1FE10 -:103B500010B102F0C0F90CE0F86D401CF8651020BF -:103B6000FDF792FE08B100F0C6FC4FF40050FDF7DF -:103B7000A0FE04F018F9CAF83400BBF80C20574630 -:103B800012B1BB6DC31A71D41044D946B865FEF7A3 -:103B9000EDF9FFF7B3F804F006F97863398F411AAD -:103BA000B981B8630820FDF76FFE48B3874914391F -:103BB000B1F9042002F145008A2822D8607900B3C7 -:103BC0008048038880480088181A00B210F1B40FAA -:103BD00002DC00F5B47000B2B42802DBA0F5B470CA -:103BE00000B299F9EC305B42434318B2637B3BB1BE -:103BF000774B5B7A43431E2093FBF0F0101A8880CA -:103C000003E070480188704801800420FDF73CFE05 -:103C100058B3A07948B36E4991F8690038B36B483E -:103C2000B7F91A201438B0F90630A3EB020CBCF136 -:103C3000000F01DCA2EB030C91F868108C4509DD44 -:103C4000DFF878C19342CCF800507E7200DD494223 -:103C5000194409E0797A21B15E490B685E490B602D -:103C60007D72574909881144C1803AE0E4E0FFE7DA -:103C7000DFF85881B7F91A00A8F11408B8F906302E -:103C80001A1A002A01DD134600E0C31A91F86810E1 -:103C90008B420FDDB98B4FF4FA6C114409B291FBE2 -:103CA000FCF34D4A0CFB131115681D441560B983D4 -:103CB0007E7207E0797A29B146490A6846490A6066 -:103CC000BD837D723E490988084400B2A8F8060009 -:103CD000B9F8D010B9F8D220963102F037FDA8F823 -:103CE00006003B4D95F86A0050B1E07808B920799C -:103CF00030B13648394A1438C18812881144C1801D -:103D00002020FDF7C1FDE8B3E07908B9207AC8B3F7 -:103D1000207BB8B32B4CB4F9000006F035FE304ED2 -:103D2000314606F0AFFD08F05DF80090B4F90000F0 -:103D300006F02AFE314606F0A5FD07F06DFC234C87 -:103D4000064695F8B900303CDFF898A0A4F11C08AD -:103D500010B3A146B4F90200241DB4F90210401AB0 -:103D600001F008FA15F8B92F514202F0EFFC618812 -:103D700008446080B9F90000B4F90010401A01F05D -:103D8000F9F900E04EE02A78514202F0DFFC218888 -:103D9000084400B2208001E0B4F9000006F0F4FD10 -:103DA0008346009906F06EFD0546B4F9020006F060 -:103DB000EBFD8146314606F065FD15E02800002048 -:103DC00024000020B0010020B20100205801002092 -:103DD000E80700205C000020600000200A000020AE -:103DE00035FA8E3C00002041294606F045FD554637 -:103DF000514606F07DFD06F0D5FDA8F800004446CA -:103E00005846314606F03EFD06464846009906F003 -:103E100039FD314606F0DEFC294606F069FD06F064 -:103E2000C1FD6080386C8047FEF7DDFCFEF767FC63 -:103E3000BDE8F84FFEF7B7BCBDE8F88F03484178FE -:103E4000002901D00021417070470000700A002055 -:103E50002DE9F843FE4CFF4BFF490026B4F8EE2055 -:103E60009846A1F1100004F0EAFB08B101260EE02B -:103E7000B4F8EE10F84804F0F1FD40B9B4F8EE10D3 -:103E8000F54803F082FD10B9032004F05FF8F34D0C -:103E90005FF0000794F8ED0006283CD2DFE800F060 -:103EA0000707192833030220FDF7FBFC33E08DF8E8 -:103EB00000704FF44870E849ADF8020010396846C8 -:103EC00002F085FF08B10120287094F8ED00012868 -:103ED00021D06EB1E049B4F8EE204346A1F11000C4 -:103EE00004F0ADFB0220287094F8ED0002281DD0EC -:103EF000D948103804F0ACFC28B10320287094F89D -:103F0000ED00032812D0D448103805F02EFB10B174 -:103F1000042028700AE0287840B994F8ED0010B128 -:103F200084F8ED70B6E70220FDF7BBFCCA481030FC -:103F300004F097FE38B9C848103002F0EFFF10B90E -:103F40000420FDF7AEFC0220FDF79EFC28B1C2491B -:103F500094F8E300103909688847BF4914F8E20F64 -:103F600009688847A07803F0F3F810B90820FDF736 -:103F700098FCBB486421B0F9262092FBF1F001FBCC -:103F8000102406B20820FDF77FFCB64D90B1204604 -:103F900006F0FAFCB44906F075FC0446304606F01B -:103FA000F3FC214606F016FCB04906F06BFC2860D5 -:103FB000BDE8F8832F60FBE770B50546A44890F88C -:103FC000060106F0EAFC0446284606F0E6FCA8498D -:103FD00006F058FCA74906F08BFC214606F052FC7F -:103FE00006F0F9FC80B270BD70B500252C460020AB -:103FF00002F04AFE05440A2003F0FEFE641C202C59 -:10400000F5D3C5F34F10FFF7D7FF914A022192F87D -:10401000073100BF03FB01F4844202D8491C062982 -:10402000F8D39548017092F80801484393490880F5 -:1040300070BD2DE9F05FDFF82492914E884FB9F8FA -:104040000220834C0025C2B38E4900204FF4C8786B -:10405000424501D141F8205051F8203036F910C0C6 -:10406000634441F8203026F8105004EB4003401C14 -:10407000A3F8FA500328EBDB012A19D10868C830ED -:1040800090FBF8F024F8FA0F4868C83090FBF8F07D -:1040900060808868C83090FBF8F1B9F80600081A0B -:1040A000A0803D850121FA3C7D850846FDF727FA71 -:1040B000B9F80210491EA9F802100420FDF7F9FB17 -:1040C000002874D0704BDFF894816E491A8808F18B -:1040D00020080C31A8F1180A322A05D0F2B30020CA -:1040E0009B46322A14D015E034F8FA0FA8F80000E5 -:1040F0006088A8F80200A088A8F80400B7F828C0D3 -:10410000AAF800C0B7F82AC0FA3CAAF802C0E6E74D -:1041100041F8205051F8203036F910C0634441F87E -:10412000203026F8105004EB4003401CA3F8FA504E -:104130000328D6DB012A1AD15448554B05800120AB -:104140001880544B02201870B8F8000024F8FA0FB9 -:10415000B8F802006080B8F8040000E00AE0A0802F -:10416000BAF800303B85BAF80200FA3C7885521E56 -:10417000ABF8002048480288012A18D105800A6857 -:10418000322092FBF0F224F8FA2F4A6892FBF0F208 -:104190006280896891FBF0F1B9F80600081AA080E6 -:1041A0003D850121FA3C7D850846FDF7A8F9308858 -:1041B00034F8FA1F401A308070886188401A708085 -:1041C000B088A188401AB080BDE8F09F224810B5A1 -:1041D000103841682A488847BDE8104029E730B5C3 -:1041E0001E4C1F4AE06892F82F200146401C824274 -:1041F00000D10020294A1368224A183242F821309F -:10420000274952F820200D682B449A1A0A60E06072 -:1042100030BD70B52348114C00682169411A01D5A1 -:10422000002070BD20610C4D6069103578B128699F -:1042300080476868804728882169084420616A6946 -:1042400019491648904700206061022070BD2DE09A -:104250006C040020EC0800204C0C00207C010020A5 -:10426000E8070020300000208988883C00002041B9 -:104270003333534000F07F4568010020EE000020FA -:104280007A0000201C0B0020DA000020E000002053 -:10429000DC000020C8000020DE000020A00000207C -:1042A0001C000020FC000020A4000020A86880471B -:1042B000E8688047FFF793FF012060616888216903 -:1042C00008442061012070BD2DE9F05FA24DA8884F -:1042D00000286AD0DFF884820024A3464FF47A795C -:1042E000A8F10C06A888484507D104EB840208EB26 -:1042F000820146F824B0C1F810B0994F56F8241046 -:1043000037F91400014446F8241006F03DFB01463D -:1043100004EB840208EB8200824600F0EFF827F8F5 -:1043200014B0904F27F814B0A888012837D1DAF8D4 -:104330001000012808DD401E06F026FB0146DAF8D1 -:104340000C0006F0D5FA00E0002007F011FE8246CE -:10435000854890F8F800A8B106F01FFB514606F01A -:104360004FFB0FD27D49A5F80490C8F810B0C1F8F2 -:1043700024B0C1F838B0C6F808B0C6F804B0C6F822 -:1043800000B00CE056F82400012200F5FA7090FB12 -:10439000F9F027F814000F210A20FEF787FC641CAF -:1043A000032C9FDBA888401EA8806D496D4A002021 -:1043B00031F8103032F810401B1B21F81030401C2F -:1043C0000328F5DB00E7654810B54C3041686448C8 -:1043D0008847BDE8104077E710B5644810240460B2 -:1043E00002F005FF6148001F04605B49012048702E -:1043F00010BD2DE9F0415E48574C0068A169411A93 -:1044000002D50020BDE8F0815A490844A0615A480D -:1044100002F0B5FEDFF864C14F4B00269CF80E0099 -:104420005549514A26339D1D88B1A069E06100209D -:1044300002EB4007A7F8006131F8107023F8107004 -:1044400025F81070401C0328F2D38CF80E606078B9 -:1044500070B10888B2F80071C01B08804888B2F8B3 -:104460000271C01B48808888B2F80471C01B888024 -:10447000E06998B3A769381A414FB84218D23B484F -:104480000838026882F008020260002031F910202A -:1044900033F91040A24201DA23F8102035F9104018 -:1044A000A24201DD25F81020401C0328EED315E0C0 -:1044B0000020E66133F9101035F91040214402EB79 -:1044C000400401EBD17141F34F01401CA4F80011ED -:1044D0000328EFD301210846FDF711F8012091E7E9 -:1044E00010B5012004F001FA1020FDF7D5F9254997 -:1044F0000020086010BD234804F04BBA2DE9F041BC -:10450000044600690E46401C206101281FD006F0B9 -:104510003BFA256880462946304606F0ADF9074645 -:10452000414606F0E5F9294606F054F90546606073 -:104530002946304606F0A0F90146384606F0A2F9B1 -:10454000A16806F047F92560E060A0605AE7666060 -:1045500000202660F9E700007C010020000C00200C -:1045600074000020A80000206C040020140C0140FE -:10457000FC000020A086010086000020700A0020B8 -:1045800080C3C901B000002070B5FB4CFB4EC1B226 -:104590000546A170306805F009F8E079A178484037 -:1045A000E071C5F30721A170306804F0FFFFE079E6 -:1045B000A1784840E071C5F30741A170306804F06C -:1045C000F5FFE079A1784840E071290EA1703068CC -:1045D00004F0ECFFE079A1784840E07170BD70B55F -:1045E000E54CE64EC1B20546E170306804F0DEFFEE -:1045F000E079E1784840E071C5F30721E170306867 -:1046000004F0D4FFE079E1784840E07170BD10B566 -:104610000446DA482146006804F0C8FFD648C1794C -:104620006140C17110BDD44AD548117A405C491C23 -:104630001172704700B5FFF7F6FF0346FFF7F3FF6F -:1046400003EB002080B200BD10B5FFF7F3FF044676 -:10465000FFF7F0FF04EB004010BD70B504460D46B7 -:104660002420FFF7D4FF4D20FFF7D1FF0CB121200C -:1046700000E03E20FFF7CBFFBF4C0020E071284652 -:10468000FFF7C5FF607ABDE87040C0E70146002033 -:10469000E3E701460120E0E7B748C079B7E770B526 -:1046A00004460D460846FFF7F1FF03E014F8010B3E -:1046B000FFF7ADFF2800A5F10105EDB2F6D170BD01 -:1046C00010B5044603E000BFFFF7A1FF641C20788B -:1046D0000028F9D110BD2DE9F05FDFF89CB2DFF8BA -:1046E000989201274FF0000A0BF10C0B00251AE0FD -:1046F000A3481438405D00EB40010BEB8108D8F86B -:10470000040006F03AF806460FB1B2440AE000246D -:1047100006E000BFD8F80400005DFFF778FF641CD6 -:10472000B442F7DB6D1C99F800008542E0DB002FF6 -:1047300005D00AF0FF00FFF7A9FF0027D6E7BDE884 -:10474000F09F70B50246032300218E4803F0D4FC8D -:104750008A49FF2208608A481421143805F0C7FFEF -:10476000874D0020143D012428700220FDF78CF8AD -:1047700020B1012068700220A87003240420FDF7F6 -:1047800083F850B103202855641C4FF40050FDF706 -:1047900090F810B104202855641C0220FDF774F82D -:1047A00018B90820FDF770F840B105202855641CA1 -:1047B00006202855641C07202855641C2020FDF77E -:1047C00078F810B108202855641C4FF48070FDF76C -:1047D00070F828B10A202855641C0B202855641C49 -:1047E00069484079082801D00E2802D10C202855AC -:1047F000641C0D202855641C0420FDF75AF810B1E4 -:1048000011202855641C132028555B48641C047033 -:1048100070BD2DE9F05F584EDFF864B14FF000082D -:10482000717A594D594C5A4FC1464FF0010AABF1BC -:10483000140B782978D011DC3046A1F1640100789E -:1048400014293BD2DFE801F0FCFBFAF9F8F7F6F5A2 -:10485000F4F3F2F1F0EFEEEDECEBEAE94C48CF299E -:10486000407871D014DCCA295FD008DCA0296CD054 -:10487000A4296BD0C82927D0C9291FD138E0CB295A -:1048800065D0CC2971D0CD2970D0CE2916D17BE34B -:10489000D4296CD00ADCD0296AD04FF00008D12985 -:1048A00067D0D22966D0D32908D1DFE0EF2918D00C -:1048B000F02960D0FA2979D0FE2978D00020FFF7BE -:1048C000E8FEBDE8F05FE7E60024324DFFF7B2FEF8 -:1048D00025F81400641C082CF8D30020FFF7D6FE3E -:1048E000EFE7FFF7A7FE6085FFF7A4FE2085F4E75A -:1048F000FFF799FEF872FFF796FE27490870FFF759 -:10490000A3FE264C2060FFF79FFE6060FFF792FE3B -:1049100023490880FFF78EFE22490880224801784B -:1049200041F002010170D8E761E10023FFF77BFE4F -:10493000E5186870FFF777FEE872FFF774FE5B1CFE -:1049400068750A2BF2D3C8E749E04BE35CE3002526 -:104950005F4606E0FFF76EFE795D6D1C04EB4101DA -:10496000C88730788542F5D3B7E721E005E358E101 -:10497000FDE2C9E26BE02BE3B4010020DC0800207B -:10498000880C0020003801406C040020E80700205B -:10499000700A0020800A0020D30000204C01002073 -:1049A000760100207801002064010020F1E2F2E2AB -:1049B000FFF739FE04F81F0FFFF735FE6070FFF7B1 -:1049C00032FE2071FFF72FFE6071FFF72CFEA07101 -:1049D000FFF729FEA070FFF726FEE0707DE7FFF7E6 -:1049E00029FEFFF727FEE93525F8190CFFF72CFE05 -:1049F000FFF720FEA4F8AE00FFF71CFEFFF724FE31 -:104A0000FFF718FE00EB80004000E084FFF70BFE8C -:104A10006877FFF708FEE87713E0D2E150E2B3E1F0 -:104A2000CCE10CE2DAE1B6E19CE183E174E16AE118 -:104A300051E13EE120E111E10BE1D5E0A1E028E008 -:104A400018E0FFF7F0FDA877FFF7EDFD45E7002838 -:104A50008AD1FFF7E8FD85F87803022801D985F8A7 -:104A6000788300210020FCF74AFD36E7FFF7E2FDDE -:104A7000F94987E20720FFF709FEE620FFF7C7FDA7 -:104A80006879FFF7C4FD0020FFF7C1FD4FF000403B -:104A9000B7E20B20FFF7FAFDF048008800B2FFF7FD -:104AA0009EFD02F0AEFE00B2FFF799FD0220FCF77A -:104AB000EBFE04460420FCF7E7FE44EA400408202D -:104AC000FCF7E2FE44EA80042020FCF7DDFE44EA25 -:104AD000C0041020FCF7D8FE44EA0010FFF77FFD69 -:104AE000F9783A79490041EA8201BA79002041EA2D -:104AF000C2017A79367841EA42117A7AD44641EA9B -:104B00008211D74AD37941EAC311137A41EA0321CA -:104B1000537A41EA4321FB7941EA83213B7A41EA16 -:104B2000C321BB7A41EA0331537B41EA4331937B92 -:104B300041EA8331137C41EA0341137941EA0311CD -:104B4000537C41EA4341937CD27C41EA834141EA70 -:104B5000C24479785F460C43002208E0BB5C0CFA43 -:104B600003F3234202D00CFA02F10843521CB24272 -:104B7000F4D3FFF709FD95F8780300BFFFF747FD71 -:104B80009FE61220FFF782FDB648B74D4FF00004B4 -:104B90000088B0F5806F0BD935F91400C11700EB10 -:104BA0005170C010FFF71BFD641C032CF4D306E00A -:104BB00035F91400FFF713FD641C032CF8D3AB4D3B -:104BC000002400BF35F91400FFF709FD641C032C15 -:104BD000F8D3A74D002400BF35F91400FFF7FFFC00 -:104BE000641C032CF8D36CE61021A24833E0382073 -:104BF000FFF74CFD5FF0000504EBC50636F96C0FBE -:104C0000FFF7EDFCB6F90200FFF7E9FCB6F9040086 -:104C1000FFF7E5FCB079FFF7FAFC6D1C082DEBD32C -:104C20004FE60020FFF732FD5FF00005FFF702FDC1 -:104C300004EBC50626F86C0FFFF7FCFC7080FFF74D -:104C4000F9FCB080FFF7EFFC6D1CB071082DEDD3BF -:104C500037E610218848FFF722FD32E61020FFF7E3 -:104C600015FD864D002400BF35F91400FFF7B7FC91 -:104C7000641C082CF8D324E61020FFF707FDF87A0F -:104C8000FFF7C5FC7E480078FFF7C1FC7D4C20682B -:104C9000FFF77AFC6068FFF777FC7B48008800B27A -:104CA000FFF79DFC7948008800B2FFF798FC784830 -:104CB0003DE00520FFF7EAFC7648008800B2FFF7E8 -:104CC0008EFC7548B0F90000FFF789FC7348007846 -:104CD00000F0010052E70820FFF7D8FC704D0024D7 -:104CE00035F91400FFF77BFC641C022CF8D36D48E7 -:104CF000B0F90000FFF773FC6B48B0F9000000BF8B -:104D0000FFF76DFCDDE50620FFF7C0FC6748006893 -:104D1000FFF73AFC66480AE00520FFF7B7FC654854 -:104D20000078FFF774FC0020FFF759FC6248008808 -:104D300000B2E5E70720FFF7A9FC14F81F0FFFF703 -:104D400066FC6078FFF763FC2079FFF760FC607910 -:104D5000FFF75DFCA079FFF75AFCA078FFF757FC3E -:104D6000E0780BE71E20FFF791FC002566197078AC -:104D7000FFF74DFCF07AFFF74AFC707DFFF747FC28 -:104D80006D1C0A2DF2D39CE52F20FFF77FFC4B48CA -:104D9000FFF796FC95E54006000EFFF777FC00252F -:104DA0005F4607E0785D04EB4000B0F93E00FFF796 -:104DB00016FC6D1C30788542F4D382E5FFF78BFC3E -:104DC0007FE5FFF763FC00245D4603E0285DFFF705 -:104DD0001EFC641C30788442F8D372E51620FFF77D -:104DE00055FC0020FFF7FBFB35F9D00FFFF7F7FB71 -:104DF000B5F90200FFF7F3FBB5F90400FFF7EFFB8D -:104E0000B4F9AE00FFF7EBFB0020FFF7E8FB002052 -:104E1000FFF7BAFBB4F926000A2190FBF1F000B2CB -:104E2000FFF7DDFB95F83600FFF7F1FB95F838004A -:104E3000FFF7EDFB95F83700FFF7E9FB62E008208C -:104E4000FFF724FC0024601CC0B2FFF7E0FB641CE9 -:104E5000082CF8D335E50000B2010020D400002072 -:104E6000C60A002082010020800000206800002087 -:104E700086000020B6000020F0080020800A0020F4 -:104E8000D30000204C010020760100207801002092 -:104E900066010020720100207401002064010020DE -:104EA00034000020B0010020E60000205C0000205B -:104EB0002C000020D2000020EA000020E8CD0008ED -:104EC000FFF7B1FB04461220FFF7E0FB14B1102CF2 -:104ED00002D004E0954800E09548D0E900892046DA -:104EE000FFF795FB4046FFF74FFB4846FFF74CFBAB -:104EF00090480068FFF748FB0020FFF770FB002098 -:104F0000FFF76DFB002039E6FFF78DFB8446FFF7C6 -:104F10009BFB0546FFF798FB0646FFF795FB04460B -:104F2000FFF788FBFFF786FBFFF77DFBBCF1000F67 -:104F300011D0BCF1100F7FF4DAAC7D49C1E9005605 -:104F40000CB17C4804607C4A0220091D107078482E -:104F500001F01DF8C1E47548002CC0E9005687F83F -:104F6000078087F80CA0F5D072480460B5E40028EB -:104F7000F0D10120FCF779FCAFE40028EAD16F49B9 -:104F80004FF4C8700880A8E40028E3D187F80EA089 -:104F9000A3E4012166E50820FFF778FB68486A4A28 -:104FA0006A4D016867481268B1FBF0F1B2FBF0F09E -:104FB00000EB4002C2EBC01001EBC000E88000240F -:104FC00035F91400FFF70BFB641C042CF8D378E4CC -:104FD0000420FFF75BFBB4F92A00FFF700FBB4F9EC -:104FE00028008DE60C20FFF751FB59480068FFF7B9 -:104FF000CBFA5748001D0068FFF7C6FA544808303E -:105000000068FFF7C1FA5CE4524D29780AEB810091 -:10501000C0B2FFF73BFB2878FFF7F9FA00244E4EA9 -:105020004E4FDFF83C81DFF83C910EE0305DFFF73A -:10503000EEFA385DFFF7EBFA18F80400FFF7E7FA2D -:1050400019F80400FFF7E3FA641C28788442EDD3D2 -:1050500037E470B5444C454E0025607810B3BDE888 -:105060007040FBF75DBF306804F0B3FAA17951B12D -:1050700001291CD002291FD0032923D0042929D0BB -:1050800005293FD12CE0242803D00021A17149B982 -:1050900001E00121FAE7232802D0522832D102E0B0 -:1050A000FBF73EFF2EE0012002F071FF2AE04D28C1 -:1050B00004D10220A07125E03C2801D00020F9E7AE -:1050C0000320F7E740281CD8607125712572E07134 -:1050D0000420EFE76072E1794140E1710520E9E7E2 -:1050E00021796279914207D2E2794240E271204A05 -:1050F0005054491C217105E0E179814201D1FFF74B -:1051000088FBA571306804F061FA0028ABD16078A3 -:10511000002809D14FF40060FCF7CBFB002803D036 -:10512000BDE8704001F0E3B970BD000054010020FB -:105130005C01002060000020C90000207E010020EA -:105140000804002040420F000C0400206A010020E7 -:10515000E8F7FF1F7A010020DA0A0020EA0A00209F -:10516000FA0A00200A0B0020B4010020DC0800200D -:10517000880C002044F25061884201DDA0EB410020 -:10518000FE49884202DA48F6A041084470472DE9FA -:10519000F04706465068994614460D46301A05F009 -:1051A000F3FB296805F0A4FB2061A768394605F0E8 -:1051B00063FB8046F24890F8B80005F0EEFBF14939 -:1051C00005F060FB01464FF07E5005F091FB2D6825 -:1051D000294605F0FFFA0146284605F089FB4146BD -:1051E00005F050FB394605F0F5FA2061C4E901608D -:1051F0000146D9F8080005F045FBBDE8F04705F089 -:10520000D1BB2DE9F0411D4614460E4605F0BCFB0E -:10521000696805F037FB316805F034FB216805F05B -:10522000D9FA2060ED680746284605F0BBFB064624 -:1052300085F0004005F0B6FB0546384605F0B2FBA8 -:105240003246294601F082FA05F09EFB2060BDE857 -:10525000F04105F0A7BB70B5CB4CD4E90D01401A65 -:10526000FFF788FF0028D4E90D01A0EB010002DD63 -:10527000FFF780FF02E0FFF77DFF404241F294110B -:10528000884228DAD4E90D01401A05F07DFBBF49B8 -:1052900005F0F8FA0646E06B05F07FFB0546304660 -:1052A00006F0A0FD294605F0EDFA05F07BFB00B203 -:1052B00040F6B8322082514201F048FA616B08444E -:1052C00048F6A0416064884200DD401A002800DAF8 -:1052D0000844606470BD606BFBE72DE9FE4F054636 -:1052E000FFF7B9FFA84842F22831406C081A05F0D0 -:1052F0004BFBA64905F0C6FA044606F08DF901906D -:10530000204606F06FFD00900024284605F03CFB87 -:10531000DFF874A2DFF87892DFF878B20AF1300A89 -:10532000029099481A3030F9140005F02DFB05461B -:105330005DF82410029805F0A5FA294605F09CFABC -:1053400005F030FB00B24FF47A7255462AF814008B -:10535000514201F0FBF98E4900B225F81400603982 -:1053600000F03CFE04EB8406894B8749074609EBB5 -:105370008602904635F91400603B2831FFF741FF63 -:10538000834B81490744424635F91400603B28317C -:10539000FFF7FDFE384400B240F6B8325D462BF808 -:1053A0001400514201F0D2F925F81400784859F858 -:1053B00026102838641C40F82610022CB1DBBDE80A -:1053C000FE8F2DE9F05F704E0024DFF8C491503657 -:1053D000DFF8C0B1A6F1360AA9F128096C4956F8E0 -:1053E0002400803900F0FAFD3AF81410664F401A94 -:1053F0003037674900B227F81400703900F0EEFD2D -:10540000054637F9140056F8241004EB84070844C5 -:105410005F4B5D4909EB87029046703B2831FFF7EF -:10542000F0FE28445A4B58492BF814005D4642467A -:1054300056F82400703B2831FFF7A9FE4FF4FA62BA -:10544000514201F083F93AF914103131622900D840 -:10545000002035F8141040F6B832084400B225F8A0 -:105460001400514201F072F925F81400484859F827 -:105470002710641C40F82710022CAFDBBDE8F09F1A -:1054800070B50546086819681446401A05F07CFA9C -:105490003D49C96A05F0F6F905F084FA01463A4833 -:1054A0005030416029682268891A016070BD2DE979 -:1054B000F0410F46DDE90685116800681E46081AAE -:1054C00005F062FA044630683968401A05F05CFA63 -:1054D0002D49C96A05F0D6F90646014605F0D2F90C -:1054E00007462146084605F0CDF9394605F072F920 -:1054F00006F03EFD284905F0C5F905F06CFAC8F83C -:10550000000084F00040314605F05CFF234905F0BF -:10551000B9F9234905F05EF905F044FA286000283E -:1055200003DA48F6A04108442860BDE8F0812DE97F -:10553000F0471C48144CD0E90056617804F1480942 -:1055400091B34FF07E50A16A05F0D2F98246D9F8A6 -:105550000400301A05F018FAE16A05F093F9514693 -:1055600005F090F905F01EFA07B2D9F8000004F131 -:105570001A08281A05F008FA514616E0B0B9FFFFDC -:10558000E8070020DB0FC940BC020020D3023739F6 -:10559000680D0020280100202C7D8E3FA00CB34513 -:1055A00000A00C464C0100201AE005F06BF905F054 -:1055B000F9F901B204F12400B0F902203A4402EBF7 -:1055C000D27242F34F02A8F80220B0F90030194419 -:1055D00001EBD17141F34F01A8F800104280018026 -:1055E00001206070C9E90056BDE8F08710B5044697 -:1055F00005F0CAF9002C01DC80F00040F74905F005 -:1056000077F9F74905F03EF906F006F8F549C86262 -:1056100010BD10B5F44CE07A002811D0F3480078A2 -:1056200005280DD3F249F34A0868106049685160B3 -:10563000FFF7DCFFF048EB490088888201202073E7 -:1056400010BD2DE9F043E749EC48E74B8E7A012580 -:1056500002790024062E29D004DC022E09D0032E64 -:1056600004D116E0122E33D0302E3DD00020BDE8FC -:10567000F083DF4A466856608668166000694FF41A -:105680007A7290FBF2F0DE4A1080C87AD8724D73BD -:1056900051E04079C00701D0032A03D00020C8722E -:1056A00010B148E00120FAE7DC7244E0C27AD20788 -:1056B00002D0827A032A03D00022CA7212B102E019 -:1056C0000122FAE7DC72C94A90F82F00107032E02C -:1056D000CC4B828A1A80806942F2107290FBF2F001 -:1056E000C94A10808D7326E0C84B102A1A7001D960 -:1056F00010221A700022C64EC64FDFF81CC3DFF816 -:105700001C931D7815E000BF02EB420300EB8303FE -:1057100093F8088006F8028093F8098007F8028061 -:1057200093F80B800CF8028093F80C8009F8028043 -:10573000521CAA42E8DB487B8A7B104097D04C730E -:105740008C73012093E72DE9F041A64900240A4615 -:1057500091F809E092F807C0157A0CEB0003D78A9C -:10576000DEB22246BEF1090F51D2DFE80EF0080585 -:105770000F151C2333434900622803D04A72B52811 -:1057800002D044E0022033E0012031E003224A72DB -:105790000873C87108723AE004224A72CE71721915 -:1057A0000A72887233E005224A72CE7172190A7247 -:1057B000C8822CE006234B72731907EB0020CE71D0 -:1057C00080B20B72C882B0F5007F01D9CA824A72DA -:1057D0000A831CE0CE7172190A720A8BC82A01D2A0 -:1057E000864B9854521C90B20883B8420FD10720C0 -:1057F00048720CE008234B72844508D04A7206E0D8 -:105800004A72854203D1FFF71CFF00B101242046F4 -:105810008BE670B5034600200246054611E02E2CAB -:1058200004D1521C00290FD054181D559C5C00EB6C -:1058300080004000A4F13006092E01D83038204401 -:10584000521C9C5C002CEAD170BD2DE9F041002671 -:10585000804635463746044604F00AFF016800E0FA -:10586000641C2078085C2028FAD0404609E01EB16C -:1058700006EB86025206160E10F8012B303E32441B -:10588000D6B2221A022AF2DC09E01DB105EB85022C -:105890005206150E10F8012B303D2A44D5B2844231 -:1058A000F3D820782E280ED1641C002007EB870245 -:1058B000570022788B5C202B02D1303F1744641CA8 -:1058C000401C0428F2DB56480621454307EBC7007D -:1058D00000EB071005EB8000B0FBF1F051494E439F -:1058E00000EBC61021E62DE9F04700273D4C0546A8 -:1058F000242815D0414E2046F03EC0782C2D13D0E0 -:105900002A2D11D021460D2D497964D00A2D62D05F -:105910000F2802D23554401CE07000295CD0BAE058 -:10592000A770E7702771B6E03754A0784FF00109EF -:1059300028B1A179012921D002294ED0A2E0A77176 -:105940003078472807D17078502804D1B07847289C -:1059500002D0522809D095E0F078472804D1307958 -:10596000412801D184F806908CE0F0784D2804D1CC -:105970003079432801D10220A07183E0DFF87080E4 -:1059800002280CD003280FD0042816D0052819D0DF -:10599000062849D0072850D0092855D072E017486A -:1059A000F038FFF752FF05E0307853286AD1D8F875 -:1059B00000004042C8F8000064E01048F038FFF7EB -:1059C00044FF05E0307857285CD1D8F80400404205 -:1059D000C8F8040056E063E05AE03BE08096184BBC -:1059E00035FA8E3CBC020020700A0020D300002053 -:1059F0004C01002054010020B0010020B80D00200F -:105A00007601002078010020660100207A01002044 -:105A1000DA0A0020EA0A0020FA0A00200A0B002015 -:105A200040420F002D3101003078302801D901208B -:105A300000E00020FE49C87224E00021FD48FFF785 -:105A4000E8FEFD4908701DE00021FA48FFF7E1FE7D -:105A5000FA4916E0072802D008280DD012E00121EB -:105A6000F448FFF7D6FE41F2184148434FF47A71EB -:105A7000B0FBF1F0F24904E00121EE48FFF7C9FE66 -:105A8000F0490880A078401CA070E7702A2D04D04F -:105A90002079684020710020A6E584F80590FAE797 -:105AA0000029F8D0307800F0C7FA0501707800F0CE -:105AB000C3FA28442179C0B288426771EBD1A0793A -:105AC0000128E8D190E52DE9FF5FDF49C0B291F8E8 -:105AD0001C1119B1012904D002297CD1FFF703FF61 -:105AE00001E0FFF730FE002875D0D24C1034A068DA -:105AF000E06002F072F9A0602020FBF7CDFED348F1 -:105B00004FF0000B0178012910D001210170C84825 -:105B1000C17A00295FD0C849097805295BD382463C -:105B2000407830B19AF80C1031B108E080F800B03C -:105B3000EDE78AF80CB002E008B1FFF76AFDC4484F -:105B400005218E460278C44C521CB2FBF1F301FBD6 -:105B50001322C0490270002091F90090BC4954F80A -:105B600020306831BA4D41F82030BC49783593FB7C -:105B7000F1F145F82010BA4D00EB80074D4303EBDF -:105B8000C51342F2107593FBF5F5AEB2B04D40353A -:105B900025F81060A74DC83505EB8707AC4D57F8C1 -:105BA00022C0603555F8208047F82230A8EB0C0C55 -:105BB000634445F8203093FBFEF3A94D6D426943E1 -:105BC00003EBC111A24B7033B9F1010F43F8201060 -:105BD00007D1B61E00E080E0B6F5797F01D844F821 -:105BE0002010401C0228B9DB02F0F7F8984D296A12 -:105BF000401A04F0D2FE9B4904F07AFEA86202F03B -:105C0000ECF82862A86A4FF07E51884200DB084613 -:105C1000A86203A902A8944BCDE900011A1F211D17 -:105C20008D48FFF744FC02986426B0FBF6F08F49DC -:105C30008F4A57460880039890FBF6F010809AF838 -:105C40000C0018B9A1F800B0A2F800B0FFF76FFC83 -:105C5000387A10B9F87900283FD07D49343101F104 -:105C6000080000F11C07CDE900013B1D3A46211D4B -:105C70007948FFF71CFC231D774A391D3846FFF78A -:105C8000FFFB744C94F90000012828D0022824D18D -:105C9000784F0121B7F9BE0000F0ABF9FFF71DFB0B -:105CA00097F8BA00744A18B1686C90FBF6F010804F -:105CB000B7F8B600E96B88420BD2D5E90D01401A5E -:105CC000FFF758FA002800DC404242F21071884287 -:105CD00003DD01202070A88A1080BDE8FF9FFFF738 -:105CE00070FBFAE72DE9F047624C607904F055FE4D -:105CF000DFF88891494604F0FBFD4E4D20352860C1 -:105D0000E07B04F04AFE494604F0F2FD5C4EEE6092 -:105D10006860A07904F041FE5A4F394604F0E8FD6E -:105D200010352860207C04F038FE494604F0E0FD80 -:105D30006860A07E04F031FEDFF82881414604F05F -:105D4000D7FDC5E90206E07904F027FE394604F0E4 -:105D5000CFFD10352860607C04F01FFE494604F03A -:105D6000C7FD6860E07E04F018FE414604F0C0FD07 -:105D7000C5E9020638E42DE9F0412E4C0646103400 -:105D80000027032527704FF48070FBF792FD002851 -:105D900019D0667002F021F8C4E901702A4890F821 -:105DA0001C0100B90125FFF79DFF374906EB4600AE -:105DB0002B4651F820203549354802F09DF93549E8 -:105DC00048600120207023E52DE9F041194C03279C -:105DD00010341D4A60782F4D00EB400192F81C31C1 -:105DE000294E686813B1012B1ED105E056F8211029 -:105DF00003F0F2FB27700BE52378012B4CD056F80B -:105E0000211003F0E9FBDFF88080002608F13C0850 -:105E1000686818F8061003F0C9FB042001F0ECFFD5 -:105E2000761C8C2EF4D3277000206060F0E4000014 -:105E3000700A0020C80C0020D3000020760100204A -:105E400078010020660100206C040020640100201D -:105E5000BC020020C90000204C0100208096980060 -:105E6000D3CEFEFF00007A445801002072010020CA -:105E700074010020E8070020B20100200000C842A1 -:105E80000000FA440000204118CE0008C75A00085C -:105E900000440040DC0800200027904607EB470044 -:105EA00056F82010686803F097FB98F91D0100EB85 -:105EB000400006EB80004168686803F07AFBC82068 -:105EC00001F09AFF7F1C052FE8DB98F81D01607038 -:105ED00002202070A8E710B55E4C207805282AD251 -:105EE000DFE800F02903031C0600BDE810406BE763 -:105EF00060680521401C60606078401CC0B2B0FB47 -:105F0000F1F201FB1200607001F067FF5249A060DE -:105F1000002008705149C87201200BE001F05DFFBC -:105F2000A168401A40F6C411884204D92020FBF72A -:105F3000B8FC0420207010BD2DE9F05FDFF814A13B -:105F40000024474FDFF81C81DFF81C910AF1400A5A -:105F500025460AF1280B00BF27F8145028F81450E2 -:105F600004EB840629F814500AEB860000F06DF863 -:105F70000BEB860000F069F83648903000EB8600A5 -:105F800000F063F8641C022CE6DBBDE8F09F7CB5F2 -:105F9000364C02682260096861600068FFF726FBE2 -:105FA000A4F1240101F10800314ECDE90001231DC7 -:105FB0002246311D3046FFF77AFAA4F15805331D09 -:105FC000686B68643246211D2046FFF759FA686BFA -:105FD000A8632848B0F8BC0068827CBD10B50C46A8 -:105FE00004F0D2FC216804F04DFCBDE8104004F040 -:105FF000D9BC70B51D4C583CE26B21B1B0EB520FCF -:106000000BD3500809E0904200D31046194900B262 -:10601000B1F8BC10814200DB0846B4F9125000B25E -:10602000A84208DD1449A06A04F02CFC04F0BAFC74 -:10603000284400B2608270BD3038C0B2092801D94E -:10604000C01FC0B200F00F00704700210160416026 -:1060500081607047D80C0020D3000020700A002017 -:106060000C0100202C010020280100201403002036 -:106070004C010020E80700200000C842F0B5404A6B -:10608000404C1178E9B192F805C01779032104F169 -:106090001C035E1816F8015CFD4005F00F05072D86 -:1060A00009D213F801E016F8016C06EA0C060EEBB3 -:1060B000062644F82560891CC9B21029E9D30021BD -:1060C0001170314907280ED2937863B151782E4A66 -:1060D000104490F80A0149B154F820004FF4777148 -:1060E00001EB500006E0B1F81401F0BD34F82000D7 -:1060F00000F5777080B2F0BD70B5214C01260546E1 -:10610000A67001F050FEA168421AC4E9020241F2F1 -:1061100088300021824200D9E1701A4AE0781C32AE -:1061200015540F2802D0401CE07070BD174826702F -:10613000018070BD70B504461348114990F81221D2 -:10614000032007252AB1012A08D108714D710120C9 -:1061500003E002220A7148710020487001234FF4C5 -:10616000E1320B490B4801F0C7FF01460A48C16004 -:106170000CB10A492160457470BD01480078704730 -:106180003C030020800E00206C040020D60000207C -:10619000F960000800440040DC0800207D60000831 -:1061A00070B57C4C06460125207880B901F015FEBB -:1061B000A1683231884207D32570012001F027FE03 -:1061C00001F00BFEA06070BD20780028FBD001F02C -:1061D00004FEA16831448842F5D30020207001F00C -:1061E00016FE01F0FAFD6C49A060087808B1401E67 -:1061F0000870657070BDF8B5664D8DF800008DF8BB -:1062000001108DF802208DF80330A8791DF80010D8 -:1062100044292DD04C2929D04D2925D04E292AD0CA -:1062200032240026032806D274B12046FFF7B8FFB7 -:10623000A879032808D301F0D0FDA968001B884283 -:1062400002D95548AE7106706878012801D0002C3B -:1062500009D1A879032801D2401CA8716E702E7054 -:10626000002001F0D4FDF8BD6424DAE7C824D8E7A3 -:106270004FF4FA64D5E70024D3E72DE9F047DFF8BF -:106280001CA10546434C9AF80D004FF00109002669 -:1062900010B184F8029000E0A6704FF40070FBF794 -:1062A00008FB3F4F18B33F493F484FF0020C91F8AD -:1062B000AC30B0F9000003EB830282420FDA97F8AA -:1062C0000180B8F1000F0AD084F8049091F8AD1065 -:1062D000194401EB8101814201DA84F804C0824251 -:1062E00003DA797809B984F804C000B9267120204E -:1062F000FBF7CAFA40B19AF80A1011B99AF80B00E4 -:1063000008B1F87AA8B1E6702079022814D00128E3 -:1063100017D0E078012817D0A078012817D0042DD5 -:1063200019D0022D1ED0012D1ED0607901281ED05B -:1063300022E084F80390E7E74E22442311464C20E4 -:106340000DE04D234C2208E04D234E2201E04D2369 -:106350005322532102E044234D224D215320BDE816 -:10636000F04748E7442305E044234E22F5E77878D8 -:1063700010B14E234D22ECE70748007818B1BDE874 -:10638000F04732200CE72670BDE8F047002001F00E -:106390003EBD00004C030020C8000020C60A0020BB -:1063A000700A0020E8070020D600002010B5D84C65 -:1063B0005E28A26807D05D280CD001461046BDE8D3 -:1063C000104003F0F3B85D21104603F0EFF83E21D2 -:1063D000A068F4E75D21104603F0E8F83D21A068CD -:1063E000EDE72DE9F041132000F04AF9C94C20688F -:1063F000002800DC4042C84D90FBF5F000B200F0F0 -:1064000051F91B2000F03CF92068002800DC4042D4 -:106410000A2690FBF6F042F2107790FBF7F107FBAB -:10642000110000B200F03EF9232000F029F92068A5 -:10643000002801DA532000E04E2000F033F912204A -:1064400000F01EF96068002800DC404290FBF5F087 -:1064500000B200F027F91A2000F012F96068002855 -:1064600000DC404290FBF6F090FBF7F107FB1100D7 -:1064700000B200F017F9222000F002F9606800284D -:1064800001DA572000E04520BDE8F04100F00AB9EC -:1064900010B54FF40040FBF70CFAA04A9C4920B11C -:1064A00092F82901012806D002E0002082F8290193 -:1064B0000868886010BD9A48FBE770B5974890F867 -:1064C000291111B9974A52780AB1012400E0002439 -:1064D000954D2A78944209D039B914B14FF4165029 -:1064E00001E0D0F82001FEF72CF92C7070BD2DE9E9 -:1064F000F0478A4890F8290118B98A48407800285E -:106500007ED08348806803F061F8002878D101F0DC -:1065100064FC854D6968401A7D2871D301F05DFCEB -:1065200068606878814F401CDFF80482DFF80492CD -:106530006870002404F12400C0B200F0A1F838888B -:1065400004F02BFA064638F9140004F01DFA31461F -:1065500004F0CEF9494604F095F904F023FA00B2AC -:1065600000F0A0F8641C032CE4DB00F096F86878D7 -:106570004FF06404800724D1102000F081F86E4EA3 -:10658000306890FBF4F000B200F08CF8212000F0AD -:1065900077F8306890FBF4F104FB110000B200F0D2 -:1065A00081F8142000F06CF86448B0F9000000F0A5 -:1065B00079F81C2000F064F8002000F073F800F077 -:1065C0006CF86878400735D1022000F059F85C4833 -:1065D0004FF00A08B0F9001091FBF8F000B200F09B -:1065E00061F80220FBF765F9E0B100F065F8554865 -:1065F0006E21007848431521B0FBF1F63A2000E007 -:106600003CE000F03DF8B6FBF4F738B200F04AF891 -:106610003B2000F035F804FB1760401DB0FBF8F09C -:1066200000F040F82020FBF72FF908B1FFF7D9FE62 -:1066300000F033F86878282820D10020687001F035 -:10664000CCFB4FF47A71B0FBF1F43C25B4FBF5F6CA -:10665000B6FBF5F005FB1067172000F011F83802C3 -:1066600000B200F01FF8182000F00AF805FB1640F1 -:1066700000F018F8BDE8F04700F00FB8BDE8F0876B -:1066800070B5234C05465E21A06802F08FFF2946B5 -:10669000A068BDE8704002F089BF1D485E21806897 -:1066A00002F084BF10B50446C0B2FFF77FFEC4F30A -:1066B0000720BDE8104079E670B52248224E40F62A -:1066C000340200783178184DB0FBF1F050432A22A3 -:1066D000B0FBF2F06A88B2FBF1F301FB13214FF635 -:1066E000FF7202EA011141EA0024C0F303200443CF -:1066F0000620FFF7C5FF20B2FFF7D4FF6888317886 -:10670000401C80B2B0FBF1F201FB1200688070BD4A -:10671000DC0800204C010020A08601006C04002051 -:10672000D8140020700A00205803002082010020A5 -:106730008000002000007A4420000020B0010020EA -:10674000E8000020D200002068010020884201DA21 -:10675000084670479042FCDD104670472DE9F0472F -:10676000BD49BD48E831B0F9E600B1F90050B1F9D2 -:10677000024010B90DB9002C7ED0B84A002111702A -:1067800004F002F9B64F394604F07CF8DFF8D492F1 -:10679000494604F0ADF88046284604F0F5F839463D -:1067A00004F070F8494604F0A3F80646204604F0C9 -:1067B000EBF8394604F066F8494604F099F80746C4 -:1067C000304604F029FF0446404604F025FF2146E8 -:1067D00004F058F8A44C2060384604F01DFF05462C -:1067E000404605F0FFFA294604F04CF805463846C5 -:1067F00005F0F8FA8246304605F0F4FA8146404644 -:1068000004F00AFF494604F03DF8514604F03AF816 -:10681000294604F031F86060384605F0E3FA054691 -:10682000404605F0DFFA294604F02CF805463846C4 -:1068300004F0F2FE8246304605F0D4FA8146404626 -:1068400004F0EAFE494604F01DF8514604F01AF837 -:10685000294603F0BFFFA060304604F0DDFE054688 -:10686000404605F0BFFA294604F00CF8E0603846CF -:1068700004F0D2FE054600E057E0404604F0CCFEAE -:10688000294603F0FFFF0546384605F0ABFA82467D -:10689000304605F0A7FA8146404605F0A3FA49467E -:1068A00003F0F0FF514603F0EDFF294603F092FF9D -:1068B0002061384605F096FA0546404604F0ACFEE5 -:1068C000294603F0DFFF0546384604F0A5FE824660 -:1068D000304605F087FA8146404605F083FA49467E -:1068E00003F0D0FF514603F0CDFF294603F0C4FF6B -:1068F0006061304605F076FA80F00040A0613846CD -:1069000005F070FA0546304604F086FE294603F08D -:10691000B9FFE061384604F07FFE0546304604F0DA -:106920007BFE294603F0AEFF2062BDE8F0872DE92B -:10693000F0470546B0F90080B0F90260B0F90400F4 -:1069400004F022F8484C8246A16803F09BFF0746FA -:10695000304604F019F88146616803F093FF06465B -:10696000404604F011F88046216803F08BFF314661 -:1069700003F030FF394603F02DFF04F013F82880B0 -:106980005046616903F07EFF07464846216903F0DF -:1069900079FF06464046E16803F074FF314603F094 -:1069A00019FF394603F016FF03F0FCFF68805046DC -:1069B000216A03F067FF07464846E16903F062FF7A -:1069C00006464046A16903F05DFF314603F002FF31 -:1069D000394603F0FFFE03F0E5FFA880A5E7092A8A -:1069E00011D2DFE802F0100509161C21262A2E001C -:1069F00002880A80428803E042880A8002880CE00C -:106A00004A808088888015480078002822D108466E -:106A10008DE7028852420A8042885242F0E742885B -:106A200052420A800288EBE7028852420A8042887A -:106A30000CE042880A80028808E002880A804288C6 -:106A400003E0428852420A80028852424A8080888B -:106A50004042D7E7704700006C040020600300202C -:106A6000DB0F494000003443AC0E00204449084489 -:106A7000444990F80A0151F820004FF4777101EB76 -:106A8000500080B2704710B5044601F08CF93E49C1 -:106A900002464868131A0020B3F57A6F00D948708F -:106AA0004A604A780AB90F2C0AD1087032B1354BC6 -:106AB00020331344182A03F8014C02D0521C4A70A8 -:106AC00010BD304A2032D27D0AB901220A704870C6 -:106AD00010BD10B504462A4800212A4BB0F8140115 -:106AE0004200A2F5F76200BF43F82120491C0829A3 -:106AF000FADB0123254A2649264801F0FDFA014622 -:106B00002548C1600CB1254921600821417410BDA0 -:106B10001D4B10B5187840B11A484FF000022030D4 -:106B2000817DC908C90702D01A70002010BD1C4918 -:106B3000401C0A8030F8011CC1F30A0411490C60A2 -:106B40000488C4F3CA044C600468C4F38A348C60BB -:106B5000B0F80340C4F34A04CC608488C4F30A1438 -:106B60000C614468C4F3CA344C61B0F80740C4F304 -:106B70008A048C6100894009C8611A70012010BD27 -:106B80006C040020D00E002064030020A0860100C9 -:106B9000876A000800440040DC0800206D6A000895 -:106BA000D60000202DE9F0410646007890B008B1EB -:106BB000012500E00025DFF8D880404602F0D0FE35 -:106BC0003448009000243448CDE90104012725B160 -:106BD0000220CDE90304802002E0CDE90374002007 -:106BE00005904FF480700690800007902020089058 -:106BF0000002CDE909046946404602F01EFF01216A -:106C0000404602F044FF8DF830500B948DF83170FF -:106C10004FF46020CDE90D040DB1022000E0012009 -:106C20001C4C8DF83C004C3C0BA9204602F004FEA5 -:106C3000032301220421204602F053FE2DB13178B6 -:106C400003230222204602F04CFE0121204602F0DE -:106C50001CFE0121204602F00EFE204602F01FFE1F -:106C6000204602F021FE0028FAD1204602F023FE41 -:106C7000204602F025FE0028FAD10121204602F02C -:106C800026FE10B0BDE8F081034931F810007047CE -:106C9000080002404C2401406C0300202DE9FF470E -:106CA000DFF86C81814698F80000D0B300273E469B -:106CB0003D463C46641CE4B202AB0822322153201C -:106CC00000F063FD9DF808009DF80910202C00EBF2 -:106CD000012000B207449DF80A009DF80B1000EB5C -:106CE000012000B206449DF80C009DF80D1000EB49 -:106CF000012000B205449DF80F0000F07F0001D292 -:106D00000028D7D197FBF4F0ADF8000096FBF4F023 -:106D1000ADF8020095FBF4F0ADF8040088F80240ED -:106D20001EE0FFE702AB06223221532000F02DFDCA -:106D30009DF808009DF8091000EB0120ADF8000057 -:106D40009DF80A009DF80B1000EB0120ADF8020041 -:106D50009DF80C009DF80D1000EB0120ADF804002B -:106D600098F8012049466846FFF739FEBDE8FF87DD -:106D700070B5274D04464FF0080228784FF02D01DA -:106D800000284FF053000ED000F0F9FC0A22312108 -:106D9000532000F0F4FC0C222C21532000F0EFFCD7 -:106DA0009022382108E000F0EAFC0A223121532029 -:106DB00000F0E5FC0A222C21532000F0E0FC1549EC -:106DC00040F20910002C088000D06C7070BD38B5FE -:106DD000054600208DF800000F480C460F4900685A -:106DE00088420AD06B4601220021532000F0CDFCDE -:106DF00018B19DF80000E52801D0002038BD0449F5 -:106E0000287808700648206006486060012038BD78 -:106E100070030020820100200C040020001BB7003A -:106E2000716D00089D6C000810B54FF48044204639 -:106E300002F08AFE012805D1204602F093FEB949EE -:106E40000120087010BD70B50D46B649B64A064619 -:106E500088885389B2F91440C01A13895843B2F98B -:106E60001230C013DB02044493FBF4F31844D061E6 -:106E700000EB8000082202EB40000411886800F05B -:106E8000D0F806B13060002D00D02C6070BD38B550 -:106E9000A44C207810B96088401C60806B460322A7 -:106EA000F621772000F071FC9DF800009DF801109C -:106EB000000440EA01209DF8021008439A49B1F904 -:106EC0002010C1F10801C840A06038BD96483421A7 -:106ED00090F8200001EB80109249C2B200200870A7 -:106EE000F421772000F04BBC38B58E4C207810B9D7 -:106EF0006088401C60806B460222F621772000F0FB -:106F000044FCBDF8000040BAA08038BD854900208F -:106F10002E220870F421772000F031BC2DE9F043D7 -:106F200004468248824985B00068884203D1002027 -:106F300005B0BDE8F083DFF8EC9199F8010008B1E5 -:106F40000120F5E74FF40055ADF80C5002208DF804 -:106F50000F001020774E8DF80E0003A9304601F087 -:106F600039FF6F00ADF80C7004208DF80E0003A9F6 -:106F7000304601F02FFF35610E21022001F060FF45 -:106F800000208DF8080008208DF809004FF0010856 -:106F9000019747468DF80A8001A802F09FFD28203E -:106FA0008DF810000F208DF811008DF812008DF86B -:106FB000137004A802F00DFC142000F01DFF6B46B6 -:106FC0000122D021772000F0E0FB574F9DF8000010 -:106FD0000321F8753984552801D07561A7E76B4600 -:106FE0000122D121772000F0D0FB9DF8000000F0B5 -:106FF0000F0139760009787600F05CF889F8018095 -:1070000041F27070208046F6781060804A486060D7 -:107010004A48A0604A48E0604A4820614A486061A6 -:107020008EE770B54049CA69B1F90E40A2F57A629F -:1070300002FB02F31D136C43E512B1F90240B1F9F2 -:107040000460544305EBE424B1F9005004EB8505DA -:1070500091F82040A54056437213B1F90C601B1300 -:107060005E4302EB2642921C9210C98802F5004250 -:10707000AD1C5143C90B4CF25032A0EBA500E240CD -:107080005043B0F1004F03D24000B0FBF1F002E0FA -:10709000B0FBF1F040000112494340F6DE325143AB -:1070A0002A4A0914424301EB224101F6CF6100EB69 -:1070B000211070BD00B587B06B461622AA2177203B -:1070C00000F063FBBDF8000041BA17480180BDF82D -:1070D000021049BA4180BDF8041049BA8180BDF858 -:1070E000061049BAC180BDF8081049BA0181BDF83F -:1070F0000A1049BA4181BDF80C1049BA8181BDF826 -:107100000E1049BAC181BDF8101049BA0182BDF80C -:10711000121049BA4182BDF8141049BA818207B0F1 -:1071200000BD0000740300200C0F00200C040020A0 -:10713000001BB700001001400D6F0008E96E000849 -:10714000CD6E00088F6E0008476E000843E3FFFF16 -:1071500038B5044600208DF800006B4601220A2154 -:107160001E2000F012FB18B19DF80000482801D045 -:10717000002038BD0CB18D480470012038BD7FB5AA -:10718000054602AB062203211E2000F0FEFABDF8E0 -:10719000080040BA00B203F0F7FB844C241D2168BC -:1071A00003F070FB03F0FEFBADF80000BDF80A0031 -:1071B00040BA00B203F0E8FBA16803F063FB03F000 -:1071C000F1FBADF80400BDF80C0040BA00B203F0CA -:1071D000DBFB616803F056FB03F0E4FBADF8020053 -:1071E000201F294602786846FFF7F9FB7FBD2DE98D -:1071F000F0476F4800246F49006825468EB02E4640 -:107200004FF0010888420CD14FF48050ADF82800AF -:1072100002208DF82B0004208DF82A000AA9664868 -:1072200008E06649884207D14FF48040ADF8280055 -:107230000AA9634801F0CEFD322000F0DDFD1122E5 -:1072400000211E2000F09BFA602201211E2000F088 -:1072500096FA642000F0D0FD6846FFF790FFDFF853 -:1072600058A1DFF8609100270AF10C0A01220221DF -:107270001E2000F084FA322000F0BEFD6846FFF7C1 -:107280007EFFBDF90210BDF90400BDF900200D44D8 -:1072900014440644814201DA0B4600E0034693425F -:1072A00001DD104602E0814200DA0846484502DC72 -:1072B0004FF0000808E0DAF8001081F01001CAF879 -:1072C00000107F1C0A2FD1DB122200211E2000F0AB -:1072D00056FA0027012202211E2000F050FA322027 -:1072E00000F08AFD6846FFF74AFFBDF90020BDF9AE -:1072F0000210BDF90400A41A6D1A361A814201DA8F -:107300000B4600E00346934201DD104602E0814255 -:1073100000DA0846484502DC4FF0000808E0DAF8D9 -:10732000001081F01001CAF800107F1C0A2FD1DB79 -:10733000204603F029FB244F0146384603F0D8FAD3 -:107340001A4C20F00040241D2060284603F01CFB4E -:107350000146384603F0CCFA20F000406060304629 -:1073600003F012FB0146194803F0C2FA20F0004076 -:10737000A060702200211E2000F001FA20220121CD -:107380001E2000F0FCF9002202211E2000F0F7F977 -:10739000642000F031FDB8F1000F04D14FF07E50B1 -:1073A00020606060A0600EB0BDE8F0878003002020 -:1073B0000C04002000127A00000C0140001BB700F2 -:1073C0000010014000F0FFFF00406F4601C05E4624 -:1073D00030B587B005464FF44060ADF81400022088 -:1073E0008DF817001C208DF8160005A9FB4801F048 -:1073F000F1FCFB4CE56000F007FAE06802F0B8FB36 -:10740000684602F020FC00224FF44071E06802F070 -:1074100050FC0025ADF804504BF6FF70ADF80600A7 -:107420004FF48040ADF80C00EE4800900121E06878 -:1074300002F017FC6946E06802F0ADFB4FF4A06073 -:1074400002F0C2F922208DF810008DF811508DF84D -:10745000125001208DF8130004A802F0BAF921207F -:107460008DF810008DF8115004A802F0B2F907B0A1 -:1074700030BD38B5DA4CE068818A009111F4706F44 -:1074800001D001212170009911F4E06F25D0018B0A -:1074900000224FF4806102F00CFC009880051CD49F -:1074A000E0680188890518D40188C9050CD50188D0 -:1074B000C905FCD4012102F0E8FBE06801888905D8 -:1074C000FCD4FFF785FF08E0012102F0DEFB00227B -:1074D0004FF44071E06802F0ECFBE068818A21F42F -:1074E000706181820020207138BDC2E72DE9F04132 -:1074F000BB4CE068818A4FF00105C9B2CA074FF062 -:10750000000627D0018821F400610180012102F0EA -:10751000C6FBE670607A20B1607860B9A079FF2878 -:1075200009D061790022E06802F0D0FBA079FF2841 -:1075300048D0FF20C9E06570E079022804D1E068F6 -:10754000018841F40061018061790122E06802F064 -:10755000BDFB37E08A074FF4806745D5BFF3508FF6 -:10756000E079012810D1607A70B1607860B10021B3 -:10757000E06802F094FBBFF3508FE068018B0121BB -:1075800002F083FBA57018E0E068008BBFF3508F1A -:10759000E079022808D1607A30B1607820B100210A -:1075A000E06802F07CFB06E0E079032805D1607A10 -:1075B00018B1607808B1002200E001223946E06885 -:1075C00002F077FB94F90310E079401C814209D165 -:1075D0006670A07828B100224FF44071E06802F094 -:1075E00068FB2671BDE8F0814A0753D5A570627A21 -:1075F0007B494978CAB3C9B3E17902291FD900216F -:1076000002F04DFBE06802F05EFB94F90310626942 -:107610005054491CE1700121E06802F036FBA5706E -:10762000E06802F050FB94F9031062695054491C61 -:10763000E17001223946E06802F03BFB25E00121C0 -:1076400002F023FBE06802F03EFB94F9031062694C -:107650005054491CE170E06802F035FB94F90310C6 -:1076600062695054891CE1700FE000E000E009B944 -:10767000217A31B1012102F008FBE078401CE07072 -:1076800003E0012102F0F7FA6570E0680188C9059E -:10769000FCD497E74A061AD502F015FB94F90310BB -:1076A00062695054491C48B2E070E179C01C8142C3 -:1076B00004D100223946E06802F0FBFAE17994F93E -:1076C00003008142E5D100F10100E0707AE709068C -:1076D000DFD594F903104B1C5AB20BD02369595CC7 -:1076E000E27002F0EEFAE07994F9031088423FF478 -:1076F0005AAF67E7E270A17902F0E3FA607A0028F6 -:107700007FF451AFE0790028F1D05BE7EEE6B0E618 -:10771000ECE670B5324C4FEA400047F230556071EC -:10772000A171012020720021617223616361E27105 -:1077300020712170E068818889050ED40188C9050F -:1077400005D401888905FCD4012102F094FA0122B4 -:107750004FF44071E06802F0ACFA207910B16D1E70 -:10776000FBD104E01DB1207880F0010070BD60897C -:10777000401C6081E068FFF72BFE002070BD07B55C -:1077800002AB0122FFF7C5FF0EBD70B5144C4FEAE6 -:10779000400047F230556071A17100202072012134 -:1077A000617263612361E27121712070E0688188F8 -:1077B00089050ED40188C90505D401888905FCD442 -:1077C000012102F058FA01224FF44071E06802F002 -:1077D00070FA207940B16D1EFBD10AE0000C014027 -:1077E00090030020801A06001DB1207880F001006F -:1077F00070BD6089401C6081E068FFF7E9FD0020F2 -:1078000070BD2A48408970472DE9F84F4FF4406712 -:10781000ADF800704FF0020A8DF803A01420DFF8D5 -:1078200090B08DF802006946584601F0D3FA204D19 -:1078300010352F60DFF8789000262C1505F104082C -:1078400009F1080902E00A2000F0CAFAD9F800009C -:107850004005F8D5C8F800400A2000F0C1FA2C60B5 -:107860000A2000F0BDFA761CF6B2082EEED34FF4D3 -:1078700000694646C8F800900A2000F0B1FA34606A -:107880000A2000F0ADFA2C600A2000F0A9FAC5F831 -:107890000090ADF800708DF803A01C208DF8020058 -:1078A0006946584601F096FABDE8F88F900300202B -:1078B000000C014038B504466B4602221B216820AB -:1078C000FFF763FFBDF8000043F2903140BA08446F -:1078D0004FF48C71B0FBF1F02330208038BD1FB520 -:1078E000044602AB06221D216820FFF74EFFBDF8BB -:1078F0000800214640BA02B2D01702EB9070801007 -:10790000ADF80000BDF80A0040BA02B2D01702EB91 -:1079100090708010ADF80200BDF80C0040BA02B2C1 -:10792000D01702EB90708010ADF804002F48427819 -:107930006846FFF754F81FBD70B50446192000F0E3 -:107940005BFA002215216820FFF719FF10B9032008 -:1079500000F0FCFA254D1621287840F01802682026 -:10796000FFF70DFF002217216820FFF708FF012213 -:107970003D216820FFF703FF01223E216820FFF729 -:10798000FEFE002C00D06C7070BD70B504460D4634 -:10799000192000F031FA002215216820FFF7EFFED0 -:1079A00000281CD012482060124860601248A06075 -:1079B0001248E0600D48622D12D004DC0A2D13D06D -:1079C000142D05D10EE0BC2D06D0B5F5807F01D079 -:1079D000032102E0002100E001210170012070BDBF -:1079E0000221FAE70421F8E70521F6E7A8030020C1 -:1079F00039790008DF780008B5780008184492311A -:107A0000FEB5064614460D46684602F039FC0120D4 -:107A1000ADF804000021ADF80050ADF80610ADF847 -:107A20000810ADF802406946304602F079FBFEBD11 -:107A300070B51646D04A02EB0015D04A02EB00148E -:107A40000122206801F003FBD4E90101182200F0B3 -:107A500087F9217B3246206800F03FF9A07B18B1FE -:107A60000121206802F01EFC0121206802F010FCB8 -:107A7000207B30B1042807D008280AD00C2806D172 -:107A80000AE02068343001E0206838302860284659 -:107A900070BD20683C30F9E720684030F6E72DE9FA -:107AA000F0410546B4480F4600EB0516B348B271E5 -:107AB00000EB05142822D4E9010100F051F9217BE3 -:107AC00000222068FFF79CFF01224FF6FF7120463D -:107AD00001F0DAFA3A462946204601F09BFA304690 -:107AE000BDE8F08170B5A648002402894281018179 -:107AF000891A8BB240F68C218B4201D9C47070BDBB -:107B00009F49A3F2EF2540F2DB569E4AC978B54261 -:107B10001BD2082919D2984DE035042925F81130D7 -:107B200007D2C588AB4204D9012305798B402B438A -:107B3000037103790F2B08D10471B2F90030142BB3 -:107B400002DD143B138000E01480491CC1701480D6 -:107B500070BD70B5884A894B02EB001203EB00132D -:107B6000D47918681B7B8CB151811489824D091B13 -:107B700091819479E03525F814100024D4712246BF -:107B80001946FFF73DFF7F48048070BD1181012138 -:107B9000D171BDE870400222194631E72DE9F04766 -:107BA0000446774DE1890020E980A17901B10220E6 -:107BB000617801B1401C7449DFF8D081002651F88A -:107BC00020704FF47A79BA5D02F00F0002F0F001F4 -:107BD000FF2A65D0A2781AB102285ED003285CD0B3 -:107BE000E2783AB1042858D0052856D0062854D057 -:107BF000072852D0E2790AB182424ED011F0300FFC -:107C000002D0227802B90021227932B1A27922B9B8 -:107C1000082801D0092800D1802162792AB1A279EF -:107C20001AB9021F032A00D88021CA0605D50022EE -:107C30005749FFF734FF082008E08A0608D5AA78DC -:107C40005449FFF72CFFA87800F10100A87024E048 -:107C50004A0612D52289B8FBF2F1A28989B202B98B -:107C60004A46FFF7E5FE0146434A2878F03242F8DB -:107C7000201000F1010028700FE009060DD562897F -:107C8000B8FBF2F189B24A46FFF7D2FE0146424AFA -:107C9000687842F82010401C6870761C0E2E92DB2B -:107CA0000020BDE8F087364A1278904205D23A4A61 -:107CB000303A52F82000006801807047304A52780C -:107CC000904204D2344A52F8200000680180704784 -:107CD0003149403931F8100070477FB506461546E6 -:107CE0000C46684602F0C2FA7020ADF80000012090 -:107CF000ADF802000020ADF804000220ADF8080045 -:107D0000C001ADF80650ADF80C0074B1042C15D0CC -:107D1000082C1CD00C2C07D16946304602F04CF9D7 -:107D20000821304602F0E7FA7FBD6946304602F08E -:107D300098F80821304602F0C8FA7FBD69463046FF -:107D400002F0C4F80821304602F0C5FA7FBD69464A -:107D5000304602F0F7F80821304602F0C6FA7FBD3F -:107D600008B5ADF800108DF8022002218DF803103F -:107D7000694601F02FF808BD300F002054CF0008ED -:107D8000AA030020D600002018CF000840420F00B0 -:107D9000E57A0008537B00085010002080484168B5 -:107DA000491C4160704710B57D484FF0E0234168A1 -:107DB0009A694468A142FAD10368006803EB43045E -:107DC000C4EBC313C2EBC302B2FBF0F001EB410200 -:107DD000C2EBC11100EBC10010BD71484068704793 -:107DE00030B50546FFF7DFFF4FEA0004FFF7DBFF82 -:107DF000001BA842FAD330BD30B504464FF47A7563 -:107E000002E02846FFF7ECFF641EFAD230BD644959 -:107E1000896808474FF4805108B1624801E0614821 -:107E2000001F016070474FF4805110B15D48001F82 -:107E300000E05C48016070472DE9F04F8DB01822DA -:107E40005949684602F041FC032701F016FC012164 -:107E5000564801F0A1FF012144F61D2001F093FFD7 -:107E60000121084601F086FF01F0B1FF4FF6FF70D7 -:107E7000ADF818004B484FF0000A8DF81AA006A97B -:107E8000143800F0A7FF06A9494800F0A3FF06A98F -:107E9000484800F09FFF4848416841F00071416048 -:107EA000464DDFF81C813E4E2968414501D14548C9 -:107EB00000E04548B0600020FFF7A9FF3C490820DA -:107EC0001031086010200860A946002483466D46E2 -:107ED000D9F80010414506D105EBC4008179142979 -:107EE00001D180F806B005EBC401091D55F8340036 -:107EF00000F070FF641CBC42EAD307A801F0F4FE56 -:107F000032490798B0FBF1F0306031484FF47A7194 -:107F10000068B0FBF1F0B0F1807F0CD220F07F411F -:107F20004FF0E020491E41612A4AF0211170C0F84B -:107F300018A0072101612848FFF74AFA00F0C9FF9D -:107F40006420FFF759FF0DB0BDE8F08F184A1021EB -:107F5000143211600821121F11600446151F40F2EF -:107F6000DB104443286880F010002860286880F007 -:107F700008002860A01EFFF73FFF0120FFF747FF22 -:107F80001920FFF739FF0020FFF741FFEAE710B1A2 -:107F90001349124808600F491248173908607047A2 -:107FA000B80300201408014028CF00080700400053 -:107FB000000C014000100140000001400C040020B2 -:107FC000001BB700277E0008157E000840420F0006 -:107FD0000804002023ED00E000580040EFBEADDEB5 -:107FE000F04F00200400FA057CB5FA4C0D46FA4922 -:107FF0002160A060A4F53070606100F58070A06120 -:108000004FF48070E0602061F4482063F348012160 -:1080100014386063880301F0B6FE02208DF8030077 -:108020000002ADF8000018208DF80200EC4EA80701 -:1080300003D56946304600F0CDFE4FF48060ADF8C0 -:10804000000048208DF80200E80703D0694630465A -:1080500000F0C0FE0E208DF8040001208DF8050010 -:108060008DF806008DF8070001A801F0B2FB20464C -:108070007CBD2DE9FC41D74C0D464C34D6492160DE -:10808000A0608020E06040202061A4F586706061DF -:108090008030A061D3480121A064480401F07CFE37 -:1080A00002268DF803600420ADF8000018208DF83A -:1080B0000200CB4FA80703D56946384600F08AFE78 -:1080C0000820ADF8000048208DF80200E80703D032 -:1080D0006946384600F07EFE26208DF80400012017 -:1080E0008DF805008DF806608DF8070001A801F0F5 -:1080F00070FB2046BDE8FC812DE9F0438946064629 -:10810000B9490024B7488FB01D4617468E4204D1A6 -:1081100019461046FFF768FF05E0864204D119466C -:108120001046FFF7A6FF04464FF00008C4F8208071 -:10813000C4F81C80C4F82880C4F82C90C4F82480AB -:10814000A6642571A760ADF83080ADF834800B9738 -:10815000ADF83280ADF83880ADF83680E80702D04F -:108160000420ADF83600A80705D5BDF8360040F06C -:108170000800ADF836000BA9304602F0E3F8012103 -:10818000304602F037F9684601F074FC301D00906B -:108190004FF48050CDE909088020CDF81080CDE95A -:1081A00005084746CDF81C80E80723D0206BD8B1DE -:1081B000E068CDE902702020089060690190206B92 -:1081C00001F0CEFB6946206B01F037FC0121206BEA -:1081D00001F05DFC01224021304602F02DF9206BB8 -:1081E00001F06AFC206405E0012240F2255130468E -:1081F00002F00AF9A80724D5606BE0B1206903906A -:10820000102008970290606B01F0AAFB6946606B32 -:1082100001F013FC01220221606B01F043FC0021FC -:10822000606B01F047FC606B4760012280213046A3 -:1082300002F002F905E0012240F22771304602F017 -:10824000E3F80FB02046BDE8F0837FB50446002078 -:10825000ADF80400ADF808000091ADF80600ADF8E7 -:108260000C00ADF80A0020790D46C00702D00420AA -:10827000ADF80A002079800705D5BDF80A0040F066 -:108280000800ADF80A006946A06C02F05BF8A56032 -:108290007FBD826A81691144426BD160D0E90921B6 -:1082A00000238A4205D9511A426B5160416A8162AA -:1082B00004E00269511A426B5160836280F84430D5 -:1082C000406B012101F0E3BB016B11B14968006C07 -:1082D00001E01C3003C8814201D00120704700201A -:1082E0007047416B11B190F844007047243003C8C7 -:1082F000814201D1012070470020704710B501462E -:10830000036BC268406943B10B6CD21A805C5B1E80 -:108310000B6401D1CA680A6410BD0B6AC05C5B1CA7 -:10832000B3FBF2F402FB14320A6210BD436A8269A5 -:10833000D154416A0269491CB1FBF2F302FB1311EB -:108340004162416B19B10968C90706D1A1E7806C88 -:10835000012240F2277102F057B8704710B51D4C4A -:108360004FF4005001F0ABFB0021606B01F08FFB7C -:10837000D4E90901884203D02046BDE8104088E7CF -:10838000012084F8440010BD1249886C028812064E -:108390000ED5D1E909329A420BD08B699A5C828062 -:1083A000886A0A69401CB0FBF2F302FB1300886282 -:1083B0007047002240F2277102F026B870B5054CD4 -:1083C0004C34A06C0588A9061CD58088E16A69B187 -:1083D000884717E03013002040CF000858000240C3 -:1083E000000801400044004000380140E269616932 -:1083F0008854E069E16800F10100B0FBF1F201FB93 -:108400001200E06128060FD5D4E9091088420CD08B -:10841000A169085CA16C8880A06A2169401CB0FB3E -:10842000F1F201FB1200A06270BDA06CBDE87040CB -:10843000002240F2277101F0E7BF0000FEB52C4C8E -:108440000125207878B1012823D0022820D164208A -:108450008DF8000027488DF8015000264078E0B3E1 -:108460008DF802503CE07A208DF8000022486B46DF -:108470000222B0F90000FF21C0F1B40000EBD0707F -:10848000C0F347008DF801006D20FFF742F9257019 -:10849000FEBD1A4E79208DF80000B6F900000A25BD -:1084A00090FBF5F05A30B4220021FEF74FF98DF819 -:1084B0000100B6F90200B42290FBF5F05A30002119 -:1084C000FEF744F98DF802006B460322FF216D2070 -:1084D000FFF71FF902202070FEBDFFE78DF8026054 -:1084E0006B460322FF216D20FFF713F92670F3E797 -:1084F000C4030020700A0020B001002034000020D6 -:108500001FB5044602AB062243216820FFF73DF960 -:10851000BDF80800214640BA02B2D01702EB9070B5 -:108520008010ADF80000BDF80A0040BA02B2D017C2 -:1085300002EB90708010ADF80200BDF80C0040BA5C -:1085400002B2D01702EB90708010ADF804007C48A6 -:1085500042786846FEF743FA1FBD38B504464FF42B -:108560000050ADF8000002208DF8030004208DF8C3 -:108570000200744874490068884202D16946734811 -:1085800004E07349884203D16946724800F022FC36 -:1085900080226B216820FFF7F2F80520FFF72CFC02 -:1085A000002219216820FFF7EAF803226B216820D6 -:1085B000FFF7E5F8022237216820FFF7E0F8604D69 -:1085C0001A2168202A78FFF7DAF818221B21682080 -:1085D000FFF7D5F810221C216820FFF7D0F8002CF7 -:1085E00000D06C7038BD1FB5044602AB06223B219B -:1085F0006820FFF7CAF8BDF80800214640BAADF878 -:108600000000BDF80A0040BAADF80200BDF80C0049 -:1086100040BAADF804004A4882786846FEF7DFF9B0 -:108620001FBD47494C4ACB7813B14FF4FF6301E0BB -:108630004FF480531380002800D0887070472DE9D4 -:10864000FE4F8146984692460D462320FFF7D4FB05 -:108650006B46012275216820FFF797F8002804D0A7 -:108660009DF80000682802D00020BDE8FE8F062299 -:1086700001AB11466820FFF788F89DF809009DF8C6 -:108680000710C007400F01F0010140EA41009DF8CA -:1086900005102B4C01F0010108434FF001064FF08B -:1086A000000704D0012833D002280DD02CE06B46FF -:1086B00001220C216820FFF768F89DF8000010F0F7 -:1086C0000F0021D0042823D0E7702449C9F80010F6 -:1086D00023492448C9F804102860234868602348C7 -:1086E000E860B8F1000F02D0E17888F80010504639 -:1086F000BAF1620F19D00DDC05281ED00A281AD055 -:10870000BAF1140F0BD114E00520FFF71FFCDCE7D2 -:10871000E670DAE7BC2806D0BAF5807F01D00320E6 -:1087200004E0277003E0267001E0022020700120A1 -:108730009BE70420FAE70520F8E70620F6E70000AB -:10874000C50300200C04002000127A00000C014038 -:10875000001BB700001001408201002023860008A2 -:10876000E78500085B8500080185000819449231FF -:108770001FB5044602AB062201211C20FFF705F8B5 -:10878000BDF80800214640BA40F38D02D01702EB35 -:1087900090708010ADF80000BDF80A0040BA40F3B8 -:1087A0008D02D01702EB90708010ADF80200BDF87A -:1087B0000C0040BA40F38D02D01702EB907080108D -:1087C000ADF80400334802786846FEF708F91FBD8B -:1087D00038B504462020ADF8000002208DF80300D3 -:1087E00004208DF8020069462B4800F0F3FA0022BD -:1087F0002A211C20FEF7C3FF02220E211C20FEF7B7 -:10880000BEFF03220F211C20FEF7B9FF12222B21ED -:108810001C20FEF7B4FF02222C211C20FEF7AFFF24 -:1088200001222D211C20FEF7AAFF00222E211C2050 -:10883000FEF7A5FF05222A211C20FEF7A0FF1749FD -:108840004FF48070002C088001D01248047038BDAD -:1088500038B5044600208DF8000011481149006821 -:1088600088420CD06B4601220D211C20FEF78DFFA3 -:1088700028B19DF800002A2803D01A2801D0002032 -:1088800038BD0949216009496160024948700120E9 -:1088900038BD0000C903002000080140820100200B -:1088A0000C040020001BB700D18700087187000866 -:1088B000434810B50068434CA188084203D0FFF735 -:1088C00072FAA0600AE0FFF76EFAA168884205D943 -:1088D000401A3B2190FBF1F061690860E068BDE857 -:1088E000104001F03FB9E3E7E2E7FEB50125354C62 -:1088F000022110B1012810D109E04FF4807060808E -:108900004000A080E06009202070172004E065800E -:10891000A180E1602570072060706088ADF80000DC -:108920001026274F8DF802608DF80310083F694626 -:10893000384600F04FFAA088ADF8000004208DF80A -:1089400002006946384600F045FA2178012000F01F -:1089500077FAE06801F006F9E068019000208DF8F0 -:1089600008008DF809608DF80A5001A801F0B6F8EA -:1089700094F9010000F01F018D4040094FF0E02103 -:1089800001EB8000C0F80051FFF727FA3C38206166 -:10899000FEBD70B50546FFF720FA0A4C21693C314F -:1089A00088420CD3C4E90405054960880831086091 -:1089B0000B20FFF715FA024960880C31086070BD82 -:1089C000080C0140CC0300201FB5044602AB062270 -:1089D000A8216820FEF7D9FEBDF80800214640BA5C -:1089E00002B2D01702EB90708010ADF80000BDF815 -:1089F0000A0040BA02B2D01702EB90708010ADF8B6 -:108A00000200BDF80C0040BA02B2D01702EB907021 -:108A10008010ADF80400264842786846FDF7DFFF75 -:108A20001FBD70B504466420FFF7E6F9F02223214C -:108A30006820FEF7A4FE10B90320FFF787FA05208F -:108A4000FFF7DAF91A4D2021287840F00F0268204C -:108A5000FEF795FE002C00D06C7070BD38B5044652 -:108A60000D461920FFF7C8F96B4601220F21682037 -:108A7000FEF78BFE9DF80000D32801D0002038BD02 -:108A80000C4820600C4860600C48E0600848362DB7 -:108A900005D04E2D07D05D2D07D0002100E04021EC -:108AA0000170012038BD8021FAE7C021F8E70000FD -:108AB000E4030020238A0008C9890008DDE9A73102 -:108AC0002DE9F04FB74C83468E4660892689010216 -:108AD000B5484FF0000A4068421AA6FB027CA08805 -:108AE0004FEAE2754FEA10414FEA00430AFB02C029 -:108AF00006FB05064FEAD71040EA466013EB000973 -:108B000041EBE611E6886388A6FB02C84FEA5340B2 -:108B10004FEAC3370AFB028306FB05364FEA1C23E4 -:108B200043EA0663FB1840EB2620A689A6FB027CDD -:108B30000AFB02C206FB05244FEAD75242EA44224E -:108B40004FF4FA654FEAE454521944F10004A24686 -:108B5000551B74F1000448DA944D5519A5FB0567BF -:108B60004AF1FF3404FB057705FB047C0525A6FBD1 -:108B700005480CFB0585002706FB07556F104FEADB -:108B8000340CB9EB0C0961EB0701A40844EA8574C5 -:108B90001B1B60EBA500864D551B7AF1FF3424DAD0 -:108BA00040F2DC555619A6FB06474AF1000505FBC5 -:108BB000067706FB05750726A4FB06C805FB068697 -:108BC000002704FB0767B9EB0C0961EB07010B27D2 -:108BD000A4FB07C805FB0785002604FB06546410A8 -:108BE0004FEA3C055B1B60EB04006F4CA56800245A -:108BF000A5FB036704FB037305FB0030740D44EA17 -:108C0000C0244015B4EB090360EB0100410441EAC4 -:108C1000D330BBF1000F01D0CBF80000BEF1000F44 -:108C200001D0CEF80020BDE8F08F10B500F072F84A -:108C30005D49886010BD5C48012200784030C1B2B7 -:108C40007720FEF79CBD10B500F064F856494860E7 -:108C500010BD5548012200785030C1B27720FEF790 -:108C60008EBD2DE9FE4305465248534900688842AF -:108C70000FD04FF40054ADF8004002208DF80300EF -:108C800010204E4E8DF802006946304600F0A2F8E2 -:108C900074610A20FFF7B0F801AB0122A021772010 -:108CA000FEF773FD002823D001221E217720FEF756 -:108CB00066FD4FF42F60FFF793F80024DFF8E4809F -:108CC0002646A02707EB4400C1B202AB0222772060 -:108CD0000296FEF75AFDBDF8080040BA28F81400C5 -:108CE000641C082CEEDB2F4800F026F810B10020A1 -:108CF000BDE8FE8342F210702880688030486860CA -:108D00003048A8603048E8603048286130486861E1 -:108D10000120EDE708B56B46032200217720FEF71E -:108D200034FD9DF800009DF80110000440EA012088 -:108D30009DF80210084308BDF0B5C289002102F475 -:108D40007F4502F00F040123C5810A4630F8126006 -:108D500006B10023521C082AF8DB4FF0FF36F3B9A6 -:108D60000022D30722F0010302D0C35C594002E085 -:108D7000C35A81EA132108230F0401D581F4C0519D -:108D800049005B1E002BF7DC521C102AE9DB25434F -:108D9000C581C1F30330844201D10020F0BD3046CB -:108DA000F0BD0000C8130020E803002030F8FFFFEA -:108DB00024FAFFFF0C040020001BB7000010014044 -:108DC000538C0008478C0008378C00082B8C000857 -:108DD000C18A0008F0B500234FF0010C0A880CFA94 -:108DE00003F52A4228D04FEAD30200EB82064FEA6D -:108DF000437491F802E04FEAD46734680EF00F0232 -:108E00005FEACE6E03D591F803E04EEA02024FF01E -:108E10000F0E0EFA07FE24EA0E04BA402243326017 -:108E20008A78282A02D0482A03D005E0C268AA43DB -:108E300001E0C2682A43C2605B1C102BCED3F0BD98 -:108E400010B58A0721F003040649130F21440F22AD -:108E50008C689A4094438C608A68984002438A6088 -:108E600010BD0000000001404FF4805108B14E4891 -:108E700001E04D48001F016070472DE9F0410446B4 -:108E80004A4817460D460088484E0C3E1CE015B176 -:108E900015F8010B00E0FF2080460221304601F06A -:108EA000D9FB0028F9D04146304601F0CFFB012123 -:108EB000304601F0CFFB0028F9D0304601F0C8FB66 -:108EC000C0B20CB104F8010B7F1EE0D20120BDE856 -:108ED000F081F0B501218C0389B0204600F05CFFE1 -:108EE0000121204600F06AFF18208DF816004FF48B -:108EF0002040ADF814002C4E03208DF81700143ECE -:108F000005A93046FFF766FFADF8144004208DF840 -:108F1000160005A93046FFF75DFFA010ADF814005C -:108F200010258DF8165005A93046FFF753FF1F4E48 -:108F30000C3E304601F040FB4FF48270ADF8020069 -:108F400068010024ADF80A000720ADF81000ADF864 -:108F500004400220ADF80E40ADF806000127ADF840 -:108F60000040ADF80870ADF80C506946304601F08D -:108F700047FB0121304601F05FFB0DA00068069021 -:108F80000120FFF771FF042206A907A8FFF775FF6C -:108F90000020FFF769FF9DF81D00EF2802D0204652 -:108FA00009B0F0BD3846FBE7140C01400C38004016 -:108FB0009F0000002DE9F04180461D4616460C46F4 -:108FC000084600F0E7F80746404600F0D8F807EBFF -:108FD0008000C0B2102805D2734901EB00108560F3 -:108FE00004710673BDE8F08151B104290BD0082942 -:108FF0000CD00C290DD101225FF0100101F05DB9F8 -:1090000001220221FAE701220421F7E701220821C7 -:10901000F4E7704770B50D460446017B13460068BF -:109020002A46FFF7C7FF217B2068BDE87040DBE7D9 -:1090300008B58DF8000000208DF8010001208DF8A2 -:1090400002008DF80300684600F0C3FB08BDFEB5C2 -:10905000064614460D46684601F0FFF853486D1E5B -:1090600044435348ADF8045069460068B0FBF4F03F -:10907000401EADF800000020ADF80600ADF802007B -:10908000304600F0B5FEFEBD10B504460068FFF79F -:10909000DEFF0121206801F0FBF8607BBDE8104095 -:1090A000C6E770B50546084600F074F80446284641 -:1090B00000F065F804EB80003B49C0B201EB001002 -:1090C00070BD70B50546022101F028F9012825D0B0 -:1090D0000421284601F022F901282CD00821284635 -:1090E00001F01CF9012833D01021284601F016F9AF -:1090F00001283AD11021284601F01CF90C212846FC -:10910000FFF7CFFF0446284601F005F9A2680146A3 -:10911000002A2AD0207BBDE8704010470221284653 -:1091200001F008F900212846FFF7BBFF0446284656 -:1091300001F0EBF8EAE70421284601F0FBF80421EE -:109140002846FFF7AEFF0446284601F0E0F8DDE7C9 -:109150000821284601F0EEF808212846FFF7A1FF74 -:109160000446284601F0D5F8D0E770BD1148A8E7BD -:109170004FF08040A5E71048A3E71048A1E701465B -:1091800000200F4A01E0401CC0B252F820308B4250 -:10919000F9D17047014600200A4A01E0401CC0B2E4 -:1091A000135C8B42FAD17047D813002040420F0065 -:1091B00008040020002C014000040040000800408A -:1091C000F403002034D00008016B4A689268896873 -:1091D0000A4290F8441204D00020002900D1012056 -:1091E000704701200029FBD100207047D0F83431AE -:1091F00001299A685B6801D021B107E090F8440228 -:1092000030B103E090F84402012801D05A61704760 -:109210001A6170470189406889B2482200F052B94A -:1092200070B5044601EB4100AC491646B1FBF0F0C5 -:1092300081B21D4603222046FFF726FF2A4631460B -:109240002046BDE87040FFF7E5BE0189406889B25D -:10925000102200F037B900B50346032083F83C0222 -:109260001846FFF7B1FF30B1B3F8400293F8391256 -:109270000843A3F8400293F83902400083F839020A -:1092800093F83E02401E10F0FF0083F83E0205D125 -:10929000012083F83802022083F83C0200BDC26836 -:1092A000016A521E914201D3002100E0491C016273 -:1092B000704710B50124034680F83C42FFF784FF55 -:1092C00001280FD1002083F8380283F83A4293F83E -:1092D0004002A3F840021A6A59698854BDE8104058 -:1092E0001846DCE710BD00B50346FFF76DFF01210E -:1092F00001280BD003F23A2300201870D8800420F4 -:1093000098700820187103F8011C00BD83F83C1206 -:1093100000BD90F83C12491E11F0FF0180F83C128C -:1093200008D190F83A1201B1DDE790F8381201B196 -:10933000BFE790E77047D0E90910814201D10120D1 -:1093400070470020704730B5044690F83B02002576 -:10935000F8B194F83D02401E10F0FF0084F83D0281 -:1093600016D1B4F8420200F001014008A4F842020C -:109370002046FFF73BFF032084F83D0294F83F02AC -:10938000401E10F0FF0084F83F0201D184F83B52E8 -:1093900030BD2046FFF7CFFF0028F9D1A16AA269AE -:1093A000481CA062515C2269904200D3A5624FF430 -:1093B000007004F23B2440EA4100A4F807000A20B0 -:1093C00020710120A070207030BD00EBC00101EBC6 -:1093D000801010B5424901EBC0042046FFF7B3FFEF -:1093E0002046BDE8104094E770B53D4C06463D4828 -:1093F000206003202071A66084F844123A4820635C -:109400001030C4F83401002504F134012562616193 -:109410004FF48070E060206104F59C71C4E906158A -:10942000A562656284F83B52012084F83A0284F810 -:10943000385284F83C02206BFFF7ECFED4F834017C -:10944000FFF703FF01212046FFF7D0FE3220FEF791 -:10945000D3FCAFF289032A463146206BBDE8704049 -:10946000DEE6D0E90721914202D14FF000007047BB -:1094700002D9A1EB020003E0C0680844A0EB02009F -:10948000C0B2704700B50346FFF7EBFF00280BD0D2 -:109490005969D869095CDA68521E904201D2401CB1 -:1094A00000E00020D861084600BD436A8269D154BB -:1094B000416A0269491CB1FBF2F302FB13114162DC -:1094C0007047704708B5ADF800108DF802200221F2 -:1094D0008DF803106946FFF77DFC08BDC0C62D005E -:1094E000D814002038D0000894CF00081FB50446D7 -:1094F00002AB062202211820FEF747F99DF808006A -:109500009DF80910800800EB0120ADF800009DF8DF -:109510000A009DF80B10800800EB0120ADF8020056 -:109520009DF80C009DF80D10800800EB0120ADF8AF -:1095300004001A48214602786846FDF750FA1FBD1C -:1095400010B5044608220F211820FEF718F90E2244 -:1095500010211820FEF713F911494FF48050002C08 -:10956000088001D00D48047010BD38B504460020B5 -:109570008DF8000001466B4601221820FEF705F920 -:1095800018B19DF80000FB2801D0002038BD054827 -:10959000206005486060012038BD00000404002000 -:1095A0008201002041950008ED94000802681268CD -:1095B000104770B50C46054603E02A682846126835 -:1095C000904714F8011B0029F7D170BD0168496864 -:1095D00008470168896808470268D268104701682F -:1095E000096908476E48016841F00101016041685E -:1095F0006C4A1140416001686B4A1140016001688A -:1096000021F480210160416821F4FE0141604FF4A2 -:109610001F0181606549C00308607047604A10B54A -:109620005068634B10F00C01624803D0042903D04A -:10963000082903D0036016E0416813E051685368BD -:1096400001F470114FF0020413F4803F04EB9141D8 -:1096500006D053689B03436800D55B084B43E9E79A -:10966000554B594301605168524AC1F30311083206 -:10967000515C0268CA40026010BD3EB400210091F6 -:109680004FF4E01301914648CDE901314B4A04689B -:1096900044F480340460846944F0100484614FF41D -:1096A000A064056805F400350195009D6D1C0095CA -:1096B000019D15B9009DA542F3D10568AD0301D503 -:1096C000022114E0056845F001050560009101687C -:1096D00001F0020101910099491C0091019911B911 -:1096E0000099A142F3D10168890739D5012102917E -:1096F00033490C6844F010040C600C6824F0030437 -:109700000C600C6844F002040C60416841604168E0 -:109710004160416841F480614160116821F070410D -:109720001160244C22496160416821F47C11416040 -:10973000116841F0004111602049091FCA6822F4F4 -:109740000042CA608968090403D51E494FF480139A -:10975000616002990193012908D002290AD100E031 -:10976000FEE7416843F48032114302E0416841F46E -:1097700060114160016841F08071016001688901F8 -:10978000FCD5416821F003014160416841F00201CC -:1097900041604168C1F381010229FAD13EBC3DE735 -:1097A000001002400000FFF8FFFFF6FE08ED00E0A9 -:1097B00000127A000804002000093D000410014056 -:1097C00000200240001BB7001849084318490860F0 -:1097D0007047F0B50F21C478027801234FF0E026DE -:1097E000DCB1134C2468457804F4E064C4F5E0640B -:1097F000240AC4F10407E1408478BD400C402C43A6 -:1098000021010C4C1155007800F01F018B404009DC -:1098100006EB8000C0F80031F0BD02F01F0083406D -:10982000500906EB8000C0F88031F0BD0000FA0559 -:109830000CED00E000E400E010B54268464B0C7906 -:109840001A400B6842EA0422134343608368434A88 -:109850001340D1E9024222434C7943EA44031A43BC -:109860008260C26A097C22F47002491EC9B242EACF -:109870000151C16210BD0029816802D041F001018F -:1098800001E021F00101816070470029816802D068 -:1098900041F4807101E021F480718160704781683A -:1098A00041F008018160704701460020896809077E -:1098B00000D501207047816841F004018160704744 -:1098C000014600208968490700D50120704700291A -:1098D000816802D041F4A00101E021F4A00181607F -:1098E000704770B5072409290AD9C568A1F10A068D -:1098F00006EB4606B440A543B3401D43C56007E0F0 -:10990000056901EB4106B440A543B3401D43056121 -:109910001F23072A09D2446B521E02EB8202934096 -:109920009C4391400C43446370BD0D2A09D2046BE3 -:10993000D21F02EB820293409C4391400C4304638C -:1099400070BDC46A0D3A02EB820293409C43914081 -:109950000C43C46270BD0000FFFEF0FFFDF7F1FF95 -:1099600001684FF6FE721140016000210160416004 -:109970008160C1605749574A0839904203D148680D -:1099800040F00F0006E0534A1432904204D1486878 -:1099900040F0F000486070474E4A2832904203D1B0 -:1099A000486840F47060F5E74A4A3C32904203D17F -:1099B000486840F47040EDE7464A5032904203D187 -:1099C000486840F47020E5E7424A6432904203D18F -:1099D000486840F47000DDE73E4A7832904203D197 -:1099E000486840F07060D5E73B4A111F904203D1B0 -:1099F000086840F00F0006E0374A1432904204D164 -:109A0000086840F0F00008607047334A28329042FE -:109A100003D1086840F47060F5E72F4A3C32904269 -:109A200003D1086840F47040EDE72B4A5032904271 -:109A3000EAD1086840F47020E5E730B5036847F6DE -:109A4000F07293430C6A8A682243D1E904452C439F -:109A500022438C692243CC6922434C6A22438C6A9C -:109A600022431A430260CA6842600A6882604968F9 -:109A7000C16030BD0021016041608160C160016151 -:109A800041618161C1610162416281627047002967 -:109A9000016802D041F0010102E04FF6FE72114070 -:109AA00001607047002A026801D00A4300E08A433F -:109AB0000260704741607047406880B27047C100E3 -:109AC00003D50549091F08607047024908394860F5 -:109AD00070470000080002400804024030B52349E6 -:109AE0008379026853B30B6893430B600A1D1368B4 -:109AF0000468A343136002790A441368046823438B -:109B000013601A4A083213680468A3431360131DD4 -:109B10001C680568AC431C604479102C05D02144B6 -:109B20000A68006802430A6030BD11680468214376 -:109B30001160196800680143196030BD007908445C -:109B400001689143016030BD084A01460020126857 -:109B5000064B0A4014331B680B4202D0002A00D087 -:109B6000012070470149143108607047000401402A -:109B70005A4910B588424FF0010101D14C0501E06E -:109B80004FF48004204600F019F92046BDE810404B -:109B9000002100F013B970B50446808886B00D46E8 -:109BA00020F03F06684600F09FF84D490298B0FB50 -:109BB000F1F189B20E43A680228822F001022280B0 -:109BC000484B2A689A421CD85200B0FBF2F080B28F -:109BD000042800D20420491C2184A083208840F05E -:109BE0000100208021884FF6F5300140A8886A895D -:109BF000104308432080A88929890843208106B0A2 -:109C000070BDEB88A3F53F46FF3E05D102EB420253 -:109C1000B0FBF2F080B208E002EBC20303EB0212E9 -:109C2000B0FBF2F080B240F48040020501D140F078 -:109C300001004FF4967251434FF47A72B1FBF2F186 -:109C400040F40040C7E741F2883101600021818083 -:109C50004BF6FF72C280018141814FF480418181C6 -:109C600070470029018802D041F0010101E021F094 -:109C70000101018070470029018802D041F4807100 -:109C800001E021F48071018070470029018802D031 -:109C900041F4007101E021F4007101807047002956 -:109CA000018802D041F4806101E021F480610180EB -:109CB0007047002A828801D00A4300E08A438280EC -:109CC000704701827047008AC0B2704712B141F0FC -:109CD000010101E001F0FE010182704700540040E3 -:109CE00040420F00A086010030B53C494A683C4B19 -:109CF00012F00C0405D03B4A042C126803D0082C47 -:109D000024D0036000E002604A680F2303EA1212C5 -:109D1000354B9C5C0268E24042604C68072505EACE -:109D200014241C5D22FA04F484604C6805EAD424EF -:109D30001B5DDA40C2604968032303EA91312A4B74 -:109D40001B1F595CB2FBF1F1016130BD4B684C68DF -:109D500003F470134FF0020514F4803F05EB9343B6 -:109D600005D04C68A40300D552085A43CBE71F4ADC -:109D70005343C6E7194A0029516901D0014300E065 -:109D8000814351617047154A0029916901D001430F -:109D900000E0814391617047104A0029D16901D0E8 -:109DA000014300E08143D16170470C4A0029D1682A -:109DB00001D0014300E08143D1607047074A002988 -:109DC000116901D0014300E08143116170470348EC -:109DD000416A41F08071416270470000001002400A -:109DE00000127A000C0400202404002000093D0029 -:109DF00030B50288FD4BFE4C98420DD0A0420BD0EE -:109E0000B0F1804F08D0FB4DA84205D0FA4DA842D2 -:109E100002D0FA4DA84203D122F070054A882A43A5 -:109E2000F74DA84206D0F74DA84203D022F4407562 -:109E3000CA882A4302808A8882850A8802859842D5 -:109E40000AD0A04208D0F04A904205D0EF4A904292 -:109E500002D0EF4A904201D1097A01860121818224 -:109E600030BD30B5028C22F001020284028C83885E -:109E7000048B22F0020224F073050C882C430D8918 -:109E800015434A882A43D94DA8420BD0D84DA84241 -:109E900008D0DD4DA84205D0DC4DA84202D0DC4DF3 -:109EA000A8420DD122F008054A8923F440732A43C1 -:109EB00022F004058A882A438D891D43CB892B43D0 -:109EC00083800483C9888186028430BD70B5028C8A -:109ED00022F010020284028C8488038B0D8823F404 -:109EE000E6464FF6FF7303EA052535430E8922F057 -:109EF000200203EA061616434A8803EA0212324396 -:109F0000BA4EB04202D0BA4EB04215D122F080060D -:109F10004A8924F4406403EA0212324322F04006E4 -:109F20008A8803EA021232438E8903EA86062643B0 -:109F3000CC8903EA8404344384800583C98801877B -:109F4000028470BD70B5028C22F480720284028C8F -:109F50008488838B0D8823F073031D4322F40073E0 -:109F60000E894FF6FF7202EA06261E434B8802EA6C -:109F7000032333439D4EB04202D09D4EB04215D1D3 -:109F800023F400664B8924F4405402EA032333434C -:109F900023F480668B8802EA032333438E8902EA26 -:109FA00006162643CC8902EA041434438480858350 -:109FB000C9888187038470BD70B5028C22F48052F9 -:109FC0000284048C8288838B0D8823F4E6464FF646 -:109FD000FF7303EA0525354324F400560C8903EA90 -:109FE000043434434E8803EA063626437F4CA042AD -:109FF00002D07F4CA04205D122F480448A8903EA32 -:10A000008212224382808583C988A0F8401006848A -:10A0100070BD828B22F440628283828B4FF6FF7385 -:10A0200003EA01210A4382837047828B22F00C02EB -:10A030008283828B0A4382837047028B22F44062C0 -:10A040000283028B4FF6FF7303EA01210A43028366 -:10A050007047F0B5048C24F010040484078B048C42 -:10A060004FF6FF7527F4734705EA03333B4305EAD0 -:10A0700002221A435D4B05EA011698420ED05C4B52 -:10A0800098420BD0B0F1804F08D05A4B984205D07F -:10A09000594B984202D0594B984205D124F02001E7 -:10A0A000314341F0100104E024F0A0030B4343F0DE -:10A0B000100102830184F0BD028B22F00C020283A6 -:10A0C000028B0A430283704770B5048C24F00104AC -:10A0D0000484058B048C4FF6FF7606EA03131343C2 -:10A0E00025F0F305414A2B4390420ED0404A90425E -:10A0F0000BD0B0F1804F08D03E4A904205D03E4A86 -:10A10000904202D03D4A904202D124F0020201E086 -:10A1100024F00A020A4342F001010383018470BD66 -:10A120002DE9F05F0D4604460888304FDFF8C0C0C7 -:10A13000DFF8C0804988AA882B894FF0804960B336 -:10A14000042832D04FF6FF7E082836D0208C9B465C -:10A1500020F480502084A38B268C704600EA0222D3 -:10A1600023F473431A4300EA0B3010430EEA013E16 -:10A17000BC420BD0644509D04C4507D0444505D0BE -:10A180001D4A944202D01D4B9C425AD126F40051E4 -:10A1900041EA0E0141F4805158E02046FFF794FF58 -:10A1A000E9882046BDE8F05F86E72046FFF751FFCB -:10A1B000E9882046BDE8F05F3FE7208C20F48070FE -:10A1C0002084B4F81CA0208C0EEA031313432AF059 -:10A1D000F30A0EEA012B43EA0A03BC4220D064458D -:10A1E0001ED04C451CD044451AD013E0002C014031 -:10A1F000003401400004004000080040000C004012 -:10A2000000100040001400400040014000440140A4 -:10A2100000480140494A944202D0494A944204D13C -:10A2200020F4007040EA0B0002E020F420600843B4 -:10A2300040F48070A3832084E9882046BDE8F05F65 -:10A24000F3E626F402420A4342F48051A0832046FA -:10A250002184E988BDE8F05FDBE64FF6FF7181807D -:10A2600000210180C180418001727047002101807E -:10A2700041808180C180018141818181C18170479C -:10A2800000210180418001228280C18001817047CC -:10A290000029018802D041F0010101E021F0010113 -:10A2A00001807047002930F8441F02D041F400417A -:10A2B00001E0C1F30E0101807047002A828901D0BC -:10A2C0000A4300E08A4382817047028B22F0080231 -:10A2D0000A4302837047028B4FF6FF7322F4006239 -:10A2E00003EA0121114301837047828B22F00802A7 -:10A2F0000A4382837047828B4FF6FF7322F4006219 -:10A3000003EA0121114381837047808E7047008FDB -:10A310007047808F7047B0F84000704702460020B9 -:10A32000138A92890B4202EA010202D0002A00D06D -:10A3300001207047C94301827047000000080040B7 -:10A34000000C004030B50446008A85B00D464CF63E -:10A35000FF710840E98801432182A1894EF6F3107C -:10A360000140A8882A8910436A890A431043A081C2 -:10A37000A08A4FF6FF410840A9890143A18268469F -:10A38000FFF7B2FC3048844201D1039800E0029804 -:10A39000A1890904002900EBC00101EB0010296824 -:10A3A00002DA4FEA410101E04FEA8101B0FBF1F02E -:10A3B0006422B0FBF2F14FEA01114FEA11136FF082 -:10A3C00018056B4300EB8300A3891D044FF0320393 -:10A3D00006D503EBC000B0FBF2F000F0070005E08B -:10A3E00003EB0010B0FBF2F000F00F0008432081F7 -:10A3F00005B030BD0029818902D041F4005101E04F -:10A4000021F400518181704710B5C1F3421301F06E -:10A410001F040121A140012B07D0022B07D01430CB -:10A42000002A026805D00A4304E00C30F8E7103037 -:10A43000F6E78A43026010BD002A828A01D00A43EF -:10A4400000E08A4382827047003801403948384929 -:10A4500041603949416070473648016941F08001E7 -:10A460000161704733490420CA68D20701D0012036 -:10A470007047CA68520701D502207047C968C906EB -:10A48000FBD50320704700B50346FFF7EBFF02E062 -:10A49000FFF7E8FF5B1E012803D0002B00D1052049 -:10A4A00000BD002BF4D1FAE770B505464FF4302615 -:10A4B0003046FFF7E8FF042811D11E4C206940F018 -:10A4C000020020616561206940F040002061304653 -:10A4D000FFF7D9FF216941F6FD721140216170BD7E -:10A4E000F8B5064600204FF4005C00900D4660462B -:10A4F000FFF7C9FF042816D10E4C206940F0010077 -:10A50000206135806046FFF7BEFF41F6FE770428E4 -:10A5100006D1B61C280C009630806046FFF7B3FFCA -:10A52000216939402161F8BD0249C86070470000C7 -:10A530002301674500200240AB89EFCD144815493F -:10A54000026800608A4203D01348804713480047DE -:10A55000134E4FF0090030601248016821F070611D -:10A56000016041020160104C182020600F49104822 -:10A5700008601048D0F800D040680047FEE7FEE7CA -:10A58000FEE7FEE7FEE7FEE7FEE7FEE7FEE7FEE7A3 -:10A59000F04F0020EFBEADDEE5950008ED000008AD -:10A5A0001810024004000140140C0140000C01404E -:10A5B0004434434400F0FF1F2A4910B588420AD1B1 -:10A5C000841401212046FFF7F0FB2046BDE810402F -:10A5D0000021FFF7EABB2449884202D1012104147B -:10A5E00004E0224988420AD10121C4132046FFF722 -:10A5F000E5FB2046BDE810400021FFF7DFBB10BDA2 -:10A6000030B502884C8802F441530A88CD88224331 -:10A610008C882C4322430C8922434C8922438C8909 -:10A620002243CC8922431A430280828B22F40062A7 -:10A630008283098A018230BD0029018802D041F05D -:10A64000400101E021F040010180704781817047A5 -:10A65000808970470246002012890A4200D00120FA -:10A66000704700000030014000380040003C0040CE -:10A670000048704710D20008A0F16101192900D8E4 -:10A68000203870472DE9F05F994615460F468346FE -:10A690004FF0FF36DDF828A011E0A819441009FB9F -:10A6A000047080460146584652469047002802D022 -:10A6B00004DA254603E04046BDE8F09F2646A5EBB8 -:10A6C00006000128E9DC0020F6E740EA01039B07C9 -:10A6D00003D009E008C9121F08C0042AFAD203E017 -:10A6E00011F8013B00F8013B521EF9D27047D2B27B -:10A6F00001E000F8012B491EFBD270470022F6E76B -:10A7000010B513460A4604461946FFF7F0FF2046E7 -:10A7100010BD421E12F8013F002BFBD111F8013B86 -:10A7200002F8013B002BF9D1704730B505462A46A7 -:10A730000B4612F8010B13F8014B08B1A042F8D0F8 -:10A740001CB1002802D06D1CF1E7284630BD10B5C1 -:10A75000044604E00B7800F8013B03B1491C521E8B -:10A76000F8D2204610BDCAB2401E10F8011F8A421E -:10A7700002D00029F9D100207047421C10F8011BBB -:10A780000029FBD1801A70472DE9F04105460020D1 -:10A7900090460E46044600E0641C44450BD2285DFA -:10A7A00000F058F90746305D00F054F9381A02D12C -:10A7B000295D0029F0D1BDE8F08170B5064600F0B2 -:10A7C00059FC046805460A220021304600F048F989 -:10A7D0002C6070BDF0B480EA0102D40F4200B2EBED -:10A7E000410F02D20246084611464A0042D0C30D2C -:10A7F000DDB2C1F3C752AD1A202D35DAC1F316010F -:10A8000041F4000204B15242C5F1200602FA06F1F9 -:10A810002A411044B3EBD05F23D0C4B1012DA0EB8B -:10A82000C35009DCF0BC4FF0004202EAC35200F50D -:10A830000000DBB200F055B9400000F1807000EB81 -:10A84000C350A0F1807040EAD170490009E0490886 -:10A8500041EAC071A0EBC35000F50000400800EBD6 -:10A86000C350F0BC00F034B96142012202EB410157 -:10A87000001BF6E7F0BC704781F00041AAE780F0CA -:10A880000040A7E780EA010210B502F00043400053 -:10A8900026D04A0023D04FEA106101EB1261C0F3C9 -:10A8A0005600C2F3560240F4000042F40002A0FB3E -:10A8B0000220A1F17F014FEA0040140401D000F111 -:10A8C000010050EA124001D44000491EC2B20C06F9 -:10A8D00004EBD010401C4008802A02D003E0002086 -:10A8E00010BD20F00100002900DA0020184310BD3F -:10A8F00030B480EA010202F0004530F0004221F05D -:10A90000004015D0A0B1C0F3C753C2F3C754C2F37F -:10A910001601C0F31600E41A41F4000140F40002ED -:10A920007D34914201D3641C00E04900002C02DA1E -:10A9300030BC002070474FF400000023914201D347 -:10A94000891A034340084FEA4101F7D151B19142BE -:10A9500002D14FF0004105E002D24FF0010101E0C9 -:10A960006FF0010103EBC450284430BC00F0B0B8D4 -:10A97000420005D0C0F3C7525242914201DC002090 -:10A98000704700EBC1507047C10F80EAE070084487 -:10A99000CA079623002100F0A4B89623002211468E -:10A9A00000F09FB800F0004220F00040C10DC0F35D -:10A9B000160040F400007F2901DA00207047962934 -:10A9C00003DCC1F19601C84001E096398840002AB5 -:10A9D000F4D04042704720F00040C10DC0F3160093 -:10A9E00040F400007F2901DA00207047962903DC3B -:10A9F000C1F19601C8407047963988407047000001 -:10AA0000002801DBC0F10040002901DBC1F1004159 -:10AA100081427047002801DBC0F10040002901DBC2 -:10AA2000C1F100418842704730B50B460146002015 -:10AA30002022012409E021FA02F59D4205D303FA00 -:10AA400002F5491B04FA02F52844151EA2F1010281 -:10AA5000F1DC30BDA0F14101192900D82030704748 -:10AA60002DE9F04791460F4680460446002614F82B -:10AA7000015B2DB1FFF7FCFD0068405DC007F6D11A -:10AA80002B2D02D02D2D18D0641E4A463946204663 -:10AA900000F0E1F927B13968A14201D1C7F800807F -:10AAA00071054FF002040BD54042002803DD00F091 -:10AAB000E1FA0460A007BDE8F08746F48066E4E7A9 -:10AAC0000028F8DA00F0D6FA04606FF00040F2E7F0 -:10AAD0000029A8BF7047401C490008BF20F00100B2 -:10AAE000704710B4B0FA80FC00FA0CF050EA010490 -:10AAF00004BF10BC704749B1CCF1200421FA04F422 -:10AB000011FA0CF118BF012121430843A3EB0C01FA -:10AB1000CB1D0106000A002BBEBF002010BC7047F1 -:10AB200000EBC35010440029A4BF10BC7047401C68 -:10AB3000490008BF20F0010010BC7047F0B40028A5 -:10AB400002DCF0BC00207047C0F3C751C0F3160010 -:10AB500040F40000CA0701D14000491E3F2202EB29 -:10AB60006105002211464FF4000626FA01F3134452 -:10AB7000D418844201D8001B1A464000491C1729EA -:10AB8000F3DD5100814202D24FF0FF3100E000219D -:10AB900002EBC550F0BCFFF79BBF10B541000CD0D5 -:10ABA000C0F3C751962908DC7E2909DC06DB410287 -:10ABB00004D000F0004040F07E5010BD002010BDD9 -:10ABC000C1F19604C4F1200100FA01F1E040FFF761 -:10ABD0007FFFA04010BD2DE9FE4F804681EA0300B3 -:10ABE000C00F0C46009021F0004123F00045B8EB67 -:10ABF0000200A94105D24046214690461C460B461C -:10AC0000024623F00040104304D14046214603B0E1 -:10AC1000BDE8F08F270DC7F30A00C3F30A51029075 -:10AC2000401A0190402866DAC3F3130040F4801BF9 -:10AC30000098924620B10023D2EB030A63EB0B0B82 -:10AC400001985946C0F14002504600F0D3F806463C -:10AC50000D4650465946019A00F0EBF810EB0800FB -:10AC60006141002487EA115284EAE7731A433BD01A -:10AC7000009A3AB3019A012A4FEA075210DC001BEE -:10AC800061EB02014FF0004202EA0752CDE90042B7 -:10AC9000001C41F5801132462B4600F038F9B6E72A -:10ACA000001B61EB0201001C41F5801300185B41A1 -:10ACB0002018A2F5001747EB030140EAD570B6193A -:10ACC0006D4111E06D084FEA360645EAC0754FEA5E -:10ACD0000752001B61EB0201001C41F5801149087D -:10ACE0004FEA30000019514132462B4603B0BDE80F -:10ACF000F04F00F0FFB80098012240000023D0EB95 -:10AD0000020263EBE073009821464FEAE074B8EB6F -:10AD1000000061EB0401E9E783F000435BE781F0A9 -:10AD2000004158E710B500F0004420F00040C20D8B -:10AD3000C0F3160040F400007F2A07DA7D2A00DA0B -:10AD40007D22763A00FA02F1002008E0962A09DC1A -:10AD5000A2F1760100FA01F1C2F19602D040FFF7AC -:10AD6000B7FE01E0963A9040002C00D0404210BD62 -:10AD700000F0004230F000400AD0C10D01F56071D2 -:10AD8000C0F3160042EA0151C20840071143704760 -:10AD900000200146704701F0004330B421F000412B -:10ADA00050EA010206D00A0DA2F56072C1F3130148 -:10ADB000002A02DC30BC00207047440F44EAC10482 -:10ADC000C100E01830BC00EBC250FFF781BE0000AC -:10ADD000064C074D06E0E06840F0010394E80700E8 -:10ADE00098471034AC42F6D3F5F784F950DB0008ED -:10ADF00070DB0008202A04DB203A00FA02F1002070 -:10AE000070479140C2F1200320FA03F319439040A8 -:10AE10007047202A04DB203A21FA02F00021704713 -:10AE200021FA02F3D040C2F12002914008431946B2 -:10AE30007047202A06DBCB17203A41FA02F043EA9A -:10AE4000E07306E041FA02F3D040C2F120029140E3 -:10AE50000843194670472DE9F05F824600780027C5 -:10AE600015468B460AF10104B946302801D09DB140 -:10AE700013E014F8010B0127782803D0582801D0DB -:10AE800045B10AE00DB1102D07D10027102514F8A7 -:10AE9000010B02E0082500E00A250026B0460EE07E -:10AEA00005FB080005FB06F1012701EB10461FFA20 -:10AEB00080F8B6F5803F00D3B94614F8010B294657 -:10AEC00000F077F80028EBDABBF1000F05D00FB1E6 -:10AED000641E00E05446CBF80040B9F1000F06D0E4 -:10AEE00000F0C8F802210160C81EBDE8F09F48EAE2 -:10AEF0000640FAE710B5002B08DA401C41F10001CA -:10AF000092185B411A4301D120F0010010BD2DE9D8 -:10AF1000F04D92469B4611B1B1FA81F202E0B0FACF -:10AF200080F220329046FFF765FF04460F4640EA64 -:10AF30000A0041EA0B0153465A46084303D1204612 -:10AF40003946BDE8F08D114653EA010015D0C8F12D -:10AF500040025046FFF75DFF05460E4650465946F3 -:10AF60004246FFF747FF084301D0012000E00020E0 -:10AF7000054346EAE0762C4337430A984FEA4453A8 -:10AF8000A0EB08004FEAD4240A304FF0000244EA54 -:10AF900047544FEAD72502D500200146D1E70105E5 -:10AFA00010196941DDE9084500196941BDE8F04D16 -:10AFB000A0E73A2800D2303820F02002412A01D3FD -:10AFC000A2F13700884201D34FF0FF30704770B5CF -:10AFD00001EB020410F8015B15F0070301D110F832 -:10AFE000013B2A1106D110F8012B03E010F8016B88 -:10AFF00001F8016B5B1EF9D12B0705D40023521E0B -:10B000000FD401F8013BFAE710F8013B02F102020C -:10B01000A1EB030303E013F8015B01F8015B521E8F -:10B02000F9D5A142D6D3002070BD00000FB4054B66 -:10B0300010B503A9044A029800F0E8F810BC5DF8C6 -:10B0400014FB00001523000834040020410008020E -:10B0500018BF04200A0E18BF40F001004FF07F42D5 -:10B0600032EA010108BF40F00200012808BF0520B4 -:10B070007047000000487047380400206FF05E0100 -:10B080000807FFF775BC00002DE9F04D0E46144689 -:10B090004FF07F41B1EB440F9EBF4FF0FF31316065 -:10B0A000BDE8F08D4FF0004040EA0421C4F3C750E2 -:10B0B0007838431100F01F00DFF814C1C0F12002FE -:10B0C000FC445CF823500CEB83038540D3F804C0A8 -:10B0D0002CFA02F72F439D680CFA00FC25FA02F8BF -:10B0E000DB6805FA00F023FA02F240EA02054CEAB6 -:10B0F000080CA7FB0132ACFB01C0A5FB015101EB21 -:10B100000C058D4234BF4FF0010C4FF0000CC118FC -:10B110006144BCF1000F02D0814202D903E08142B8 -:10B1200001D2012000E00020104400F120024FEA8B -:10B1300092188006CA0C40EA42304F03C6F80080DD -:10B14000FFF722FC82463846FFF727FC6FF012011A -:10B15000FFF70EFC07462846FFF71FFC6FF025019E -:10B16000FFF706FC834639465046FFF733FB594646 -:10B17000FFF730FB00F500656FF30B0551462846DD -:10B18000FFF77AFB3946FFF777FB5946FFF777FB66 -:10B190001049FFF777FB07460F492846FFF772FB78 -:10B1A0003946FFF717FB07460C492846FFF76AFBAD -:10B1B0003946FFF70FFB14F0004F08BFBDE8F08DD4 -:10B1C000C8F1805180F000403160BDE8F08D000092 -:10B1D00050210000DB0FC92F22AAFD290000C92F32 -:10B1E00002E008C8121F08C1002AFAD17047704750 -:10B1F000002001E001C1121F002AFBD170470000AE -:10B200000149086070470000380400202DE9FF4F15 -:10B210008BB09A460F4605460026C9E0252837D14F -:10B2200000246D1C6649A04601222B78203B02FABF -:10B2300003F0084202D004436D1CF6E728782E285C -:10B2400017D115F8010F44F004042A280ED06FF02E -:10B250002F022878A0F1300109290AD808EB8801CB -:10B2600002EB410100EB01086D1CF2E757F8048B7B -:10B270006D1C287869283FD006DC002871D063282F -:10B280000CD0642804D137E0732811D075284ED033 -:10B2900052460D99904706F1010688E017F8040B15 -:10B2A0008DF8000000208DF80100E946012003E040 -:10B2B00057F8049B4FF0FF3061074FF0000401D4B2 -:10B2C0000AE0641C44450DDA8442FADB19F80410E4 -:10B2D0000029F6D106E0641C8442FCDB19F8041056 -:10B2E0000029F8D1264404E019F8010B52460D99C3 -:10B2F0009047641EF8D25AE001CF4FF00A0B0028A5 -:10B3000004DAC0F100004FF02D0102E0210504D560 -:10B310002B218DF82410012103E0E10705D0202125 -:10B32000F7E70DF1200908910CE00021F9E701CFC2 -:10B330004FF00A0BF9E75946FFF776FB01F13002AF -:10B3400009F8012D0028F6D1ADEB090000F1200B22 -:10B35000600701D44FF00108D84503DDA8EB0B00CE -:10B3600001E029E000208046002406E009A85246BA -:10B37000005D0D999047761C641C08988442F5DBAB -:10B3800004E0302052460D999047761CB8F1000138 -:10B39000A8F10108F5DC05E019F8010B52460D99FA -:10B3A0009047761CBBF10001ABF1010BF4DC6D1C86 -:10B3B000287800287FF432AF0FB03046BDE8F08F18 -:10B3C000092801002DE9F0474FF0684202EB4003E5 -:10B3D0000C460546B3F1654F3CBF02EB4102B2F1AA -:10B3E000654F3FD34FF07F42B2EB400F28BFB2EB27 -:10B3F000410F03D2BDE8F047FFF7ECB940EA010383 -:10B400005B0008BF44F0FF410AD0B2EB400F08BF19 -:10B41000B2EB410F06D125F0804024F08041054673 -:10B420000C461FE0B2EB400F12BF5FEA410245F04D -:10B43000FF4004F0004115D04FEA410292EA400378 -:10B4400010D4002AB4BF4FF03E564FF09F4631460D -:10B45000FFF718FA054631462046FFF713FA04466F -:10B4600028462146C0F3C753C1F3C7529A1A1B2A74 -:10B4700006DD10F0004F14BF54485548BDE8F08772 -:10B4800012F11A0F17DA11F0004F06D010F0004F2A -:10B490000CBF50485048BDE8F08721462846FFF7CA -:10B4A00027FA0446FFF7D2FD042808BFFFF7E6FDA0 -:10B4B0002046BDE8F0874200B2EB410F25D910F0DD -:10B4C000004F19BF454F464E464F474E224685F026 -:10B4D000004415460A4680F0004110460A1A520000 -:10B4E000B2F1807F3ED248404049DFF804A110F01D -:10B4F000004F18D04FF03F483846FFF7BDF90746D8 -:10B5000051463046FFF7B8F917E011F0004F04BF7D -:10B5100000263746E2D010F0004F19BF354F364EA7 -:10B52000364F374EDAE74FF07C583846FFF752F97E -:10B53000074651463046FFF74DF906464146284634 -:10B54000FFF7A0F92146FFF745F98246214640461C -:10B55000FFF798F92946FFF792F95146FFF7C8F926 -:10B56000044604E021462846FFF7C2F90446014696 -:10B57000FFF788F980462349FFF784F92249FFF74E -:10B5800029F94146FFF77EF92049FFF723F94146A3 -:10B59000FFF778F91E49FFF71DF94146FFF772F9E9 -:10B5A0001C49FFF717F9054641462046FFF76AF99F -:10B5B0002946FFF767F93146FFF70CF92146FFF7F7 -:10B5C00009F93946BDE8F047FFF704B9DB0FC9BFF9 -:10B5D000DB0FC93FDB0F4940DB0F49C00000C9BF8B -:10B5E00022AAFDB90000C93F22AAFD390060ED3E44 -:10B5F000C30ACE37000049C022AA7DBA00004940E4 -:10B6000022AA7D3A2DAD65BD8FB8D53D0FB511BECF -:10B6100061C84C3EA8AAAABE2DE9F84304460246DA -:10B6200050486946B0EB420F09D94FF0E640B0EB05 -:10B63000420F94BF00204FF0FF30009034E04A4B9F -:10B6400022F0004083422BD948492046FFF71AF9DF -:10B65000FFF7A3FA8046FFF7A5F900F0030000907A -:10B6600043494046FFF70EF9054642494046FFF779 -:10B6700009F9064640494046FFF704F907463F49A5 -:10B680004046FFF7FFF82146FFF7F9F83946FFF784 -:10B69000F3F83146FFF7F0F82946FFF7EDF802E03E -:10B6A0001046FFF7F1FC04462546009C002C18DAF2 -:10B6B0006800B0F17F4F3CBF4FF07E50BDE8F8838B -:10B6C00009D14FF00100FFF79BFDBDE8F8430021D1 -:10B6D0000846FFF70DB92846BDE8F8430121FFF7FA -:10B6E00047B9294614F0010F08461CD0FFF7CAF8E5 -:10B6F00006462349FFF7C6F82249FFF7C0F831464E -:10B70000FFF7C0F82049FFF765F83146FFF7BAF8B0 -:10B710002946FFF7B7F82946FFF75CF814F0020F47 -:10B720001CD0BDE8F883FFF7ADF805461749FFF7D1 -:10B73000A9F81749FFF74EF82946FFF7A3F815496E -:10B74000FFF748F82946FFF79DF84FF07E51FFF7C5 -:10B7500041F814F0020F08BFBDE8F88380F0004004 -:10B76000BDE8F883B61F927E490E494683F9223F11 -:10B770001A61342C0020A23300A0FD390000C93F1B -:10B78000336D4C39DA82083CA0AA2ABEB93AB2BA63 -:10B79000CA9F2A3DDDFFFFBE70B50546FFF7C2FA1E -:10B7A00004464000801C0DD12846FFF7F6F90546F7 -:10B7B0002046FFF7E9F82946FFF722F91CBF0120D0 -:10B7C000FFF71EFD204670BD2DE9F04D0F460E46D9 -:10B7D000A0F50001804604464FF0007084B04FF0A1 -:10B7E0007E554FF0000B00EB47004FF07F4AB1F160 -:10B7F000FE4F04D2B0F1804F80F0018141E0B0F102 -:10B80000804F3ED304F1FF40B0F1FE4F1FD200BF86 -:10B8100028F00048C6F3C75044467F2809DB972824 -:10B820007DDAC0F19600012101FA00F0411E31429B -:10B8300009D00120FFF7E4FC04B00021BDE8F04D81 -:10B840000846FFF755B8304218BFFE4DD7E06000FC -:10B8500000281CBF4FF08070B0EB440F0BD91B21A8 -:10B860004046FFF785F8804604466FF01A0B10F04B -:10B87000004FCDD1C3E0A4F50000B0F1FE4F1BD2C4 -:10B88000BDE0B0F1007F11D300213846FFF7B8F8D2 -:10B8900006D16000002818BFBAEB440F71D8B1E799 -:10B8A00006F0004040F0FC563746ABE7B0F1807F31 -:10B8B00038BFA6F50007A5D324F000406FF0FF4283 -:10B8C000E14B8118994210D326F000410A449A4274 -:10B8D0000BD3B4F17E5F18BF5FEA460251D0B0F1DE -:10B8E000FF4F98BFB1F1FF4F06D904B0394640462B -:10B8F000BDE8F04DFEF76EBFB4F1FF4F10D0C6F3B8 -:10B90000C7507F2809DB972812DAC0F19600012181 -:10B9100001FA00F0411E314206D0002009E06EE03D -:10B9200016F0004F5DD127E0304218BF012000D152 -:10B93000022014F5000F13D024B3B4F1004F27D028 -:10B9400014F1814F56D04FF0FE40B0EB440F94BF3E -:10B9500001200020012101EBE671884241D10BE07A -:10B9600016F0004F02D001283FD03AE0012802BF74 -:10B97000B64804B0BDE8F08D4FF0FF4004B0BDE81C -:10B98000F08D37E016F000400ED104B0BDE8F08D28 -:10B99000B6F1FF4F25D016F5000F05D016F0004F79 -:10B9A00018D008B101280AD00220FFF729FC04B002 -:10B9B0000021BDE8F04D4FF07E50FEF799BF022008 -:10B9C000FFF71EFC04B04146BDE8F04D4FF07E503D -:10B9D000FEF78EBF002804BF04B0BDE8F08D01283B -:10B9E00003D004B00020BDE8F08D04B04FF000405B -:10B9F000BDE8F08D04B04FF07E50BDE8F08D944866 -:10BA00002044B0F5005F44D84046FFF7B1F900226A -:10BA1000904BFFF781F9FFF7BEF904466FF0010183 -:10BA2000FEF7A6FF8C49FEF72AFF2146FEF72AFF04 -:10BA30004FF07C51FEF723FF064621460846FEF7ED -:10BA400021FF80F000403146FEF71CFF804683490D -:10BA50002046FEF717FF064681494046FEF712FFD3 -:10BA6000804680492046FEF70DFF4146FEF7B2FEB4 -:10BA7000044601463046FEF7ADFE00F5006B6FF35D -:10BA80000B0B59463046FEF7F7FE2146FEF7A2FEA5 -:10BA9000D4E004F58020C00C00F00F06C0F30710BE -:10BAA0007F38A4EBC05483443046FEF76DFF6FF03F -:10BAB0000301FEF75DFF4FF07E51FEF78BFE01465E -:10BAC00002902046FEF7D8FE019020460299FEF72C -:10BAD00081FE00F500686FF30B0800904146029864 -:10BAE000FEF7CAFE2146FEF775FE02904FF07E502B -:10BAF0000099FEF7FDFE014600900198FEF7C2FE98 -:10BB000000F500646FF30B0420460299FEF7BAFEBD -:10BB1000029041462046FEF7B5FE0199FEF7AFFEC2 -:10BB20000299FEF7A9FE0099FEF7ACFE01460090CF -:10BB30002046FEF74FFE0146FEF7A4FE80464A4926 -:10BB4000FEF7A0FE4449FEF745FE4146FEF79AFE89 -:10BB5000804600212046FEF70BFF01902046009909 -:10BB6000FEF738FE4146FEF78DFE044600210098A0 -:10BB7000FEF7FEFE2146FEF72DFE804601460198A7 -:10BB8000FEF728FE00F500646FF30B0421460198D0 -:10BB9000FEF772FE4146FEF71DFE80463349204601 -:10BBA000FEF770FE009032494046FEF76BFE80467D -:10BBB00030492046FEF766FE4146FEF70BFE804602 -:10BBC00001460098FEF706FE00F500646FF30B04D3 -:10BBD00021460098FEF750FE4146FEF7FBFD8046E9 -:10BBE0002548784450F8361000EBC60001914668AD -:10BBF0004FEA0B10FEF7C8FE009031464046FEF7B4 -:10BC0000E9FD2146FEF7E6FD0199FEF7E3FD009907 -:10BC1000FEF7E0FD00F5006B6FF30B0B5846009943 -:10BC2000FEF72AFE0199FEF727FE2146FEF724FEC5 -:10BC30003146FEF721FE4146FEF721FE804607F51C -:10BC400000641BE0000080BFFFFF3F00000080FF9A -:10BC5000001080C00000F03FABAAAA3E00B0B8417F -:10BC60003BAAB841D49A38BB7EE24C3E00B0384281 -:10BC70003BAA3842D49AB8BB661400006FF30B0499 -:10BC800021463846FEF7F8FD074621465846FEF79E -:10BC9000F9FD064639462046FEF79CFD4146FEF773 -:10BCA000F1FD044639465846FEF7ECFD2146FEF705 -:10BCB00091FD074601463046FEF78CFD00F5006415 -:10BCC0006FF30B0421463046FEF7D6FD3946FEF7EA -:10BCD00081FD804601462046FEF77CFDFFF722F8F5 -:10BCE00007460611FEF750FE2146FEF7C8FD414605 -:10BCF000FEF770FD04463549FEF7C4FD3449FEF7F2 -:10BD000069FD2146FEF7BEFD3249FEF763FD21467F -:10BD1000FEF7B8FD0146304807F00F04784450F8AC -:10BD20002400FEF7AFFD2D49794451F82410FEF7A9 -:10BD300051FD2B49794451F82410FEF74BFD06F1D3 -:10BD40007D01FC2908D23146FEF712FE04B02946D7 -:10BD5000BDE8F04DFEF796BD06F1BF01B1F5BF7F1E -:10BD600016D83146FEF704FE2946FEF78BFD044641 -:10BD7000BAEB440F1AD060000CD02046FFF766F9EA -:10BD8000042808BFFFF77AF9204604B0BDE8F08D1B -:10BD9000002E0BDA0220FFF733FAFFF76FF90146A6 -:10BDA000284604B061F31E00BDE8F08D0220FFF7C5 -:10BDB00027FA61214FF0E040FEF7DAFD0146284600 -:10BDC00004B061F31E00BDE8F08D0000FC5963373C -:10BDD000C9FF753A1872313D2C140000E0130000C1 -:10BDE000941300002DE9F84304460246534869467F -:10BDF000B0EB420F09D94FF0E640B0EB420F94BFD1 -:10BE000000204FF0FF30009034E04D4B22F0004016 -:10BE100083422BD94B492046FEF734FDFEF7BDFE89 -:10BE20008046FEF7BFFD00F0030000904649404603 -:10BE3000FEF728FD054645494046FEF723FD064628 -:10BE400043494046FEF71EFD074642494046FEF77D -:10BE500019FD2146FEF713FD3946FEF70DFD31466B -:10BE6000FEF70AFD2946FEF707FD02E01046FFF740 -:10BE70000BF904462546009C002C1DDA6800B0F141 -:10BE80007F4F09D22846FFF7E1F8042808BFFFF7E3 -:10BE9000F5F82846BDE8F88308D10120FFF7B0F98E -:10BEA000BDE8F84300210846FEF722BD2846BDE85C -:10BEB000F8430121FEF75CBD294614F0010F084646 -:10BEC0001ED0FEF7DFFC05462349FEF7DBFC2349C5 -:10BED000FEF780FC2946FEF7D5FC2149FEF77AFCE7 -:10BEE0002946FEF7CFFC4FF07E51FEF773FC14F0AD -:10BEF000020F08BFBDE8F88380F00040BDE8F8837A -:10BF0000FEF7C0FC06461749FEF7BCFC1649FEF7D3 -:10BF1000B6FC3146FEF7B6FC1449FEF75BFC314631 -:10BF2000FEF7B0FC2946FEF7ADFC2946FEF752FCB1 -:10BF300014F0020FE0D1BDE8F8830000B61F927E36 -:10BF4000490E494683F9223F1A61342C0020A2335E -:10BF500000A0FD390000C93FB93AB2BACA9F2A3DD4 -:10BF6000DDFFFFBE336D4C39DA82083CA0AA2ABE41 -:10BF700070B50546FEF7E2FD044620F00040C0F132 -:10BF8000FF40C00F08D025F00040C0F1FF40C00FB7 -:10BF900004BF0120FFF734F9204670BDCDD2000860 -:10BFA0002AD3000888D30008CAD20008D1D20008DA -:10BFB00069D2000864D20008B8D2000859D200083B -:10BFC00082D300086CD200083BD3000897D3000846 -:10BFD00083D20008FBD2000894D2000852D2000895 -:10BFE000C4D200081DD3000863D3000856D300084C -:10BFF000F4D200080000000009D3000872D3000842 -:10C00000D8D200088ED3000830D3000877D30008B8 -:10C01000A0D20008AFD200086ED300087AD2000880 -:10C0200045D30008A1D300084BD300080DD3000866 -:10C0300077D20008E9D200080000000018D30008F9 -:10C0400073D2000813D3000890D2000845D300082B -:10C050006ED300088CD2000800000000D0D9000880 -:10C060005CD2000843D2000890D900084BD20008E7 -:10C07000F2D4000800000000ABD900083ED9000847 -:10C0800033030008A6D9000838D800088703000841 -:10C090008BD80008ECD80008A906000808D80008CA -:10C0A0001FD700085B070008B9D80008D0D90008DE -:10C0B000D10800081BD500088AD60008F10800083E -:10C0C00003D80008D0D90008BD090008FFD7000830 -:10C0D0000DD80008E909000846D8000809D9000869 -:10C0E000730C0008A3D4000834D20008F70C000831 -:10C0F00090D50008DCD80008AB080008B5D80008C7 -:10C100001CD90008310D0008AED80008A2D80008DC -:10C11000710E00085CD70008D0D900081B0F00087A -:10C12000E9D40008020000007804002000000000AC -:10C1300028230000B5D3000802000000800500207D -:10C14000B0040000A4060000D1D4000802000000E2 -:10C150003C05002000000000D0070000DDD40008EE -:10C16000020000003E05002000000000D007000093 -:10C1700053D4000802000000400500200000000029 -:10C18000D00700003AD60008020000008205002017 -:10C1900000000000D007000043D6000802000000A5 -:10C1A0008405002000000000D007000081D90008AD -:10C1B000020000004205002000000000D00700003F -:10C1C0000BD600080200000044050020000000001B -:10C1D000D0070000BBD30008020000004605002085 -:10C1E00000000000D0070000ABD4000802000000EF -:10C1F0004805002000000000D00700004AD50008D4 -:10C20000020000004A05002032000000F201000098 -:10C210003BD50008020000004C0500203200000061 -:10C22000F201000012D7000800000000860500207F -:10C2300000000000010000006BD5000804000000B1 -:10C240008C050020B004000000C2010067D5000882 -:10C25000040000009005002080250000004B000035 -:10C26000E4D3000800000000940500200000000056 -:10C2700001000000F7D4000800000000880500203D -:10C2800000000000030000007BD500080100000052 -:10C2900089050020FFFFFFFF0400000000D5000813 -:10C2A000000000007E0500200000000002000000E9 -:10C2B0005BD600080000000095050020000000008B -:10C2C0000100000099D40008000000007205002061 -:10C2D0000A000000C800000071D40008000000003F -:10C2E000730500200A000000320000005ED4000840 -:10C2F00000000000740500200A0000003200000069 -:10C300009ED6000800000000750500200000000017 -:10C3100009000000C3D70008000000004E050020FF -:10C320000000000008000000ABD30008000000007F -:10C330004F0500200000000008000000BBD50008E9 -:10C340000000000050050020000000000800000070 -:10C35000E5D6000803000000520500204CFFFFFF57 -:10C3600068010000DAD50008030000005405002031 -:10C370004CFFFFFF6801000065D9000803000000C2 -:10C38000560500204CFFFFFF6801000074D700082D -:10C390000100000058050020FFFFFFFF0100000022 -:10C3A0000ED5000800000000590500200000000024 -:10C3B0000500000000D40008000000006405002013 -:10C3C0000000000080000000B2D50008020000005C -:10C3D0005A05002000000000000100005BD80008A2 -:10C3E000020000005C05002064000000E80300007B -:10C3F0006CD80008020000005E0500206400000008 -:10C40000E803000029D8000800000000E807002029 -:10C4100000000000010000004AD4000800000000F5 -:10C420004E080020000000002000000047D4000853 -:10C43000000000004F080020000000006400000021 -:10C4400070D6000800000000500800200100000025 -:10C45000FA00000084D40008000000005108002009 -:10C46000000000000100000098D700080000000054 -:10C4700052080020000000006400000023D50008DE -:10C48000000000000708002000000000FA00000083 -:10C49000B2D70008000000000808002000000000DB -:10C4A00064000000F8D30008000000000908002024 -:10C4B0000000000064000000BAD70008000000007F -:10C4C0000A08002000000000FA0000002BD5000838 -:10C4D000000000000B0800200000000064000000C5 -:10C4E00088D50008000000000C08002000000000B3 -:10C4F00064000000AFD9000800000000940800208C -:10C5000000000000C8000000BED9000800000000C4 -:10C510009508002000000000C8000000BFD40008FB -:10C520000200000096080020E8030000D007000089 -:10C5300010D40008020000009808002064000000E9 -:10C54000D0070000B0D600080100000087050020D9 -:10C5500000000000040000008AD70008010000006D -:10C560009A080020FFFFFFFF01000000CED700085F -:10C57000010000009B0800200000000001000000F6 -:10C580007ED80008000000009C0800200000000089 -:10C59000FF0000004CD80008000000001408002034 -:10C5A00000000000FA0000002AD40008000000008B -:10C5B00016080020000000006400000039D40008C4 -:10C5C00000000000150800200000000064000000CA -:10C5D0004CD60008000000002408002000000000E5 -:10C5E00001000000F4D5000803000000120800203C -:10C5F000D4FEFFFF2C010000FDD600080300000060 -:10C6000010080020D4FEFFFF2C01000095D5000883 -:10C6100000000000170800200000000030000000AB -:10C62000A3D5000805000000180800200000000045 -:10C6300001000000C1D60008050000001C08002011 -:10C640000000000001000000C4D800080500000040 -:10C6500020080020000000000100000064D700084E -:10C66000030000000E080020B0B9FFFF5046000094 -:10C67000EBD7000800000000ED07002000000000DC -:10C68000C800000026D6000800000000F7070020C0 -:10C6900000000000C8000000D0D300080000000027 -:10C6A0000108002000000000C8000000E0D70008DA -:10C6B00000000000EE07002000000000C80000009D -:10C6C0001BD6000800000000F80700200000000052 -:10C6D000C8000000C5D300080000000002080020C8 -:10C6E00000000000C8000000F5D7000800000000AE -:10C6F000EF07002000000000C800000030D600084E -:10C7000000000000F907002000000000C800000041 -:10C71000DAD3000800000000030800200000000039 -:10C72000C800000094D80008020000009E08002005 -:10C7300000000000D0070000C5D500080000000080 -:10C74000A208002000000000010000004ED70008F1 -:10C7500002000000A40800200A000000D00700002A -:10C7600098D9000802000000A60800200A00000076 -:10C77000D007000059D5000800000000A1080020E3 -:10C78000000000006400000003D600080000000064 -:10C79000EA07002000000000C8000000ECD50008F7 -:10C7A00000000000F407002000000000C8000000A6 -:10C7B000E4D5000800000000FE0700200000000093 -:10C7C000C80000000BD7000800000000E9070020A7 -:10C7D00000000000C8000000F6D6000800000000BD -:10C7E000F307002000000000C8000000EFD600089A -:10C7F00000000000FD07002000000000C80000004D -:10C800007BD9000800000000EB07002000000000BA -:10C81000C800000075D9000800000000F5070020DE -:10C8200000000000C80000006FD9000800000000F0 -:10C83000FF07002000000000C8000000D6D8000854 -:10C8400000000000EC07002000000000C80000000D -:10C85000D0D8000800000000F6070020000000000B -:10C86000C8000000BED8000800000000000800203A -:10C8700000000000C8000000DDD600080000000035 -:10C88000F007002000000000C8000000D5D6000816 -:10C8900000000000FA07002000000000C8000000AF -:10C8A000CDD60008000000000408002000000000B1 -:10C8B000C8000000414552543132333400000000BA -:10C8C0000000803F00000000A8AAAA3F000000006E -:10C8D0000000803F000080BFB0AA2ABF0000000017 -:10C8E0000000803F0000803FB0AA2ABF0000000087 -:10C8F0000000803F000000000000803F000080BF7B -:10C900000000803F000080BF000000000000803F6A -:10C910000000803F0000803F000000000000803FDA -:10C920000000803F00000000000080BF000080BFCA -:10C930000000803F000080BF0000803F000080BFFB -:10C940000000803F000080BF000080BF0000803FEB -:10C950000000803F0000803F0000803F0000803FDB -:10C960000000803F0000803F000080BF000080BFCB -:10C970000000803F0000803F000000000000000039 -:10C980000000803F000080BF0000000000000000A9 -:10C990000000803F00000000A8AAAA3F0000803FDE -:10C9A0000000803F000080BFB0AA2ABF000080BF07 -:10C9B0000000803F0000803FB0AA2ABF000080BF77 -:10C9C0000000803F00000000A8AAAA3F000080BF2E -:10C9D0000000803F000080BFB0AA2ABF0000803F57 -:10C9E0000000803F0000803FB0AA2ABF0000803FC7 -:10C9F0000000803F000080BFD0B35D3F0000803F5B -:10CA00000000803F000080BFD0B35DBF000080BF4A -:10CA10000000803F0000803FD0B35D3F0000803FBA -:10CA20000000803F0000803FD0B35DBF000080BFAA -:10CA30000000803F00000000D0B35DBF0000803FD9 -:10CA40000000803F00000000D0B35D3F000080BFC9 -:10CA50000000803F000000000000803F000080BF19 -:10CA60000000803F000080BF000080BF0000000089 -:10CA70000000803F000000000000803F0000803F79 -:10CA80000000803F0000803F000080BF00000000E9 -:10CA90000000803FD0B35DBF0000803F0000803FBA -:10CAA0000000803FD0B35DBF000080BF0000803F2A -:10CAB0000000803FD0B35D3F0000803F000080BF9A -:10CAC0000000803FD0B35D3F000080BF000080BF0A -:10CAD0000000803FD0B35DBF00000000000080BFB9 -:10CAE0000000803FD0B35D3F000000000000803FA9 -:10CAF0000000803F000080BF0000803F000080BF3A -:10CB00000000803F000080BF000080BF0000803F29 -:10CB10000000803F0000803F0000803F0000803F19 -:10CB20000000803F0000803F000080BF000080BF09 -:10CB30000000803F000080BF0000803F0000803F79 -:10CB40000000803F000080BF000080BF000080BF69 -:10CB50000000803F0000803F0000803F000080BF59 -:10CB60000000803F0000803F000080BF0000803F49 -:10CB70000000803FF704353FF70435BF0000803FD9 -:10CB80000000803FF70435BFF70435BF0000803F49 -:10CB90000000803FF70435BFF704353F0000803FB9 -:10CBA0000000803FF704353FF704353F0000803F29 -:10CBB0000000803F00000000000080BF000080BF38 -:10CBC0000000803F000080BF00000000000080BF28 -:10CBD0000000803F000000000000803F000080BF98 -:10CBE0000000803F0000803F00000000000080BF88 -:10CBF0000000803F0000803F000000BF0000803F39 -:10CC00000000803F000000BF000080BF0000803FA8 -:10CC10000000803F000080BF0000003F0000803F18 -:10CC20000000803F0000003F0000803F0000803F88 -:10CC30000000803F0000003F000080BF000080BF78 -:10CC40000000803F000080BF000000BF000080BFE8 -:10CC50000000803F000000BF0000803F000080BF58 -:10CC60000000803F0000803F0000003F000080BFC8 -:10CC70000000803F000000000000803F0000803F77 -:10CC80000000803F000080BF000080BF0000000067 -:10CC90000000803F000000000000803F000080BFD7 -:10CCA0000000803F0000803F000080BF0000008047 -:10CCB0000000803F000080BF0000803F000080BF78 -:10CCC0000000803F000080BF000080BF0000803F68 -:10CCD0000000803F0000803F0000803F0000803F58 -:10CCE0000000803F0000803F000080BF000080BF48 -:10CCF0000000803F00000000000000000000000075 -:10CD00000000803F00000000000000000000000064 -:10CD10000000803F0000000000000000000080BF15 -:10CD20000000803F00000000000000000000803F85 -:10CD3000000000000000000003010000C0C800085F -:10CD400004000000F0C800080400000030C900081A -:10CD50000201000070C9000800010000000000008E -:10CD60000600000090C9000806000000F0C9000895 -:10CD700001010000000000000400000050CA00088B -:10CD80000600000090CA000808000000F0CA000871 -:10CD90000800000070CB000808000000F0CB00087D -:10CDA0000101000000000000000100000000000080 -:10CDB00000010000000000000400000070CC00082A -:10CDC00006000000B0CC00080001000000000000D8 -:10CDD0000201000010CD0008010100000000000069 -:10CDE0000000000000000000524F4C4C3B504954E2 -:10CDF00043483B5941573B414C543B506F733B5068 -:10CE00006F73523B4E6176523B4C4556454C3B4D01 -:10CE100041473B56454C3B0000C2010017DB000870 -:10CE20003ADB000800E10000F5DA0008E1DA00086A -:10CE300000960000ABDA0008CDDA0008004B0000D5 -:10CE400089DA000875DA000880250000D0D90008CA -:10CE5000D0D90008B56206010300F00500FF19B53E -:10CE60006206010300F00300FD15B5620601030030 -:10CE7000F00100FB11B56206010300F00000FA0F9B -:10CE8000B56206010300F00200FC13B5620601035F -:10CE900000F00400FE17B562060103000102010E56 -:10CEA00047B562060103000103010F49B56206019F -:10CEB0000300010601124FB56206010300011201D1 -:10CEC0001E67B5620616080003070300510800003C -:10CED0008A41B56206080600C80001000100DE6A4A -:10CEE0001048494A4B4C4D44454647FF20212223D8 -:10CEF0002425262748494A4B4C4DFF1048498A8B28 -:10CF00008C8D84858687FF2021222324252627488F -:10CF1000498A8B8C8DFF0000ECCE0008E0CE000823 -:10CF200007CF0008FBCE0008000C014008001002EB -:10CF3000000C014010001002000801400010140213 -:10CF40002D830008C9820008FD8200084B8200087A -:10CF5000E3820008000000400008014001000000DA -:10CF6000001C00000000004000080140020000001A -:10CF7000041C000000000040000801400400000004 -:10CF8000081C0000000000400008014008000000EC -:10CF90000C1C00000004004000080140400000009C -:10CFA000001D000000040040000801408000000057 -:10CFB000041D000000040040000C014001000000BE -:10CFC000081D000000040040000C014002000000A9 -:10CFD0000C1D0000002C0140000801400001000071 -:10CFE000001B0100002C0140000801400008000067 -:10CFF0000C1B010000080040000C01404000000034 -:10D00000001E000000080040000C014080000000ED -:10D01000041E000000080040000C01400001000058 -:10D02000081E000000080040000C01400002000043 -:10D030000C1E00000004080CAB9400086394000868 -:10D0400085940008C394000837930008000000008E -:10D05000000000000000B33FB2BE7D3A00002E4049 -:10D06000DFCF513800007E40BF51FABA00E0A44043 -:10D0700019DAC3BA00E0C840C2ED8AB90040EB40FB -:10D08000CD1F2CBA001006412AFFFABA00C0154184 -:10D09000DFCFD13700D024419A97703A0050334106 -:10D0A00089478E3600404141E75B9D3800B04E41D4 -:10D0B000C00A98B900A05B41558F943A003068418E -:10D0C000DA92C0BA0040744162B3C63A0000803FB1 -:10D0D00000A0853F00908B3F00C0913F0030983FFB -:10D0E00000F09E3F00F0A53F0050AD3F0000B53F6F -:10D0F0000000BD3F0060C53F0020CE3F0040D73F4D -:10D1000000C0E03F00C0EA3F0020F53F0000000003 -:10D110007D36AC397D3C3839EBDCF438320A7E3967 -:10D12000124C26399B6AED39A4EE83397F661E398D -:10D13000F6398A392B426539A48211395B991F3936 -:10D14000C3EECD39DDE7C637A5A22F390000803FF9 -:10D15000C3AA853FC2958B3FD3C3913FF037983F19 -:10D1600032F59E3FD7FEA53F3F58AD3FF304B53F94 -:10D17000A408BD3F2A67C53F8C24CE3FFD44D73F5E -:10D18000DFCCE03FC7C0EA3F7D25F53F004040408F -:10D19000404040404040414141414140404040408A -:10D1A0004040404040404040404040404005020236 -:10D1B00002020202020202020202020202202020F5 -:10D1C0002020202020202002020202020202909051 -:10D1D000909090901010101010101010101010104F -:10D1E00010101010101010100202020202028888A3 -:10D1F00088888888080808080808080808080808AF -:10D200000808080808080808020202024000000096 -:10D210008DD10008000000006E83F9A22915444E4C -:10D22000D15727FCC0DD34F5999562DB4190433C32 -:10D23000AB6351FE696E64657820283020746F20DE -:10D240003229004D50553630353000424D4132388C -:10D250003000565441494C34005934004144584C34 -:10D260003334350048455836005936004F43544F43 -:10D27000583800414343003344004641494C534130 -:10D28000464500414952504C414E45004750532BB2 -:10D290004D41470048454C495F39305F44454700A0 -:10D2A0004759524F5F534D4F4F5448494E47004CDA -:10D2B00045445F52494E4700464C59494E475F57D7 -:10D2C000494E4700484558364800424900545249A3 -:10D2D0000047494D42414C00494E464C494748544D -:10D2E0005F4143435F43414C00534F4654534552C3 -:10D2F00049414C00435553544F4D0048454C495FFC -:10D300003132305F4343504D0050504D0056415232 -:10D31000494F004241524F004759524F0050504D23 -:10D320005F544F5F534552564F0051554144500092 -:10D330004D4F544F525F53544F50004F43544F463C -:10D340004C41545000534F4E415200504F5745529C -:10D350004D455445520053494E474C45434F505458 -:10D360004552004455414C434F505445520047509C -:10D3700053005642415400534552564F5F54494C56 -:10D3800054004845583658005155414458005345BB -:10D390005249414C5258004F43544F464C41545807 -:10D3A0000054454C454D4554525900616C69676EB7 -:10D3B0005F616363006D69647263006E65757472AA -:10D3C000616C3364006770735F706F73725F6400C9 -:10D3D0006770735F706F735F64006770735F6E6117 -:10D3E000765F6400736F667473657269616C5F6900 -:10D3F0006E766572746564007468725F6D6964004E -:10D400006D6F726F6E5F7468726573686F6C6400C5 -:10D410006661696C736166655F6465746563745F9A -:10D420007468726573686F6C640061636378795FB8 -:10D430006465616462616E64006163637A5F646500 -:10D44000616462616E6400796177646561646261E0 -:10D450006E64006D696E636F6D6D616E64007662FF -:10D4600061746D696E63656C6C766F6C7461676511 -:10D4700000766261746D617863656C6C766F6C7454 -:10D4800061676500616C745F686F6C645F6661738F -:10D49000745F6368616E676500766261747363616F -:10D4A0006C650070726F66696C65006465616462CA -:10D4B000616E6433645F7468726F74746C65006667 -:10D4C00061696C736166655F7468726F74746C65B2 -:10D4D000006D696E7468726F74746C65006D61784C -:10D4E0007468726F74746C65006C6F6F7074696DC2 -:10D4F00065004E6F6E65006770735F7479706500CC -:10D5000073657269616C72785F74797065006163CC -:10D51000635F6861726477617265006665617475E6 -:10D5200072650072635F7261746500726F6C6C5F2C -:10D5300070697463685F7261746500736572766F99 -:10D540005F70776D5F72617465006D6F746F725F8D -:10D5500070776D5F72617465006E61765F736C6584 -:10D56000775F7261746500736F6674736572696169 -:10D570006C5F6261756472617465006770735F628D -:10D5800061756472617465007961777261746500B8 -:10D5900073617665006261726F5F7461625F736967 -:10D5A0007A65006261726F5F6E6F6973655F6C7040 -:10D5B00066006779726F5F6C706600616C69676E98 -:10D5C0005F6D6167006E61765F636F6E74726F6C22 -:10D5D000735F68656164696E6700616C69676E5F3F -:10D5E000626F6172645F706974636800695F70691B -:10D5F000746368006163635F7472696D5F706974FE -:10D60000636800705F706974636800646561646278 -:10D61000616E6433645F68696768006770735F7028 -:10D620006F73725F69006770735F706F735F69001B -:10D630006770735F6E61765F69006D696E636865C0 -:10D64000636B006D6178636865636B006163635F42 -:10D65000756E61726D656463616C0074656C656D97 -:10D66000657472795F736F667473657269616C005B -:10D67000616C745F686F6C645F7468726F74746CF3 -:10D68000655F6E65757472616C006C697374206F90 -:10D6900072202D76616C206F722076616C00706F45 -:10D6A0007765725F6164635F6368616E6E656C006D -:10D6B000727373695F6175785F6368616E6E656CC4 -:10D6C000006261726F5F63665F76656C00645F6CB9 -:10D6D0006576656C00695F6C6576656C00705F6C83 -:10D6E0006576656C00616C69676E5F626F6172641C -:10D6F0005F726F6C6C00695F726F6C6C006163636A -:10D700005F7472696D5F726F6C6C00705F726F6CCA -:10D710006C0072657461726465645F61726D007043 -:10D7200072696E7420636F6E666967757261626C90 -:10D73000652073657474696E677320696E2061205B -:10D740007061737461626C6520666F726D006E61EA -:10D75000765F73706565645F6D696E007665727380 -:10D76000696F6E006D61675F6465636C696E61749B -:10D77000696F6E007961775F636F6E74726F6C5F53 -:10D78000646972656374696F6E007961775F64695B -:10D7900072656374696F6E007468726F74746C651F -:10D7A0005F616E676C655F636F7272656374696FEA -:10D7B0006E0072635F6578706F007468725F657881 -:10D7C000706F00616C69676E5F6779726F00747269 -:10D7D000695F756E61726D65645F736572766F0007 -:10D7E0006770735F706F73725F70006770735F70E4 -:10D7F0006F735F70006770735F6E61765F70006D4E -:10D8000061700068656C700064756D70006D6170AA -:10D8100070696E67206F66207263206368616E6E48 -:10D82000656C206F72646572007069645F636F6E0F -:10D8300074726F6C6C65720064657369676E2063E7 -:10D840007573746F6D206D69786572006163635FD5 -:10D850006C70665F666163746F72006779726F5F88 -:10D86000636D70665F666163746F72006779726F73 -:10D870005F636D70666D5F666163746F7200676988 -:10D880006D62616C5F666C6167730064656661758B -:10D890006C7473006770735F77705F726164697531 -:10D8A000730073686F772073797374656D20737478 -:10D8B0006174757300736574006578697400645FE2 -:10D8C000616C74006261726F5F63665F616C7400AB -:10D8D000695F616C7400705F616C74007361766580 -:10D8E00020616E64207265626F6F7400726573658B -:10D8F0007420746F2064656661756C747320616E4A -:10D9000064207265626F6F74006D69786572206E55 -:10D91000616D65206F72206C697374006E616D6556 -:10D920003D76616C7565206F7220626C616E6B2054 -:10D930006F72202A20666F72206C697374006665AE -:10D9400061747572655F6E616D6520617578666C76 -:10D950006167206F7220626C616E6B20666F72204F -:10D960006C69737400616C69676E5F626F61726489 -:10D970005F79617700695F79617700705F796177BE -:10D98000006465616462616E6433645F6C6F77002C -:10D990004D4D4138343578006E61765F7370656542 -:10D9A000645F6D617800636D697800617578006609 -:10D9B00061696C736166655F64656C61790066615D -:10D9C000696C736166655F6F66665F64656C6179DB -:10D9D0000043414D535441423B0043414C49423B7B -:10D9E0000047505320484F4C443B00484541444673 -:10D9F0005245453B00414E474C453B004750532064 -:10DA0000484F4D453B004D41473B0043414D54522B -:10DA100049473B004845414441444A3B0041524D3F -:10DA20003B00484F52495A4F4E3B00564152494FD6 -:10DA30003B004241524F3B004245455045523B005E -:10DA4000474F5645524E4F523B004C4C4947485465 -:10DA5000533B0050415353544852553B004C4544AE -:10DA60004C4F573B004F53442053573B004C4544C9 -:10DA70004D41583B0024504D544B3235312C3139F7 -:10DA80003230302A32320D0A0024505542582C349C -:10DA9000312C312C303030332C303030312C313986 -:10DAA0003230302C302A32330D0A0024505542587F -:10DAB0002C34312C312C303030332C303030312C70 -:10DAC00033383430302C302A32360D0A0024504D91 -:10DAD000544B3235312C33383430302A32370D0A3A -:10DAE0000024504D544B3235312C35373630302AE6 -:10DAF00032430D0A0024505542582C34312C312C1D -:10DB0000303030332C303030312C35373630302C0B -:10DB1000302A32440D0A0024505542582C34312CFE -:10DB2000312C303030332C303030312C31313532F3 -:10DB300030302C302A31450D0A0024504D544B32E0 -:10DB400035312C3131353230302A31460D0A000062 -:10DB500070DB0008000000203C040000CEAF00088D -:10DB600060DC00083C0400202C250000F0B1000817 -:10DB70000196031E7A44CBDC0502A1023701138D06 -:10DB800031025C08021A030936B3914B1DDABC2935 -:10DB90004913F5D92A080832021A22182908297CC3 -:10DBA0001A320C290832041A2B0C290832051A06DD -:10DBB0000C3908311AEB3C290832071A14182908C5 -:10DBC00029591AD118290832091A0B182908320ABA -:10DBD0001AFC182908320B1AE10C2908320C1A53C6 -:10DBE000242908320D1A380C2908320E1A6D0C2916 -:10DBF00008320F1A5D0C290832101A4A0C29083213 -:10DC0000111ADA48290832121A4018290832131A50 -:10DC1000650C2908721402A7FF021001E2045203E6 -:10DC20008B803F0401165A03494AD931E91D12017C -:10DC30000A1C0285C208342C01401A408C1A401973 -:10DC40003A405B14A24A048B127A33380B02030465 -:10DC5000060708090204063B291069148100000028 +:10087000F7DB00220A54B5A00AF07CFDB64D002437 +:1008800004EB840005EB800655F82010B3A00AF0B5 +:1008900071FD00213046FFF719FF6FA000F015FE33 +:1008A000641C622CECD3BDE8FF8710B5AEA000F04D +:1008B0000CFE0121002000F0FAFEAEA000F005FEC3 +:1008C0000A2007F01BFCBDE81040002007F0E1BC47 +:1008D00010B50446ABA000F0F8FDB048002101704F +:1008E000AF480160AF48017001F052FF2046BDE8FB +:1008F0001040DAE72DE9F04706460AF0C0F8054651 +:1009000001F0BCF8DFF8248107464FF0010908F137 +:100910005C0855B12A46A4A130460AF0D9F8C8B1FE +:10092000307800272D2824D026E0A1A000F0CDFDAE +:1009300000244D464FEA080656F8241041B105FA46 +:1009400004F0384202D09FA00AF014FD641CF3E7C3 +:1009500041A01EE09CA000F0B8FD00244FEA08056D +:1009600055F824100029F3D096A00AF003FD641C6A +:10097000F6E70127761C6D1E5FF0000458F824107E +:1009800031B12A4630460AF0A3F830B1641CF5E7CD +:1009900093A0BDE8F04700F098BD09FA04F01FB13C +:1009A00001F067F895A002E000F0E2FE96A000F0EA +:1009B0008CFD58F82410BDE8F04761A00AF0DABCBD +:1009C00010B505F074FC401C04D092A0BDE81040A6 +:1009D00000F07BBD97A0F9E770B500249FA000F060 +:1009E00074FD5D4DB5F1C00504EB440005EB8001DD +:1009F0004A6855F820109FA00AF0BCFC641C102C1B +:100A0000F2D370BD3EB505460AF039F8082809D181 +:100A10000024285D09F0B2FF2855641C082CF8D387 +:100A200000242BE140E100004F4B0900E4C2000824 +:100A3000496E76616C6964206D697865722074799D +:100A400070652E2E2E0D0A004C6F616465642025A2 +:100A500073206D69782E2E2E0D0A00004D6F746F75 +:100A600072206E756D626572206D7573742062659B +:100A7000206265747765656E203120616E64202583 +:100A8000640D0A00526573657474696E6720746F33 +:100A90002064656661756C74732E2E2E0D0A00003D +:100AA0005265626F6F74696E672E2E2E0000000013 +:100AB00025640000202564202564000025730000C3 +:100AC0002025730043757272656E7420436F6E66E5 +:100AD00069673A20436F707920657665727974682A +:100AE000696E672062656C6F7720686572652E2E6F +:100AF0002E0D0A00700400206D6978657220257340 +:100B00000D0A000000008080636D69782025640074 +:100B100020000000636D697820256420302030209B +:100B20003020300D0A000000666561747572652022 +:100B30002D25730D0A0000006665617475726520CD +:100B400025730D0A0000000028CC00086D6170209C +:100B500025730D0A0000000080C40008736574202E +:100B60002573203D20000000536176696E672E2EAC +:100B70002E0000000D0A5265626F6F74696E672E59 +:100B80002E2E00000D0A4C656176696E6720434C7D +:100B900049206D6F64652E2E2E0D0A004004002042 +:100BA00000000020B50100206C6973740000000093 +:100BB000456E61626C65642066656174757265730B +:100BC0003A20000025732000417661696C61626CF7 +:100BD000652066656174757265733A2000000000D7 +:100BE000496E76616C696420666561747572652012 +:100BF0006E616D652E2E2E0D0A0000004469736132 +:100C0000626C656420000000456E61626C65642062 +:100C100000000000456E61626C696E6720475053AA +:100C200020706173737468726F7567682E2E2E0D55 +:100C30000A0000004572726F723A20456E61626C64 +:100C40006520616E6420706C756720696E20475066 +:100C5000532066697273740D0A0000004176616961 +:100C60006C61626C6520636F6D6D616E64733A0DCB +:100C70000A00000025730925730D0A00295DFB4851 +:100C800009F0F3FE28B12819295D401C09F0EDFE9A +:100C900018B1F7A000F019FC3EBD641C082CFFF44D +:100CA000C0AE284600F04EFCF9A000F00EFCEF4B61 +:100CB000FD4A0020694615181C5C95F80A51401C35 +:100CC00008284C55F7D300220A54AFF28C100AF0D2 +:100CD00051FB3EBD2DE9F041804609F0D0FEF24FB8 +:100CE000F24D060012D00246AFF24411404609F020 +:100CF000EFFE90B15FF0000455F82410F1B13246D8 +:100D0000404609F0E5FEF8B1641CF5E7787905EB9B +:100D1000800050F8041CE6A01BE0EAA000F0D5FB20 +:100D20005FF0000455F8241029B1AFF268100AF002 +:100D300021FB641CF6E7AFF2E02001E0AFF21030D7 +:100D4000BDE8F04100F0C1BB601C787155F824107B +:100D5000E1A0BDE8F0410AF00DBB2DE9F04100250E +:100D600007462C462E4609F08AFE18B1AFF26021E4 +:100D7000384610E0DDA02BE016B1012E07D103E0CC +:100D800009F0BFFE054602E009F0BBFE0446761CF2 +:100D9000AFF28421002009F079FE0028ECD10C2D5F +:100DA00005D3BDE8F0410C21DFA00AF0E3BAE84F1B +:100DB000022E07DA37F915202946BDE8F041E5A0F3 +:100DC0000AF0D8BAA4F57A70B0F57A7F04D9E7A012 +:100DD000BDE8F0410AF0CEBA22462946ECA00AF05E +:100DE000C9FA27F81540BDE8F08170B5054609F04D +:100DF00046FEAD4C10F0FF0F0CD0284609F081FEE6 +:100E000002280ED884F878030021084600F04FFC31 +:100E1000A4A0EBE794F87813BDE87040E3A00AF0D3 +:100E2000A9BA70BD2DE9F047824609F028FEE54DCC +:100E3000060029D0012E03D19AF800002A2823D0D9 +:100E4000E1A1504609F0F3FD00286FD0401C044694 +:100E500009F057FE81462046FFF778F980460026C4 +:100E600006EB860705EB870455F8270009F007FE17 +:100E7000024655F82710504609F02AFEF8B1761CB4 +:100E8000622EEDD3D1A04DE0D8A000F01EFB0024CF +:100E900004EB840005EB800755F82010AFF24030DA +:100EA0000AF068FA31463846FFF710FCAFF25840B6 +:100EB00000F00BFB641C622CEAD3BDE8F08706EB64 +:100EC000860605EB8607F86809F002FF414609F03F +:100ED0003BFF26D8386909F0FBFE414609F03EFF8A +:100EE0001FD83979052907D0484606290ED2DFE8F0 +:100EF00001F0050508080B0B4046F6E7A1680870ED +:100F000004E0A168088001E0A168086055F8261097 +:100F1000BCA00AF02FFA2046BDE8F0470021FFF7F9 +:100F2000D5BBBBA0BDE8F04700F0CFBA5FF000042E +:100F300004EB8406514655F8260009F078FD78B197 +:100F400055F8261005EB8607AFF2EC300AF012FADE +:100F500000213846FFF7BAFBAFF204500AF00AFA54 +:100F6000641C622CE4D3A8E72DE9F04107F0B7F840 +:100F70004FF47A71B0FBF1F1AF480378AF480278D3 +:100F8000AFA00AF0F7F900F069FD0646BC48BD497C +:100F90000068B0FBF1F1BCA00AF0ECF9434F00246B +:100FA0000125A03757F8241051B105FA04F030425A +:100FB00003D0AFF2F0300AF0DDF9641CE4B2F1E7DF +:100FC000022000F039FDA0B1B74C38482178C0307C +:100FD00050F82110B5A00AF0CDF92078022808D1E8 +:100FE000B548007C08B16F2100E06E21B3A00AF083 +:100FF000C1F9AFF29C5000F068FA06F084FD024699 +:10100000AF484FF45F730188BDE8F041ADA00AF02E +:10101000B1B9B9A000F059BA2DE9FF5FDFF8089324 +:1010200099F8000038B9012189F80010BFA000F03C +:101030004CFA00F056FADFF82CB3DFF87CA25446E5 +:10104000DAF8000008F044FC00280CD0206808F012 +:1010500042FC092808D03F2806D0DBF800105C4687 +:10106000002902D0D0E12EE27EE1CBE128CC0008BD +:101070004D75737420626520616E79206F726465AE +:1010800072206F662041455452313233340D0A00CC +:1010900043757272656E742061737369676E6D65F6 +:1010A0006E743A200000000070040020E4C20008C2 +:1010B00043757272656E74206D697865723A202589 +:1010C000730D0A00417661696C61626C65206D691F +:1010D000786572733A2000004D69786572207365F7 +:1010E0007420746F2025730D0A000000557361672A +:1010F000653A0D0A6D6F746F7220696E64657820B1 +:101100005B76616C75655D202D2073686F77205B61 +:101110006F72207365745D206D6F746F72207661DD +:101120006C75650D0A0000004E6F207375636820B2 +:101130006D6F746F722C207573652061206E756DF4 +:10114000626572205B302C2025645D0D0A00000072 +:101150000C0900204D6F746F722025642069732084 +:101160007365742061742025640D0A00496E7661F0 +:101170006C6964206D6F746F722076616C75652C7C +:1011800020313030302E2E323030300D0A00000049 +:1011900053657474696E67206D6F746F7220256477 +:1011A00020746F2025640D0A0000000043757272E0 +:1011B000656E742070726F66696C653A2025640DE7 +:1011C0000A00000080C400083D0000004552523A69 +:1011D00020556E6B6E6F776E207661726961626CFE +:1011E00065206E616D650D0A000000004375727226 +:1011F000656E742073657474696E67733A200D0AA6 +:101200000000000025732073657420746F200000B7 +:101210004552523A2056616C756520617373696757 +:101220006E6D656E74206F7574206F662072616ECE +:1012300067650D0A0000000068010020D200002050 +:1012400053797374656D20557074696D653A202506 +:1012500064207365636F6E64732C20566F6C7461C9 +:1012600067653A202564202A20302E315620282513 +:1012700064532062617474657279290D0A0000005C +:101280000804002040420F004350552025644D487B +:101290007A2C2064657465637465642073656E736D +:1012A0006F72733A200000007C01002041434348E4 +:1012B000573A202573000000E00800202E25630027 +:1012C000D40000204379636C652054696D653A2031 +:1012D00025642C20493243204572726F72733A2084 +:1012E00025642C20636F6E6669672073697A653A9E +:1012F0002025640D0A0000004166726F33322043DE +:101300004C492076657273696F6E20322E32204E02 +:101310006F762031342032303133202F2031383A6B +:1013200033313A3537000000B50100200D0A456E13 +:10133000746572696E6720434C49204D6F64652C5B +:1013400020747970652027657869742720746F2070 +:1013500072657475726E2C206F72202768656C70D0 +:10136000270D0A0000000020614F0024254607F1E8 +:10137000C008DBF800600BE0DBF8002022B15D481C +:10138000396809F0A5FB10B904B93C463D460C3755 +:101390004745F1D394B1574F5946226808682B68E6 +:1013A000125C1B5C9A4209D192B92E2810D22022DD +:1013B0003A54401C0021CBF800003954DBF80000FF +:1013C0005F4608B1AC4213D04BA000F07EF80AE0B3 +:1013D0003A54401C0860E0E7206800F076F80920E5 +:1013E00000F081F80C34AC42F6D900F07AF800260F +:1013F000404C38688642BFF422AEA05D00F073F81E +:10140000761CF6E7042812D00C2816D019B10A2849 +:1014100017D00D2815D07F283FD03029EBD22028B7 +:10142000FFF40DAE7E283FF60AAEA9B343E004B048 +:101430003048BDE8F05FFFF74BBA31A000F045F847 +:1014400027E0AFF6EC1000F040F82A4E20680025A7 +:101450000C2335542D48CDE900061022244902956D +:1014600001A809F091FA070007D0386809F007FBD6 +:101470003044B968401C884702E025A000F025F8F8 +:1014800030211C4809F0BCFA256099F800000028BA +:1014900019D000F026F8D2E50BE00029FBD0154A60 +:1014A000491E0020CBF80010505422A000F00DF887 +:1014B000C5E52028EFD00F4A5054491CCBF8001046 +:1014C00000F011F8BBE5BDE8FF9F70B504461A4D6A +:1014D00003E0641C286807F0ABF821780029F8D1F4 +:1014E00070BD16A0F1E701461348006807F0A0B8E8 +:1014F000C0C30008400400200D1B5B4B000000002F +:101500001B5B324A1B5B313B31480000190300086A +:101510004552523A20556E6B6E6F776E20636F6D39 +:101520006D616E642C20747279202768656C702759 +:101530000000000008200800E00800200D0A232019 +:10154000000000002DE9F04105460446FD4EFE4F27 +:1015500009E0FC4809F089FA20B1611B801B38447E +:1015600080F80A11641C21780029F2D1BDE8F081CD +:10157000F64800210278372A12D14288B2F55F7FFF +:101580000ED10279BE2A0BD190F87923EF2A07D128 +:1015900000F55F7210F8013B59409042FAD309B14F +:1015A00000207047012070472DE9F05FFFF7E0FF52 +:1015B00010B90A2006F04CFE4FF45F72E349E2488E +:1015C00009F005FAE04C94F87803022802D90020CB +:1015D00084F87803C0B200EB001101EB401004EB7B +:1015E000800101F59671C422D94809F0F0F9D84A72 +:1015F000D84F002092F8201092F81F5040F6C416E1 +:1016000000FB00F3193B4B4303F6C41343436B4306 +:1016100093FBF6F327F81030401CC0B20728EFD335 +:1016200092F8211092F822509146B4F8D220B4F8E2 +:10163000D080DFF824A300204FF00A0E4FF47A7B0D +:10164000C5F1640701EB8106A2EB080400EB800200 +:10165000C1EB42030122002B03DDC1F16402D2B2CF +:1016600001E000DA0A4603FB03FC05FB0CFC02FB6D +:1016700002F29CFBF2F23A4402FB03F292FBFEF20E +:1016800002EB460212B204FB02F292FBFBF242446E +:101690002AF8102000F10100C0B20C28D6D399F826 +:1016A000000002F079F8BDE8F05F04F09FBC2DE97E +:1016B000F047A54D8146372028704FF45F7400270E +:1016C0006C80BE202871EF2085F879033E4685F8AE +:1016D0007A7369B195F87803C42200EB001101EB2D +:1016E000401005EB800000F59670994909F06FF9FC +:1016F0009548974903E000BF10F8012B57408842F6 +:10170000FAD385F87A73914F4FEA040809F020F86C +:10171000342009F08BF8384609F048F804280FD136 +:101720000024E019295909F05DF8042805D009F0D2 +:1017300015F8761C032EE9DB02E0241D4445F0D3A6 +:1017400009F00CF8032E02D0FFF712FF10B90A209F +:1017500006F07EFDFFF728FFB9F1000F06D0BDE8C7 +:10176000F047012214210F2001F00EBCBDE8F087E4 +:1017700075498A6802438A6070472DE9FC5F77A14A +:10178000D1E90001CDE900014FF45F716E4809F025 +:1017900037F9C4216E4809F033F96B4B3720002527 +:1017A00018700320587102209D60FFF7E1FF83F855 +:1017B00078534FF41670A3F8F000FA20A3F8F20063 +:1017C000D0332A20D8835D859D85DD859D74DD74A9 +:1017D0001D75DD821D835D831C334FF001095D7033 +:1017E00083F80090202018735E4898606E209876E9 +:1017F0002B20D876212018775D7783F82650283360 +:1018000040F2DC505D75188040F24C405880443BFB +:1018100040F26C70A3F8480083F84A5040F27E40D2 +:10182000188040F23A7058804FF47A70988040F2F5 +:101830007E50D88040F2EA50188140F2B45058816E +:101840003220C1009881D981188283F84D5083F8E5 +:101850004E504FF4E13119654FF49641596583F8C4 +:10186000585040F6AC513A4C23F8C41C83F84C5005 +:101870002826257066701E27E77217216175A670ED +:101880002773A1755521E1702D226273E5752671CC +:101890001921A1733C2121760B216171E5736576D5 +:1018A0004FF0140B84F806B008232374A2760E229E +:1018B000E27184F811B05021E1765A2121724FF083 +:1018C0000A0884F812804FF0640A84F81CA066723B +:1018D000A5722575A577E177412184F8201084F859 +:1018E000235084F8245084F8255084F8210084F88B +:1018F000225025856585E584042084F82C0084F831 +:101900002D6084F82E60152084F82F00164820637F +:10191000164860631648A063012084F83C0015A0B7 +:10192000FFF710FE84F8665084F8675084F868600A +:10193000012084F8690084F86A5004F8AC8FC82349 +:1019400063701DE028CC00087004002000F8010836 +:10195000EC070020C00A0020CE0A00201E1E64648E +:1019600064646464031414009A99193F52B87E3F6A +:101970003333733F41455452313233340000000059 +:101980004FF49660608040F2D930A0803D4800213D +:10199000EE4640F2DC544FF47F754FF4FA6C00BF12 +:1019A00000EBC10222F86C5FA2F802C094801EF81E +:1019B0000180491C82F806800829F1DB00F8B29FFB +:1019C0004FF4967180F8019080F80290838080F83F +:1019D00006B0C77180F80890A0F80AA08181C6817E +:1019E0000020294D014600BF05EB0012401C11618B +:1019F0000C28F9DB5FF0000404EB041000EB44104A +:101A000005EB800000F59670C4221E4908F0DFFF48 +:101A1000641C032CF0DBBDE8FC9F10B50446FFF707 +:101A2000A7FD641E204206D1FFF7A7FE0021BDE8F6 +:101A3000104008463BE610BD14490968014201D038 +:101A4000012070470020704710490A6802430A606D +:101A500070470E490A6882430A6070470B48006865 +:101A6000704709498968014201D001207047002070 +:101A7000704705498A6882438A60704702488068D7 +:101A800070470000EC0700207004002004000020D4 +:101A900070B5FE4809F064FF0446FD48008809F06F +:101AA00020F90546214609F091F809F01FF9F94C93 +:101AB00029462080F84809F0BFF8F84909F0BCF839 +:101AC000E0650820FFF7B8FF002803D0BDE87040AC +:101AD00002F0F0BD70BD002801DD024600E0424288 +:101AE0008A4201DA00207047002802DDA0EB0100E5 +:101AF0007047FDDA084470472DE9F04F91B0D0E906 +:101B00000045814686688846086809F029FF0490E8 +:101B1000D8F800000AF00AFB0590D8F8040009F094 +:101B20001FFF0190D8F804000AF000FB0746D8F820 +:101B3000080009F015FF8246D8F808000AF0F6FA06 +:101B400083465046049909F041F8079050460199A0 +:101B500009F03CF880465846049909F037F8069099 +:101B60005146059809F032F808905946059809F051 +:101B70002DF803900198594680F0004009F026F8AE +:101B800082463946089809F021F8069908F0C6FF00 +:101B900010903946039809F019F8079909F013F8DD +:101BA0000E900598019980F0004009F00FF805901B +:101BB0003946079809F00AF8039909F004F80290E9 +:101BC0003946069809F002F8089908F0A7FF8346FD +:101BD0000499019808F0FAFF04903046029908F041 +:101BE000F5FF01902846109908F0F0FF009041465B +:101BF000204608F0EBFF009908F090FF019908F0EB +:101C00008DFFC9F800005946304608F0DFFF8346D3 +:101C100028460E9908F0DAFF80465146204608F023 +:101C2000D5FF414608F07AFF594608F077FFC9F81A +:101C300004003046049908F0C9FF06462846059975 +:101C400008F0C4FF05463946204608F0BFFF294684 +:101C500008F064FF314608F061FFC9F8080011B0D0 +:101C6000BDE8F08F2DE9F04380468A4887B0843084 +:101C7000016881F000410391406880F000400490C9 +:101C80008748B0F9000009F023F8864908F09EFF64 +:101C9000804C05907834B4F9000009F019F80090F0 +:101CA000B4F9020009F014F80190B4F9040009F045 +:101CB0000FF8029003A96846FFF71EFF7A4D783CA3 +:101CC00095F83C00012804D07148008809F009F813 +:101CD00017E0764840780028206B0CD1C11700EB44 +:101CE0009161A0EBA11008F0F3FF029908F016FF34 +:101CF00008F0FCFF2063C11700EB9160801108F031 +:101D0000E7FF029908F05FFF0290616B894608F0D7 +:101D100057FF0746404608F0E4FF0646644908F0CE +:101D2000FDFE0146304608F087FF394608F04EFFB9 +:101D3000494608F0F3FE606309F0D2FE15F82D1F46 +:101D4000FFF7C9FE08F0C4FF0290009809F0C8FE32 +:101D50006978FFF7C0FE08F0BBFF0090019809F01A +:101D6000BFFE6978FFF7B7FE08F0B2FF0190E168A7 +:101D700001EB0800E0602069401C2061009809F038 +:101D8000AFFE4C4C216808442060019809F0A8FE81 +:101D9000616808446060029809F0A2FEA1680844E6 +:101DA000A06007B0BDE8F0832DE9F05F394D04462F +:101DB0008435286809F0D4FD834628680AF0B6F90E +:101DC0008246686809F0CCFD814668680AF0AEF981 +:101DD0000546D4F808802946404608F0F7FE5946E3 +:101DE00008F0F4FE676806465146384608F0EEFEF5 +:101DF000294608F0EBFE05464946206808F0E6FE55 +:101E0000294608F08BFE314608F088FE044651460C +:101E1000404608F0DBFE05465946384608F0D6FE37 +:101E2000294608F0CDFE214609F070FC224908F051 +:101E3000CDFE224908F000FF1649896A08F06EFEBF +:101E40001F4908F0F9FE09F04BFE00B2002802DA43 +:101E500000F5B47000B2BDE8F09F2DE9F04F8DB0F1 +:101E6000002606F022F9DFF82CB005465C46DBF8C8 +:101E70003800281A099008F034FF1249C96808F0A0 +:101E8000A5FE0490A56300241EE00000F366DF3E7B +:101E900082010020080000200AE81C4100401C4686 +:101EA000B001002035FA8EBCEC0700208C0A00201F +:101EB0003661023CC80800200000E144DB0F4940C5 +:101EC000000020416C0C00200BF1720A0AF106059B +:101ED0004FF07E58FE4890F82C70FE4830F9140000 +:101EE00008F0F6FE049908F071FE06A941F82400F6 +:101EF00017B3384608F0F5FE0146404608F09CFE50 +:101F000081460B903AF9140008F0E2FE494608F0C9 +:101F10005DFE814641460B9808F055FEEE4951F8AA +:101F2000241008F053FE494608F0F8FDEA4941F84C +:101F3000240008F0DBFE01E03AF8140025F8140054 +:101F400035F91400641C00FB0066032CC5D3DFF8D0 +:101F50008CA364204643BAF8000006A9404396FBD0 +:101F6000F0F4DD481830FFF7C7FD0820FFF764FDE7 +:101F700006A910B1D8480C3801E0D6482030FFF748 +:101F8000BBFDA0B24938DFF858933C2827D2002483 +:101F9000B9F8F00008F0A5FE45464146059008F066 +:101FA000BDFD0146284608F047FECB4E05461836D3 +:101FB000C8480C3030F9140008F08AFE074656F87D +:101FC0002410059808F002FE394608F0A7FD2946BE +:101FD00008F0FCFD46F82400641C032CE8D308201C +:101FE000FFF72AFD48B34546BB4EDFF8E8820024E0 +:101FF0000C3E08F11208B9F8F20008F072FE8146B2 +:10200000294608F08BFD0146284608F015FE0546D6 +:1020100038F9140008F05CFE0746484656F82410CC +:1020200008F0D4FD394608F079FD294608F0CEFDC8 +:1020300046F82400641C032CEAD35E46BBF900007A +:1020400008F046FEA44C1834A16808F07DFE01D2C9 +:10205000012100E00021A3484173D4E9010109F006 +:1020600055FB9C4D18352860A068014608F0AEFD70 +:1020700007466068014608F0A9FD394608F04EFDA4 +:102080000AF01AF90146206880F0004009F03EFB92 +:10209000DFF8548268604146286808F097FD09F02F +:1020A0001FFDA5F1580741463880686808F08EFD8D +:1020B00009F016FD78800820FFF7BEFC8B4D10B1AB +:1020C00085480C3801E083482030FFF76DFE2880FA +:1020D0000998FFF7C7FD7E4D95F86A0000281BD0D0 +:1020E000BAF8000008F0FDFD0146A06808F0A4FD64 +:1020F0007F4908F06BFD08F0F9FDC0F1640064222F +:10210000002104F0F1FC95F86A104843C11700EB78 +:10211000517040F3CF0070800DB0A1E52DE9F04182 +:1021200002F0BFFA0220FFF787FC20B102F0BCF9F1 +:10213000FFF793FE05E067480021801D0180418084 +:1021400081804020FFF78DFC624B654CA3F10C01B0 +:1021500018B3A1F15A02107830B9D4F8F400040C85 +:102160001470040A547090705A4C0020B4F10604A4 +:10217000155C33F9106034F91070A5F1010C07FB00 +:102180000C66761C96FBF5F521F8105024F81050DB +:10219000401C0328ECD3BDE8F0816079012809D008 +:1021A0005FF0000033F8102021F81020401C0328B5 +:1021B000F8D3F0E7474AB3F904006C3AB2F90440A7 +:1021C00000EB4400032490FBF4F088809080188892 +:1021D000088058884880DEE73F4900200C310860BD +:1021E000486088603B496C390861C86070472DE9D8 +:1021F000F84F05F05AFF374C46F2A8126C3CE16BE1 +:10220000A0EB0108904502D20020BDE8F88F394FBD +:10221000E0632F4D3888DFF8E090DFF8E0A0DFF8CA +:10222000E0B04FF07E5640B3206D6269C11700EBFD +:102230005171A0EBE10095F82F10491EB2FBF1F1AE +:102240000844C117206500EB5170C01008F040FD34 +:10225000494608F0F1FC514609F05AFC314608F0B5 +:10226000B2FC594608F0B2FC08F040FDE0640020E2 +:10227000206460643888401E388095F82F006169BA +:10228000401EB1FBF0F008F02CFD494608F0D4FCEC +:10229000514609F03DFC4FF07E5108F094FC594640 +:1022A00008F094FC09F01CFCE16C2F6B461A3946CF +:1022B0004FF07E5008F084FC8146304608F008FD5F +:1022C000494608F083FC0646A06908F001FD19E0C4 +:1022D000EC07002074000020BC08002082010020D0 +:1022E000700400208C0A00204C3D0F44B0010020F7 +:1022F0000000C842AE01002080E6C547B1DC423E86 +:10230000D048874A394608F061FC314608F006FC9F +:1023100009F0E6FB8346A061E06808F0E2FC0746AE +:10232000654908F053FC0646206908F0D1FC814657 +:102330006248806808F0CCFCE16D08F047FC394643 +:1023400008F044FC494608F077FC0746206C31460B +:10235000009008F03BFC81464FF0FF31384608F012 +:10236000ABFC314608F032FC494608F0D7FB616C03 +:1023700008F0D4FBD5F83890824649464FF07E509D +:1023800008F01EFC0646584608F0A2FC314608F04C +:102390001DFC06464946504608F018FC314608F038 +:1023A000BDFB606408F0A2FC60653946009808F047 +:1023B000B5FB2064FFF710FFD4E915104FF49677B2 +:1023C000401AC7F100093A46494604F08DFB0A213C +:1023D000FFF781FB297906467143C81701EB50606E +:1023E000C822C011514204F07FFBE061A97B4CF28E +:1023F00050327143C81701EB9060216A01EBA010C5 +:102400005142206204F070FBC117206200EBD150F2 +:10241000E16901EB6020E061404608F062FC804623 +:10242000A669A06C301A08F053FC254908F0CEFBD1 +:10243000414608F001FC08F059FC3A464946A664BA +:1024400004F052FB0A21FFF746FB6F6B80463946CA +:102450004FF07E5008F0B4FB0646404608F038FCCA +:10246000314608F0B3FB06463946206C08F0AEFB57 +:10247000314608F053FB206408F038FC4FF47A72C0 +:10248000514204F031FB08F023FC206409F028FBE2 +:102490000521FFF720FB6062297E96224143C81781 +:1024A00001EB107000116FF0950104F01DFBE16964 +:1024B000081AE0610120A8E6BD378635C80800206B +:1024C0000024744970B5994D0446286807F009FA4C +:1024D0000028FAD0E1B2286807F0EAF9204670BD7A +:1024E00086B005F02BFE0020FFF797FAFFF75CF8A7 +:1024F0008F4C002594F8090118B101281ED0092835 +:102500001CD08DF8105084F8095104A804F0CCFCBC +:1025100004F0F2FA0E20FFF797FA00F050F9607914 +:1025200001260E280DD008280BD08DF8065000BFCC +:102530004FF48070FFF795FA50B905E08DF8100060 +:10254000E3E78DF80660F3E70820FFF78AFA00B1A9 +:1025500001208DF802004FF4004B5846FFF781FA36 +:102560008DF803000120FFF77CFA8DF801000820A8 +:10257000FFF777FADFF8B48180F001008DF80000F2 +:102580006C4F98F812008DF8040097F8B400C0F36F +:1025900080008DF80500B4F8DE00ADF80800B4F84E +:1025A000E000ADF80A004FF48040FFF75AFA08B196 +:1025B000B4F8DA00ADF80C00B7F8B000ADF80E00D2 +:1025C00094F80901012823D0092824D08DF8075058 +:1025D000684605F065FC5849002040F2DE5200BF15 +:1025E00021F81020401CC0B21228F9D35449534896 +:1025F0000827086088F811703846FFF732FAB0B142 +:1026000094F8120158B1012809D002281CD10AE01F +:102610008DF80760DCE707208DF80700D8E7484809 +:1026200003F056FF10E0464804F0D5FB0CE094F8A8 +:102630001D0128B194F91E01002801DA84F81E5109 +:1026400094F81E0103F01BFD0120FFF70AFA30B1D8 +:102650004FF48060FFF705FA08B102F0AFF839498E +:102660004FF0100AC1F800A0A1F10409B846C9F85A +:1026700000700025A9F10407386880F01000386068 +:10268000386880F008003860192005F037FD012017 +:1026900005F03FFD192005F031FD002005F039FD62 +:1026A0006D1CEDB20A2DE7D3C9F80080C9F800A06F +:1026B00001F03CFDFFF7ECF90220FFF7D2F908B179 +:1026C00001F000FED4F8200102F0A9F95846FFF706 +:1026D000C8F928B194F82811D4F8240107F006F8B5 +:1026E0004FF40060FFF7BDF908B104F09FF805F062 +:1026F000DCFC154908606079052803D113494FF4C3 +:10270000C870088012494FF47A7008801149C820B7 +:102710000880114880F80D6001F046F8FCE7044895 +:10272000B0F9D40000F041F9FEE70000E008002015 +:1027300070040020EC0700209C0A00205B33000896 +:1027400004010020140C0140000100207E01002043 +:1027500080010020AE0100208C0A00200146FE48C6 +:1027600000EBC100B0F97000122804DA082902DA7F +:10277000FA4931F910007047F74A02EBC00090F9AE +:102780007200084202D04FF0FF30704701207047BE +:102790002DE9F041F24DF34E00244FF480473846C6 +:1027A000FFF75FF910B1B5F8DA0001E0B5F8D40031 +:1027B00026F81400641C0C2CF1DBBDE8F0812DE937 +:1027C000F041E74EE84F707907EBC000407800B168 +:1027D0000120E64CA0742020FFF743F908B1012046 +:1027E000A074E04D7079E24C1835162808D017F81F +:1027F000301007EBC0002170426842B3002024E093 +:102800005FF0000006EB00110A6912F0FF4F1ED0C6 +:10281000D1E9057C05EB0013C969401CC3E902C17D +:10282000C3E900272178491C21700C28EADB0EE05F +:1028300002EB001305EB0016D3E9007CD3E9028319 +:10284000C6E90283C6E9007C401C8842F0DB4FF4F5 +:102850008040FFF706F9D8B12778012F18D9002654 +:1028600014E000BF05EB06144FF0FF384146A068A6 +:1028700008F022FAA0604146606808F01DFA606026 +:102880004146E06808F018FA761CE060BE42E9DBD9 +:10289000BDE8F0417CE7F0B5401C0021B04A0B4692 +:1028A00002EB0114491C23610C29F9DBAE4B03EB4D +:1028B000C0014C68002C11D0002113F830000BE04F +:1028C00004EB011302EB011593E8C010DB68491C0F +:1028D000C5E906C3C5E904678842F1DCF0BDA34839 +:1028E00010B5807C00284DD0A14C9D48241D427914 +:1028F000E0882189082A27D006DC012A15D0042A7D +:1029000029D0052A06D10AE00E2A29D0142A22D07D +:10291000152A25D02020FFF7A4F8002832D02188DE +:10292000002005F04DFB618813E091498A48091D9C +:1029300090F8B300498908B100201FE08D48407825 +:102940000028F9D10021F7E70146002005F038FB07 +:102950002189012012E0002005F032FB6189F8E7AF +:102960000146002005F02CFB2189012005F028FB01 +:102970006189022005F024FBA1890320BDE81040F5 +:1029800005F01EBB10BD70B5764E0024183E784D84 +:1029900007E000BF36F81410204605F006FB641C63 +:1029A000E4B228788442F5D370BD714A6D4B0021A2 +:1029B0001278183B04E000BF23F81100491CC9B28B +:1029C0009142F9D3DFE72DE9F047DFF8A891684C91 +:1029D000002599F80100684F614E241D48B3B6F8F0 +:1029E000D220B6F8D010B7F9060004F07DF85D49A2 +:1029F000E0811839B046088096F81B01564E4FF01A +:102A0000640A48B30220FFF7A9FEB6F97E20B6F9A2 +:102A10007C1004F069F8B8F81431181A0FFA80FC29 +:102A20005348B0F90220624506DA98F81B111144A8 +:102A300007E0B6F8D400DAE704DD98F81B11A2EB42 +:102A40000101418096F98210B0F9020001FB00F10A +:102A500091FBFAF01844A08099F80A0050B1388828 +:102A600000EB0501E18000EB25402081B888608102 +:102A700078880AE04148018801EB0502E28001EB19 +:102A800025412181818861814088A0814FF0030226 +:102A90004FEA0A0306EBC20034F9121090F97200F3 +:102AA00000FB01F090FBF3F024F812001046FFF752 +:102AB00055FE34F81210084424F81200521C072A5C +:102AC000E8DBBDE8F0872DE9FC5F294C2A4E2B4D51 +:102AD0002078032814D9B6F904004142002801DD0A +:102AE000024600E00A4602F1640200DC08466FF08C +:102AF0006301A1EB0001B5F9040003F0F5FFA88024 +:102B00001B48DFF86090DFF850A00078A9F11809A1 +:102B100001284FD9002480464AE000BF9AF9B2004C +:102B2000B5F904104042484308F0D2F80D49183175 +:102B300001EB0417F96808F049F80190B5F90000B5 +:102B400008F0C6F8796808F041F80090B5F902007D +:102B500008F0BEF8B96813E0EC0700209C0A0020DA +:102B6000700400200C090020A4D00008E008002018 +:102B7000B40000208C0A002044010020360100200F +:102B800008F024F88346B6F9060008F0A1F8396881 +:102B900008F01CF8594607F0C1FF009907F0BEFF86 +:102BA000019907F0BBFF08F0A1F829F81400641C94 +:102BB0004445B3D3DFF8B483DFF8B4B3ED4C98F8F1 +:102BC0000500082868D006DC012837D0042809D081 +:102BD000052840D140E00E285BD014287ED015286F +:102BE000F7D1D7E00420FFF7B9FD03460221042006 +:102BF000FFF7C2FDB5F9041000FB01F60121042026 +:102C0000FFF7BAFDB5F9021000FB016018442081FE +:102C10000520FFF7A3FD064602210520FFF7ACFDC6 +:102C2000B5F9041000FB01F301210520FFF7A4FD15 +:102C3000B5F9021000FB013030440BE00520FFF72E +:102C40008DFD034601210520FFF796FDB5F904101F +:102C500000FB01306081C1E09AF97200BBF90210FB +:102C60003222484390FBF2F60AF172035D460020DF +:102C7000FFF774FD3044208093F90800B5F9001087 +:102C8000484390FBF2F20120FFF768FD104460809A +:102C9000A4E0FFF798FEA1E0B74F787888B3B8F8C2 +:102CA000D220B8F8D010B6F9060003F01DFFE0817D +:102CB000A9F80000B87A4FF0010100284FF0030096 +:102CC00023D0FFF759FDB6F9021000FB01F30221F2 +:102CD0000320FFF751FDB6F9001000E042E000FBD1 +:102CE0000130E08001210420FFF746FDB6F9021013 +:102CF00000FB01F302210420FFF73EFDB6F90010AE +:102D000020E0FFE7B8F8D400D1E7FFF735FDB5F9CB +:102D1000021000FB01F302210320FFF72DFDB5F99E +:102D2000001000FB0130E08001210420FFF724FDAA +:102D3000B5F9021000FB01F302210420FFF71CFD8E +:102D4000B5F9001000FB013020810320FFF706FDDC +:102D5000E1880844E0800420FFF700FD2189084451 +:102D600020813BE0042301211846FFF705FDC3F154 +:102D7000050135F81110484324F813001846FFF7F1 +:102D8000EDFC34F81310084424F813005B1C062BE8 +:102D9000E9D323E0032302211846FFF7EDFCB5F940 +:102DA000041000FB01F701211846FFF7E5FCC3F111 +:102DB000060121F00101695E01FB007024F8130097 +:102DC0001846FFF7CBFC34F81310084424F813001E +:102DD0005B1C072BDFD3F188A9F800102020FEF739 +:102DE00040FEC0B30020FFF7B9FC20800120FFF7B0 +:102DF000B5FC62496080097A69B39AF8B4205146FB +:102E0000920715D591F97220BBF9025052426A43DC +:102E100032259AF97A10BBF9003092FBF5F259434A +:102E200091FBF5F32588D11A691A2180D11810E099 +:102E30009AF97230BBF90220268803FB02F5322290 +:102E400095FBF2F535442580BBF900104B4393FB0D +:102E5000F2F10844608000254FEA0A0606EBC5003F +:102E60006C30B0F90220B0F9001034F9150003F00D +:102E70003BFE24F815006D1C082DEFD396F8B40026 +:102E8000DFF8FCA0400711D500252020FEF7E9FD62 +:102E900000B102250024564606EB44000189601962 +:102EA000C0B205F08DF8641C042CF5D3314F01201D +:102EB0003F1F4D46B9F900603A7805E035F910102A +:102EC000B14200DD0E46401C9042F7D3002448E09A +:102ED000B8F8D200B04205DA35F81410301A081AE2 +:102EE00025F814004FF48040FEF7BBFDA0B1BAF9FD +:102EF000060040F2DC518842404604DDB0F8D220A2 +:102F0000B8F8D81003E0B0F8D620B8F8D41035F9E6 +:102F1000140003F0E9FD15E0B8F8D220B8F8D0109D +:102F200035F9140003F0E0FD25F81400BAF9061095 +:102F3000B8F81601814207DA1020FEF792FD38B189 +:102F4000B8F8D40025F814000B48407818B107E011 +:102F5000B8F8D000F6E70B4830F8140025F8140054 +:102F6000641C38788442B3D3BDE8FC9F7004002011 +:102F700034000020B80000208C0A0020E60A00205F +:102F80009C0A00200C0900202DE9F04717468946CD +:102F900006460025DFF83C841AE0002411E000BF5B +:102FA000D8F8001081F00801C8F80010012005F0E1 +:102FB000B0F8484605F0A2F8002005F0AAF8641C15 +:102FC000E4B2B442ECD33C2005F098F86D1CEDB2AD +:102FD000BD42E2D3BDE8F0872DE9FC5FFE4C002541 +:102FE00040F2DC51B4F90600FC4E4FF4FA7388420B +:102FF00001DA64210CE0F949B0F5FA6F91F8251077 +:1030000004DAA0F2DC52514391FBF3F1C1F1640107 +:103010008946F34996F866E096F867B0B1F814412E +:103020000022B246EC49EE4B40F2E63C31F9126028 +:10303000311B01F2F317674503D8002903DCA11BFC +:1030400001E04FF4FA71022A34D0BEF1000F05D02E +:103050008E4502DAA1EB0E0100E00021642391FB12 +:10306000F3F3DD4F6FF01808243707EB430C37F903 +:103070001370BCF902C003FB08F3ACEB070C01EBC7 +:1030800083030CFB03FC64239CFBF3F33B44D54F0D +:1030900027F812309AF823304B434FF4FA7193FB20 +:1030A000F1F1C1F1640189B201FB09F1642391FBE3 +:1030B000F3F11CE0BBF1000F05D08B4502DAA1EB68 +:1030C0000B0100E0002193F9EC30DFF818C35B42FC +:1030D0004B43ACF804309AF82430002900DC494214 +:1030E0004B434FF4FA7193FBF1F1C1F164010AEB28 +:1030F0000207642397F801C0DFF8E8820CFB01FCAB +:103100009CFBF3FCA8F1540808F802C097F80BC028 +:1031100008F103080CFB01FC9CFBF3FC08F802C05F +:103120007F7D4F4397FBF3F108F10303A6429954C7 +:1031300005DAAC4931F812305B4221F81230521CEA +:10314000032AFFF66FAFDFF898A24FF4FA625446F5 +:10315000BAF8161103F0C8FCB4F816114FF47A72DD +:10316000401A5043C1F5FA61B0FBF1F1642291FBC2 +:10317000F2F0994B6FF01806323303EB400433F949 +:1031800010307043B4F9024001EB8000E41A44436C +:1031900094FBF2F0DFF84C828F4E1844103EA8F8F2 +:1031A0000600707AA8F17C04E8B38F48B4F91E10C9 +:1031B000B0F90000401A07F08BFD8C4907F006FDBE +:1031C0008B4907F039FD074608F0CAFB01903846E5 +:1031D00008F0ACFF00904746B8F9000007F078FD12 +:1031E0008346009907F0F2FC8046B7F9020007F029 +:1031F0006FFD8146019907F0E9FC414607F08EFC1E +:1032000007F074FD80464846009907F0DFFC8146D0 +:103210005846019907F0DAFC494607F0D1FC07F05F +:1032200065FD388000E001E0A7F802800220FEF78B +:1032300018FC002750B3E078401CC0B20621B0FB58 +:10324000F1F2E07001FB1200B8B9002003F09EFE1D +:103250002179614A01F00703AC3A491C22F81300B6 +:103260002171002032F81010401C29448DB208282A +:10327000F8DBE80801F00EF8A072A07AE18C884231 +:1032800003D89AF80811814201D9A77001E00420FF +:10329000A070A07803F0BFF956484E4D008818B1D1 +:1032A0000220FEF7C9FB10B95348008820B12868F6 +:1032B00080F00800286011E0B178082011B145497C +:1032C000091D0860717811B14249083108604FF456 +:1032D0000060FEF7C6FB08B103F0BDFA8020FEF7E0 +:1032E000C0FB48B1E16C606B411A05D44CF250311F +:1032F0000844E06405F024FAA16C606B411A03D421 +:10330000717BF9B10120B07002F027F82020FEF7A0 +:1033100093FB68B1216D606B411A09D4E17A0529EC +:1033200006D3364908442065286880F010002860DC +:103330003348816800290ED002B02A48BDE8F05F0A +:103340005C380847B770296881F0080129602D4969 +:103350000844A064D8E7BDE8FC9F10B5204C204489 +:1033600090F80A0104F036FEA0F2EE2140F2DD52A0 +:10337000914201D3B4F8140110BD2DE9F047194E64 +:10338000DFF854807C3EA8F19C087079124F401CF5 +:1033900000247071A14608F14005F16B2046884772 +:1033A000727908EBC40102F0030221F8120025F83B +:1033B0001490002035F8143031F81020401C1A44C5 +:1033C000C0B225F814200428F4D335F91400801C69 +:1033D000C11719E00C0C01409C0A0020EC070020EA +:1033E0007004002044010020B0010020DB0F4940A0 +:1033F000000034437E01002080010020F0490200DB +:103400006C0C002020A1070000EB9170801025F8C3 +:10341000140037F91410C91E884202DA811C27F8FB +:10342000141037F91410C91C884202DD801E27F8D9 +:103430001400641CE4B2082CAFD3CBE5FE4802882C +:10344000FE48417852B9827842B1002905D1012164 +:103450004170FB48FB490088C88370470029FCD1B4 +:103460000122FF2102208FE52DE9FC5F0020F549B4 +:1034700082467C31054607460190B1F9020043427D +:10348000002801DD044600E01C468B46B1F900101F +:103490004A42002901DD0E4600E01646B44203DD33 +:1034A000002806DC184604E0002901DD084600E09B +:1034B0001046DFF8949300240090E04EF07808B9AD +:1034C0003079E8B3022C3FDADE484FF4FA72443028 +:1034D00030F914103BF9140001EB4000514203F0A5 +:1034E00003FBDA49DFF868A331F91410411A0AEB3B +:1034F0004400B0F9280001EB00089AF80810642095 +:1035000001FB08F191FBF0F09AF81C1001EB81022D +:10351000494201EB810103F0E7FA0190C94842F208 +:103520001072743050F8241001EB0800514203F07F +:10353000DBFAC449743141F824009AF8121000E013 +:1035400008E048434FEA203AF07818B1307908B9DA +:10355000022C48D13BF91450B84F05EB850001010E +:10356000BB48A83F00EB04084FF47A5298F80100DA +:1035700091FBF0F039F91410401A57F82410084460 +:10358000514203F0B1FA47F8240039F9140000F56C +:103590002070B0F5A06F02D857F8240002E0002098 +:1035A00047F824007D2190FBF1F098F80B10484378 +:1035B00087113079A8B1022C13DA0098009AC0F56F +:1035C000FA710198009B484305FB02004FF4FA7220 +:1035D00001FB0AF107FB031190FBF2F091FBF2F6FD +:1035E00008E0F07820B1022C02DA5646019801E09A +:1035F00028463E46934A39F9141028325023125D6A +:10360000DFF838824A4392FBF3F28E4B821A68331A +:10361000A8F13C0833F9140023F81410081A08F133 +:103620000C0158F8243051F824C041F824309C444F +:10363000844448F8240083482E30005D00FB0CF0E1 +:10364000C11700EBD1609119A1EB60107D496E317B +:1036500021F81400641C032CFFF62FAF7BE62DE944 +:10366000F05F764E4FF0000BDFF8E4A1DFF8D49165 +:103670005C46A83E714DE87808B92879D0B1022C93 +:1036800018DA70484FF4FA72443030F914103830B8 +:1036900030F9140001EB4000514203F025FA6B4968 +:1036A00031F91410411A0AEB4400B0F9280001EB7B +:1036B000000B01E0022C52D0E878E0B39AF8080041 +:1036C00000FB0BF0001160490AEB040731F91410FC +:1036D000FA7A451A787856F8241068434FEAE018C9 +:1036E000B9F80C006843C01200FB02104FF400123E +:1036F00046F82400514203F0F7F946F8240043133A +:103700004E480C3850F8241040F82450B9F80C00FA +:10371000691A02094FF6FF70B0FBF2F048434749BF +:103720008011243901F10C0251F824C052F82450C0 +:103730006544054400E01CE042F824C041F8240040 +:10374000787D6843011208EB030008443D496E315F +:1037500021F81400641C032C8CDBBDE8F09F9AF860 +:10376000240038491B307C31B1F904104843401122 +:10377000A9E7344A9AF823007C321B3032F914202E +:1037800050432A790011002A9DD09AF8121001FBAB +:103790000BF100EB212096E72A49012801D02D48A2 +:1037A00000E02D48086470472DE9F84F0027B9461E +:1037B000B8460820FEF755F9DFF8A0B068B19BF8CD +:1037C000120120B1012802D0022806D102E002F045 +:1037D000A2FE01E003F01EFB8046DFF868A0174C54 +:1037E0004FF00005DAF83410DAF854004FF0010613 +:1037F000081A02D5B8F1000F7DD044F620621144BA +:10380000CAF85410FFF7B9FD4FF48040FEF729F9CC +:1038100028B10A485A30007808B900F07DFC9BF8BE +:103820001C0168B305494FF47A72103101EB400076 +:103830000021B0F9060013E0800100208C0A00206E +:10384000B0010020C80000206800002034000020E3 +:10385000EC070020693400085F360008700400207F +:10386000A0F57A7003F040F907F032FAFE4907F04C +:10387000E3F9FE4907F0AAF907F051FAAAF8220085 +:103880004FF40070FEF7EDF8B0B3DFF8E483BAF957 +:103890000E2098F8ACC00CEB8C0191421DDA6078D8 +:1038A000D8B1BBF91431F349002000BF21F8103022 +:1038B000401C0328FADBB8F8AE30CB8098F8AD0096 +:1038C000604400EB8000904202DA00F025FC257095 +:1038D000BAF81010491CAAF8101098F8AC0000EBC8 +:1038E0008001BAF90E00814204DA607810B900F064 +:1038F00013FC257001E068E204E0BAF80E10491CE0 +:10390000AAF80E10BBF816C1BBF81821DFF86483C3 +:103910000020BF0838F91030634501DD47F080070B +:10392000934201DA47F04007401C0428F1DB9AF883 +:10393000071050468F4205D18179FA2903D2491CDC +:10394000817100E085718AF807704FF4804738462E +:10395000FEF787F858B1BBF81411BBF8DC00B8F9D2 +:1039600006200B1A934202DA0844904209DC3846DA +:10397000FEF777F8E8B9B8F90610BBF816018142EE +:1039800017DABC48B838056045608560BA480560FC +:103990004560B748C08F60B1B6484A30007820B162 +:1039A000207810B1FFF74AFD03E0607808B100F01D +:1039B000B3FB9AF80600142817D16078B0B1AC4F69 +:1039C000F88F28B99AF807005F2801D100F0A4FB0E +:1039D0009BF81A01002808D0F88F002805D19AF822 +:1039E00007007D2801D100F097FB8FE09AF80700CF +:1039F000572809D00420FEF734F8E8B19AF80710E8 +:103A000050465A2921D017E09C494FF47A7008801B +:103A10004FF48070FEF725F808B101F07EFF042016 +:103A2000FEF70AF810B196490A2008800820FEF730 +:103A300003F808B9934805809AF807005D2817D065 +:103A40005B2817D05E2817D023E0818A19B18582C0 +:103A5000AAF816601DE0818C21B10021818419B182 +:103A6000022102E00121F9E703218AF8001010E0A9 +:103A7000012702E0022700E00327781E8BF8780375 +:103A800000210846FDF713FE3A4628210220FFF7E1 +:103A90007BFA774FF88F18B99AF807106F290ED074 +:103AA0009BF81A1121B118B99AF807007E2806D0A0 +:103AB0009AF80700972805D0A72808D008E0FFF754 +:103AC000BDFC05E070494FF4C870088000E0A673A3 +:103AD0009AF80700BB2806D0B72807D0BE2809D01F +:103AE000BD280AD012E0788D801C01E0788D801E00 +:103AF000788505E0388D801C01E0388D801E388582 +:103B000001210846FDF7D3FD8AF806500420FDF791 +:103B1000A8FF20B3BAF82420504632216AB1627857 +:103B20005AB1B8F90630BBF81621934205DD514A67 +:103B30004A3212780AB9418285844E4A4A32527C0E +:103B400032B1028B838A1A4309D1AAF8121006E017 +:103B5000818A21B1617811B98582AAF816600020A6 +:103B6000C64640F2A46700BF0EEB4001B1F9082041 +:103B700040F214518A4201DA012300E0002300EBF5 +:103B800040018B40A2F2155CBCF5C77F02D84FF014 +:103B9000010C01E04FF0000C01F101080CFA08FCE7 +:103BA00043EA0C03BA4201DD012200E00022891C35 +:103BB0008A40134343EA0903401C1FFA83F904288F +:103BC000D2DB2C4F00204A37294901EB4001C98F35 +:103BD00011EA090100D001213954401C1428F3DBFB +:103BE000787840B9224890F8AC0000EB8001BAF92F +:103BF0000E0081420ADA0220FDF71EFF30B1E078A4 +:103C000028B91D4805604560E67000E0E570B878A9 +:103C100038B1E570207928B91748056045602671EC +:103C200000E025713878B84600B92670E178102098 +:103C300009B9217909B1154901E01449091F086042 +:103C40000420FDF7F9FE70B198F80300474650B321 +:103C5000A07938BB0E48A67101680E48016006487D +:103C60000830C18818E02BE000007A4400C07F448F +:103C7000EC0700209C0A00203C010020800100206D +:103C8000AE010020B00100207E010020140C014094 +:103C90005C00002060000020FF48AAF81A100560B0 +:103CA000FE48056000E0A5714FF40050FDF7D9FE15 +:103CB00030B1387918B1E07B10B9E67300E0E573F4 +:103CC0000220FDF7B9FE18B90820FDF7B5FED0B106 +:103CD00098F80510404639B1617931B9F0496671FB +:103CE0000A88F0490A8000E06571817919B1617A2A +:103CF00011B9667200E0657298F8070018B1E848DB +:103D00000188AAF81E102020FDF796FEF0B3E07A95 +:103D1000E8B39AF80B005746052844D398F80A10E0 +:103D200059B1E07990BBE671DF4925723D72081FF9 +:103D300002F0F0FA0220787039E0E57198F80B0093 +:103D400030B3D94A143AB2F90000002800DC4042EE +:103D5000D649B1F8C01088421DDAB2F90200002835 +:103D600000DC4042884216DA207A78B9CE482672C2 +:103D70000C383D7200F1100102680A60406841F899 +:103D8000040FC948001D02F0C5FA02E00FE00AE086 +:103D900001E07E700BE02572387A40B98AF808603D +:103DA00002F05AFA03E0E57125728AF8015098F89A +:103DB0000C0008B1A67200E0A5729BF80500082867 +:103DC00001D00E2843D1657241E0DAF85C00574615 +:103DD000042801DD401FF865052838D2DFE800F02F +:103DE000030B151F2A000820FE65FDF725FE10B104 +:103DF00000F06DFC58BBF86D401CF8650420FDF721 +:103E00001BFE10B100F073FB08BBF86D401CF86599 +:103E10000420FDF711FE10B1FEF7E9F9B8B9F86D0D +:103E2000401CF8654FF48070FDF71BFE10B102F0E6 +:103E3000DFF90CE0F86D401CF8651020FDF7FCFD83 +:103E400008B100F0C6FC4FF40050FDF70AFE04F084 +:103E50002CF9CAF83400BBF80C20574612B1BB6DE0 +:103E6000C31A71D41044D946B865FEF757F9FFF765 +:103E7000B3F804F01AF97863398F411AB981B8633D +:103E80000820FDF7D9FD48B387491439B1F904205A +:103E900002F145008A2822D8607900B3804803885F +:103EA00080480088181A00B210F1B40F02DC00F547 +:103EB000B47000B2B42802DBA0F5B47000B299F976 +:103EC000EC305B42434318B2637B3BB1774B5B7A88 +:103ED00043431E2093FBF0F0101A888003E07048E3 +:103EE0000188704801800420FDF7A6FD58B3A07931 +:103EF00048B36E4991F8690038B36B48B7F91A2096 +:103F00001438B0F90630A3EB020CBCF1000F01DC51 +:103F1000A2EB030C91F868108C4509DDDFF878C13D +:103F20009342CCF800507E7200DD4942194409E00A +:103F3000797A21B15E490B685E490B607D72574901 +:103F400009881144C1803AE0E4E0FFE7DFF85881D6 +:103F5000B7F91A00A8F11408B8F906301A1A002A9D +:103F600001DD134600E0C31A91F868108B420FDDA3 +:103F7000B98B4FF4FA6C114409B291FBFCF34D4A32 +:103F80000CFB131115681D441560B9837E7207E0A0 +:103F9000797A29B146490A6846490A60BD837D722B +:103FA0003E490988084400B2A8F80600B9F8D010C4 +:103FB000B9F8D220963102F097FDA8F806003B4DE3 +:103FC00095F86A0050B1E07808B9207930B13648E8 +:103FD000394A1438C18812881144C1802020FDF765 +:103FE0002BFDE8B3E07908B9207AC8B3207BB8B3D9 +:103FF0002B4CB4F9000006F06BFE304E314606F053 +:10400000E5FD08F093F80090B4F9000006F060FEBA +:10401000314606F0DBFD07F0A3FC234C064695F87D +:10402000B900303CDFF898A0A4F11C0810B3A146F9 +:10403000B4F90200241DB4F90210401A01F01EFA6E +:1040400015F8B92F514202F04FFD61880844608095 +:10405000B9F90000B4F90010401A01F00FFA00E0BD +:104060004EE02A78514202F03FFD2188084400B218 +:10407000208001E0B4F9000006F02AFE8346009992 +:1040800006F0A4FD0546B4F9020006F021FE8146C3 +:10409000314606F09BFD15E028000020240000209A +:1040A000B0010020B201002058010020EC070020E0 +:1040B0005C000020600000200A00002035FA8E3CE1 +:1040C00000002041294606F07BFD5546514606F08A +:1040D000B3FD06F00BFEA8F80000444658463146F2 +:1040E00006F074FD06464846009906F06FFD31461D +:1040F00006F014FD294606F09FFD06F0F7FD6080EE +:10410000386C8047FEF7DFFCFEF7E9FBBDE8F84FAF +:10411000FEF739BCBDE8F88F03484178002901D08B +:1041200000214170704700008C0A00202DE9F843FF +:10413000FE4CFF4BFF490026B4F8EE209846A1F153 +:10414000100004F0FEFB08B101260EE0B4F8EE10FA +:10415000F84804F005FE40B9B4F8EE10F54803F055 +:1041600096FD10B9032004F073F8F34D5FF00007DB +:1041700094F8ED0006283CD2DFE800F00707192884 +:1041800033030220FDF765FC33E08DF800704FF437 +:104190004870E849ADF802001039684602F099FF0E +:1041A00008B10120287094F8ED00012821D06EB1EB +:1041B000E049B4F8EE204346A1F1100004F0C1FB41 +:1041C0000220287094F8ED0002281DD0D94810383C +:1041D00004F0C0FC28B10320287094F8ED000328F7 +:1041E00012D0D448103805F042FB10B104202870DA +:1041F0000AE0287840B994F8ED0010B184F8ED7029 +:10420000B6E70220FDF725FCCA48103004F0ABFEEB +:1042100038B9C848103003F003F810B90420FDF78E +:1042200018FC0220FDF708FC28B1C24994F8E3000D +:10423000103909688847BF4914F8E20F09688847B0 +:10424000A07803F007F910B90820FDF702FCBB487D +:104250006421B0F9262092FBF1F001FB102406B294 +:104260000820FDF7E9FBB64D90B1204606F030FD81 +:10427000B44906F0ABFC0446304606F029FD214661 +:1042800006F04CFCB04906F0A1FC2860BDE8F883BC +:104290002F60FBE770B50546A44890F8060106F0CC +:1042A00020FD0446284606F01CFDA84906F08EFCB9 +:1042B000A74906F0C1FC214606F088FC06F02FFD58 +:1042C00080B270BD70B500252C46002002F05EFE65 +:1042D00005440A2003F012FF641C202CF5D3C5F31B +:1042E0004F10FFF7D7FF914A022192F8073100BF24 +:1042F00003FB01F4844202D8491C0629F8D39548EF +:10430000017092F8080148439349088070BD2DE977 +:10431000F05FDFF82492914E884FB9F80220834C69 +:104320000025C2B38E4900204FF4C878424501D120 +:1043300041F8205051F8203036F910C0634441F85C +:10434000203026F8105004EB4003401CA3F8FA502C +:104350000328EBDB012A19D10868C83090FBF8F07C +:1043600024F8FA0F4868C83090FBF8F0608088683D +:10437000C83090FBF8F1B9F80600081AA0803D8516 +:104380000121FA3C7D850846FDF791F9B9F8021044 +:10439000491EA9F802100420FDF763FB002874D021 +:1043A000704BDFF894816E491A8808F120080C31AF +:1043B000A8F1180A322A05D0F2B300209B46322A0F +:1043C00014D015E034F8FA0FA8F800006088A8F8B7 +:1043D0000200A088A8F80400B7F828C0AAF800C016 +:1043E000B7F82AC0FA3CAAF802C0E6E741F8205024 +:1043F00051F8203036F910C0634441F8203026F8D7 +:10440000105004EB4003401CA3F8FA500328D6DBFD +:10441000012A1AD15448554B058001201880544B6D +:1044200002201870B8F8000024F8FA0FB8F802005B +:104430006080B8F8040000E00AE0A080BAF800301C +:104440003B85BAF80200FA3C7885521EABF8002092 +:1044500048480288012A18D105800A68322092FB58 +:10446000F0F224F8FA2F4A6892FBF0F26280896831 +:1044700091FBF0F1B9F80600081AA0803D850121F2 +:10448000FA3C7D850846FDF712F9308834F8FA1FAA +:10449000401A308070886188401A7080B088A18886 +:1044A000401AB080BDE8F09F224810B5103841682E +:1044B0002A488847BDE8104029E730B51E4C1F4AFE +:1044C000E06892F82F200146401C824200D1002073 +:1044D000294A1368224A183242F82130274952F8F3 +:1044E00020200D682B449A1A0A60E06030BD70B538 +:1044F0002348114C00682169411A01D5002070BD84 +:1045000020610C4D6069103578B128698047686872 +:10451000804728882169084420616A69194916483A +:10452000904700206061022070BD2DE070040020E3 +:10453000F00800206C0C00207C010020EC0700201B +:10454000300000208988883C0000204133335340EC +:1045500000F07F4568010020EE0000207A00002076 +:104560003C0B0020DA000020E0000020DC000020EE +:10457000C8000020DE000020A00000201C00002059 +:10458000FC000020A4000020A8688047E86880475D +:10459000FFF793FF0120606168882169084420616A +:1045A000012070BD2DE9F05FA24DA88800286AD0D7 +:1045B000DFF884820024A3464FF47A79A8F10C0630 +:1045C000A888484507D104EB840208EB820146F82D +:1045D00024B0C1F810B0994F56F8241037F91400E0 +:1045E000014446F8241006F073FB014604EB8402F4 +:1045F00008EB8200824600F0EFF827F814B0904FE5 +:1046000027F814B0A888012837D1DAF8100001285B +:1046100008DD401E06F05CFB0146DAF80C0006F0EF +:104620000BFB00E0002007F047FE8246854890F82B +:10463000F800A8B106F055FB514606F085FB0FD2F5 +:104640007D49A5F80490C8F810B0C1F824B0C1F8AD +:1046500038B0C6F808B0C6F804B0C6F800B00CE030 +:1046600056F82400012200F5FA7090FBF9F027F8C3 +:1046700014000F210A20FEF787FC641C032C9FDB2B +:10468000A888401EA8806D496D4A002031F810307E +:1046900032F810401B1B21F81030401C0328F5DBBA +:1046A00000E7654810B54C30416864488847BDE86C +:1046B000104077E710B564481024046002F019FF39 +:1046C0006148001F04605B490120487010BD2DE95E +:1046D000F0415E48574C0068A169411A02D500209C +:1046E000BDE8F0815A490844A0615A4802F0C9FE69 +:1046F000DFF864C14F4B00269CF80E005549514A23 +:1047000026339D1D88B1A069E061002002EB4007BF +:10471000A7F8006131F8107023F8107025F81070B8 +:10472000401C0328F2D38CF80E60607870B10888C2 +:10473000B2F80071C01B08804888B2F80271C01B33 +:1047400048808888B2F80471C01B8880E06998B3FB +:10475000A769381A414FB84218D23B480838026856 +:1047600082F008020260002031F9102033F9104075 +:10477000A24201DA23F8102035F91040A24201DDEF +:1047800025F81020401C0328EED315E00020E66138 +:1047900033F9101035F91040214402EB400401EBCD +:1047A000D17141F34F01401CA4F800110328EFD34D +:1047B00001210846FCF77BFF012091E710B501209D +:1047C00004F015FA1020FDF73FF925490020086094 +:1047D00010BD234804F05FBA2DE9F041044600699A +:1047E0000E46401C206101281FD006F071FA256892 +:1047F00080462946304606F0E3F90746414606F072 +:104800001BFA294606F08AF90546606029463046BB +:1048100006F0D6F90146384606F0D8F9A16806F048 +:104820007DF92560E060A0605AE7666000202660A0 +:10483000F9E700007C010020200C0020740000201B +:10484000A800002070040020140C0140FC0000208F +:10485000A0860100860000208C0A002080C3C901C8 +:10486000B000002070B5F34CF34EC1B20546A17004 +:10487000306805F01DF8E079A1784840E071C5F393 +:104880000721A170306805F013F8E079A17848405D +:10489000E071C5F30741A170306805F009F8E079CF +:1048A000A1784840E071290EA170306805F000F849 +:1048B000E079A1784840E07170BD70B5DD4CDE4E06 +:1048C000C1B20546E170306804F0F2FFE079E178AA +:1048D0004840E071C5F30721E170306804F0E8FF5B +:1048E000E079E1784840E07170BD10B50446D248E7 +:1048F0002146006804F0DCFFCE48C1796140C171F7 +:1049000010BDCC4ACD48117A405C491C11727047E9 +:1049100000B5FFF7F6FF0346FFF7F3FF03EB0020B8 +:1049200080B200BD10B5FFF7F3FF0446FFF7F0FFBC +:1049300004EB004010BD70B504460D462420FFF77F +:10494000D4FF4D20FFF7D1FF0CB1212000E03E2025 +:10495000FFF7CBFFB74C0020E0712846FFF7C5FFFB +:10496000607ABDE87040C0E701460020E3E70146F9 +:104970000120E0E7AF48C079B7E770B504460D46BF +:104980000846FFF7F1FF03E014F8010BFFF7ADFF56 +:104990002800A5F10105EDB2F6D170BD10B50446B1 +:1049A00003E000BFFFF7A1FF641C20780028F9D1C5 +:1049B00010BD2DE9F05FDFF87CB2DFF878920127B7 +:1049C0004FF0000A0BF10C0B00251AE09B4814383D +:1049D000405D00EB40010BEB8108D8F8040006F0C5 +:1049E0004EF806460FB1B2440AE0002406E000BFCC +:1049F000D8F80400005DFFF778FF641CB442F7DBD1 +:104A00006D1C99F800008542E0DB002F05D00AF00C +:104A1000FF00FFF7A9FF0027D6E7BDE8F09F70B5BC +:104A2000024603230021864803F0E8FC8249FF2266 +:104A3000086082481421143805F0DBFF7F4D002008 +:104A4000143D012428700220FCF7F6FF20B101205C +:104A500068700220A87003240420FCF7EDFF50B119 +:104A600003202855641C4FF40050FCF7FAFF10B1E6 +:104A700004202855641C0220FCF7DEFF18B908202A +:104A8000FCF7DAFF40B105202855641C06202855A4 +:104A9000641C07202855641C2020FCF7E2FF10B19D +:104AA00008202855641C4FF48070FCF7DAFF28B109 +:104AB0000A202855641C0B202855641C6148407945 +:104AC000082801D00E2802D10C202855641C0D2086 +:104AD0002855641C0420FCF7C4FF10B11120285590 +:104AE000641C132028555348641C047070BD2DE9C4 +:104AF000F05F504EDFF844B14FF00008717A514D2D +:104B0000514C524FC1464FF0010AABF1140B7829BA +:104B10007CD011DC3046A1F16401007814293FD229 +:104B2000DFE801F0FDFCFBFAF9F8F7F6F5F4F3F233 +:104B3000F1F0EFEEEDECEBEA4448D029407875D087 +:104B400018DCCB2973D00CDCC8292FD004DCA029B9 +:104B50006ED0A42924D1DBE3C9293BD0CA291FD1B7 +:104B600055E0CC2965D0CD297ED0CE297DD0CF2966 +:104B700016D1A7E0D62979D00ADC4FF00008D12958 +:104B800075D0D22974D0D32973D0D42908D1CCE1DF +:104B9000EF2918D0F0296DD0FA296CD0FE296BD0FE +:104BA0000020FFF7E4FEBDE8F05FE3E60024284DB7 +:104BB000FFF7AEFE25F81400641C082CF8D3002083 +:104BC000FFF7D2FEEFE7FFF7A3FE6085FFF7A0FE39 +:104BD0002085F4E7FFF795FEF872FFF792FE1D4976 +:104BE0000870FFF79FFE1C4C2060FFF79BFE606083 +:104BF000FFF78EFE19490880FFF78AFE18490880E2 +:104C00001848017841F002010170D8E773E10023F0 +:104C1000FFF777FEE5186870FFF773FEE872FFF79D +:104C200070FE5B1C68750A2BF2D3C8E725E324E00D +:104C30005EE330E0B4010020E0080020A80C002072 +:104C40000038014070040020EC0700208C0A00208E +:104C50009C0A0020D30000204C0100207601002097 +:104C600078010020640100200DE313E362E0D4E248 +:104C70006AE078E032E312E313E300255F4606E0E2 +:104C8000FFF746FE795D6D1C04EB4101C887307863 +:104C90008542F5D393E7FFF734FE04F81F0FFFF7C3 +:104CA00030FE6070FFF72DFE2071FFF72AFE607165 +:104CB000FFF727FEA071FFF724FEA070FFF721FE8B +:104CC000E0707CE7FFF724FEFFF722FEE93525F8C8 +:104CD000190CFFF727FEFFF71BFEA4F8AE00FFF745 +:104CE00017FEFFF71FFEFFF713FE00EB80004000EA +:104CF000E084FFF706FE13E0E7E16AE2C8E1E1E1E4 +:104D00005BE2EFE1CBE1B1E198E189E17FE166E1CE +:104D100053E135E126E120E1EAE0B6E03DE026E0BE +:104D20006877FFF7EEFDE877FFF7EBFDA877FFF771 +:104D3000E8FD44E70024FE4DFFF7EAFD25F81400E6 +:104D4000641C082CF8D32EE70028A3D1FFF7D9FD67 +:104D500085F87803022801D985F87883002100209E +:104D6000FCF7A5FC2BE7FFF7D3FDF24990E2072003 +:104D7000FFF7FAFDE620FFF7B8FD6879FFF7B5FD0C +:104D80000020FFF7B2FD95F81B0100B10820EA49A9 +:104D900050EA0100FFF766FD05E70B20FFF7E4FD91 +:104DA000E648008800B2FFF788FD02F0ACFE00B2D2 +:104DB000FFF783FD0220FCF73FFE04460420FCF7CA +:104DC0003BFE44EA40040820FCF736FE44EA800437 +:104DD0002020FCF731FE44EAC0041020FCF72CFE32 +:104DE00044EA0010FFF769FDF9783A79490041EA91 +:104DF0008201BA79002041EAC2017A79367841EA23 +:104E000042117A7AD44641EA8212CD49CB7942EAFC +:104E1000C3120B7A42EA03224B7A42EA4322FB791D +:104E200042EA83223B7A42EAC322BB7A42EA033255 +:104E30004B7B42EA43328B7B42EA83320B7C42EA71 +:104E400003420B7942EA03124B7C42EA43428B7CD9 +:104E5000C97C42EA834242EAC14479785F460C4306 +:104E6000002108E07B5C0CFA03F3234202D00CFA29 +:104E700001F21043491CB142F4D3FFF7F3FC95F85B +:104E8000780300BFFFF731FD8DE61220FFF76CFDC0 +:104E9000AC48AD4D4FF000040088B0F5806F0BD9E1 +:104EA00035F91400C11700EB5170C010FFF705FD74 +:104EB000641C032CF4D306E035F91400FFF7FDFC65 +:104EC000641C032CF8D3A14D002400BF35F9140055 +:104ED000FFF7F3FC641C032CF8D39D4D002400BFA6 +:104EE00035F91400FFF7E9FC641C032CF8D35AE6EB +:104EF0001021984833E03820FFF736FD5FF00005B9 +:104F000004EBC50636F96C0FFFF7D7FCB6F90200C3 +:104F1000FFF7D3FCB6F90400FFF7CFFCB079FFF739 +:104F2000E4FC6D1C082DEBD33DE60020FFF71CFDD3 +:104F30005FF00005FFF7ECFC04EBC50626F86C0FEC +:104F4000FFF7E6FC7080FFF7E3FCB080FFF7D9FCC9 +:104F50006D1CB071082DEDD325E610217E48FFF7BA +:104F60000CFD20E61020FFF7FFFC7C4D002400BF65 +:104F700035F91400FFF7A1FC641C082CF8D312E6E5 +:104F80001020FFF7F1FCF87AFFF7AFFC74480078C7 +:104F9000FFF7ABFC734C2068FFF764FC6068FFF719 +:104FA00061FC7148008800B2FFF787FC6F480088F9 +:104FB00000B2FFF782FC6E483DE00520FFF7D4FC0D +:104FC0006C48008800B2FFF778FC6B48B0F900002D +:104FD000FFF773FC6948007800F0010052E70820F1 +:104FE000FFF7C2FC664D002435F91400FFF765FC9D +:104FF000641C022CF8D36348B0F90000FFF75DFC95 +:105000006148B0F9000000BFFFF757FCCBE5062070 +:10501000FFF7AAFC5D480068FFF724FC5C480AE043 +:105020000520FFF7A1FC5B480078FFF75EFC00203D +:10503000FFF743FC5848008800B2E5E70720FFF778 +:1050400093FC14F81F0FFFF750FC6078FFF74DFC3E +:105050002079FFF74AFC6079FFF747FCA079FFF75A +:1050600044FCA078FFF741FCE0780BE71E20FFF737 +:105070007BFC002566197078FFF737FCF07AFFF7A4 +:1050800034FC707DFFF731FC6D1C0A2DF2D38AE5EC +:105090002F20FFF769FC4148FFF780FC83E54006BD +:1050A000000EFFF761FC00255F4607E0785D04EB2A +:1050B0004000B0F93E00FFF700FC6D1C30788542DF +:1050C000F4D370E5FFF775FC6DE5FFF74DFC0024A8 +:1050D0005D4603E0285DFFF708FC641C30788442DD +:1050E000F8D360E51620FFF73FFC0020FFF7E5FB53 +:1050F00035F9D00FFFF7E1FBB5F90200FFF7DDFB53 +:10510000B5F90400FFF7D9FBB4F9AE00FFF7D5FB02 +:105110000020FFF7D2FB0020FFF7A4FBB4F9260024 +:105120000A2190FBF1F000B2FFF7C7FB38E0000066 +:105130000C090020B201002004000080D4000020EF +:10514000E60A002082010020800000206800002084 +:1051500086000020B8000020F40800209C0A0020EF +:10516000D30000204C0100207601002078010020AF +:1051700066010020720100207401002064010020FB +:1051800034000020B0010020E60000205C00002078 +:105190002C000020D2000020EA0000205CD1000892 +:1051A00095F83600FFF7A1FB95F83800FFF79DFB57 +:1051B00095F83700FFF799FB2DE00820FFF7D4FBA7 +:1051C0000024601CC0B2FFF790FB641C082CF8D3CD +:1051D000E9E4FFF796FB04461220FFF7C5FB14B184 +:1051E000102C02D004E0934800E09348D0E90089F5 +:1051F0002046FFF77AFB4046FFF734FB4846FFF7AF +:1052000031FB8E480068FFF72DFB0020FFF755FBB0 +:105210000020FFF752FB002034E6FFF772FB064642 +:10522000FFF780FB0546FFF77DFB8446FFF77AFB1F +:105230000446FFF76DFBFFF76BFBFFF762FB86B1E0 +:10524000102E7FF4C6AC7C49C1E9005C0CB17B48F0 +:1052500004607B4A0220091D1070774801F05AF85B +:10526000ADE47448002CC0E9005C87F8078087F83B +:105270000CA0F5D071480460A1E40028F0D1012011 +:10528000FCF7CBFB9BE40028EAD16E494FF4C870D1 +:10529000088094E40028E3D187F80EA08FE4012170 +:1052A0005DE50820FFF760FB6748694A694D0168C2 +:1052B00066481268B1FBF0F1B2FBF0F000EB40027F +:1052C000C2EBC01001EBC000E880002435F91400E7 +:1052D000FFF7F3FA641C042CF8D364E40420FFF70E +:1052E00043FBB4F92A00FFF7E8FAB4F928008BE68B +:1052F0000C20FFF739FB58480068FFF7B3FA56480F +:10530000001D0068FFF7AEFA53480830006841E519 +:10531000524D29780AEB8100C0B2FFF725FB2878AF +:10532000FFF7E3FA00244E4E4E4FDFF83C81DFF8E2 +:105330003C910EE0305DFFF7D8FA385DFFF7D5FA03 +:1053400018F80400FFF7D1FA19F80400FFF7CDFAB6 +:10535000641C28788442EDD325E470B5444C454E56 +:105360000025607810B3BDE87040FBF755BE30688B +:1053700004F0B1FAA17951B101291CD002291FD042 +:10538000032923D0042929D005293FD12CE0242842 +:1053900003D00021A17149B901E00121FAE72328D6 +:1053A00002D0522832D102E0FBF736FE2EE0012077 +:1053B00002F06FFF2AE04D2804D10220A07125E001 +:1053C0003C2801D00020F9E70320F7E740281CD84B +:1053D000607125712572E0710420EFE76072E17958 +:1053E0004140E1710520E9E721796279914207D2D4 +:1053F000E2794240E271204A5054491C217105E093 +:10540000E179814201D1FFF772FBA571306804F0A8 +:105410005FFA0028ABD16078002809D14FF4006012 +:10542000FCF71FFB002803D0BDE8704001F02DBA47 +:1054300070BD0000540100205C01002060000020CD +:10544000C90000207E0100200804002040420F0017 +:105450000C0400206A010020E8F7FF1F7A010020F9 +:10546000FA0A00200A0B00201A0B00202A0B002049 +:10547000B4010020E0080020A80C002044F2506194 +:10548000884201DDA0EB4100FE49884202DA48F67D +:10549000A041084470472DE9F047064650689946F8 +:1054A00014460D46301A05F013FC296805F0C4FBBC +:1054B0002061A768394605F083FB8046F24890F8E2 +:1054C000B80005F00EFCF14905F080FB01464FF0F5 +:1054D0007E5005F0B1FB2D68294605F01FFB014603 +:1054E000284605F0A9FB414605F070FB394605F05A +:1054F00015FB2061C4E901600146D9F8080005F0F8 +:1055000065FBBDE8F04705F0F1BB2DE9F0411D4614 +:1055100014460E4605F0DCFB696805F057FB316860 +:1055200005F054FB216805F0F9FA2060ED680746A4 +:10553000284605F0DBFB064685F0004005F0D6FB6B +:105540000546384605F0D2FB3246294601F0CCFA32 +:1055500005F0BEFB2060BDE8F04105F0C7BB70B5AB +:10556000CB4CD4E90D01401AFFF788FF0028D4E99D +:105570000D01A0EB010002DDFFF780FF02E0FFF765 +:105580007DFF404241F29411884228DAD4E90D01AE +:10559000401A05F09DFBBF4905F018FB0646E06B7D +:1055A00005F09FFB0546304606F0C0FD294605F094 +:1055B0000DFB05F09BFB00B240F6B8322082514251 +:1055C00001F092FA616B084448F6A0416064884299 +:1055D00000DD401A002800DA0844606470BD606B8A +:1055E000FBE72DE9FE4F0546FFF7B9FFA84842F259 +:1055F0002831406C081A05F06BFBA64905F0E6FA65 +:10560000044606F0ADF90190204606F08FFD0090AB +:105610000024284605F05CFBDFF874A2DFF87892DE +:10562000DFF878B20AF1300A029099481A3030F95E +:10563000140005F04DFB05465DF82410029805F0B6 +:10564000C5FA294605F0BCFA05F050FB00B24FF44C +:105650007A7255462AF81400514201F045FA8E49F3 +:1056600000B225F81400603900F080FE04EB8406D7 +:10567000894B8749074609EB8602904635F91400A5 +:10568000603B2831FFF741FF834B81490744424685 +:1056900035F91400603B2831FFF7FDFE384400B2B5 +:1056A00040F6B8325D462BF81400514201F01CFA66 +:1056B00025F81400784859F826102838641C40F85A +:1056C0002610022CB1DBBDE8FE8F2DE9F05F704E95 +:1056D0000024DFF8C4915036DFF8C0B1A6F1360AD5 +:1056E000A9F128096C4956F82400803900F03EFEE3 +:1056F0003AF81410664F401A3037674900B227F85D +:105700001400703900F032FE054637F9140056F8DF +:10571000241004EB840708445F4B5D4909EB8702C2 +:105720009046703B2831FFF7F0FE28445A4B584909 +:105730002BF814005D46424656F82400703B283191 +:10574000FFF7A9FE4FF4FA62514201F0CDF93AF9A0 +:1057500014103131622900D8002035F8141040F6B9 +:10576000B832084400B225F81400514201F0BCF9E7 +:1057700025F81400484859F82710641C40F82710F1 +:10578000022CAFDBBDE8F09F70B5054608681968CC +:105790001446401A05F09CFA3D49C96A05F016FA0C +:1057A00005F0A4FA01463A48503041602968226861 +:1057B000891A016070BD2DE9F0410F46DDE90685CB +:1057C000116800681E46081A05F082FA044630681F +:1057D0003968401A05F07CFA2D49C96A05F0F6F9D6 +:1057E0000646014605F0F2F907462146084605F04F +:1057F000EDF9394605F092F906F05EFD284905F00D +:10580000E5F905F08CFAC8F8000084F00040314654 +:1058100005F07CFF234905F0D9F9234905F07EF90D +:1058200005F064FA2860002803DA48F6A04108442D +:105830002860BDE8F0812DE9F0471C48144CD0E900 +:105840000056617804F1480991B34FF07E50A16A87 +:1058500005F0F2F98246D9F80400301A05F038FA5A +:10586000E16A05F0B3F9514605F0B0F905F03EFAEA +:1058700007B2D9F8000004F11A08281A05F028FA2E +:10588000514616E0B0B9FFFFEC070020DB0FC9401E +:10589000BC020020D30237398C0D002028010020E3 +:1058A0002C7D8E3FA00CB34500A00C464C0100207F +:1058B0001AE005F08BF905F019FA01B204F12400A1 +:1058C000B0F902203A4402EBD27242F34F02A8F838 +:1058D0000220B0F90030194401EBD17141F34F01BE +:1058E000A8F800104280018001206070C9E90056CC +:1058F000BDE8F08710B5044605F0EAF9002C01DC9C +:1059000080F00040F74905F097F9F74905F05EF996 +:1059100006F026F8F549C86210BD10B5F44CE07ADF +:10592000002811D0F348007805280DD3F249F34A36 +:105930000868106049685160FFF7DCFFF048EB49E8 +:10594000008888820120207310BD2DE9F043E749CB +:10595000EC48E74B8E7A012502790024062E29D0E7 +:1059600004DC022E09D0032E04D116E0122E33D00F +:10597000302E3DD00020BDE8F083DF4A46685660F7 +:105980008668166000694FF47A7290FBF2F0DE4A86 +:105990001080C87AD8724D7351E04079C00701D0A9 +:1059A000032A03D00020C87210B148E00120FAE7B2 +:1059B000DC7244E0C27AD20702D0827A032A03D092 +:1059C0000022CA7212B102E00122FAE7DC72C94A6F +:1059D00090F82F00107032E0CC4B828A1A808069D8 +:1059E00042F2107290FBF2F0C94A10808D7326E0EB +:1059F000C84B102A1A7001D910221A700022C64E04 +:105A0000C64FDFF81CC3DFF81C931D7815E000BFFC +:105A100002EB420300EB830393F8088006F8028050 +:105A200093F8098007F8028093F80B800CF8028045 +:105A300093F80C8009F80280521CAA42E8DB487BEC +:105A40008A7B104097D04C738C73012093E72DE92B +:105A5000F041A64900240A4691F809E092F807C0EF +:105A6000157A0CEB0003D78ADEB22246BEF1090F8D +:105A700051D2DFE80EF008050F151C23334349000F +:105A8000622803D04A72B52802D044E0022033E0F5 +:105A9000012031E003224A720873C87108723AE0AB +:105AA00004224A72CE7172190A72887233E005229A +:105AB0004A72CE7172190A72C8822CE006234B72A8 +:105AC000731907EB0020CE7180B20B72C882B0F55B +:105AD000007F01D9CA824A720A831CE0CE71721912 +:105AE0000A720A8BC82A01D2864B9854521C90B273 +:105AF0000883B8420FD1072048720CE008234B728C +:105B0000844508D04A7206E04A72854203D1FFF705 +:105B10001CFF00B1012420468BE670B5034600202F +:105B20000246054611E02E2C04D1521C00290FD04C +:105B300054181D559C5C00EB80004000A4F1300619 +:105B4000092E01D830382044521C9C5C002CEAD12C +:105B500070BD2DE9F04100268046354637460446A3 +:105B600004F008FF016800E0641C2078085C20282D +:105B7000FAD0404609E01EB106EB86025206160E28 +:105B800010F8012B303E3244D6B2221A022AF2DC3F +:105B900009E01DB105EB85025206150E10F8012B28 +:105BA000303D2A44D5B28442F3D820782E280ED135 +:105BB000641C002007EB8702570022788B5C202BA7 +:105BC00002D1303F1744641C401C0428F2DB5648C5 +:105BD0000621454307EBC70000EB071005EB8000EB +:105BE000B0FBF1F051494E4300EBC61021E62DE920 +:105BF000F04700273D4C0546242815D0414E20464D +:105C0000F43EC0782C2D13D02A2D11D021460D2D15 +:105C1000497964D00A2D62D00F2802D23554401C35 +:105C2000E07000295CD0BAE0A770E7702771B6E099 +:105C30003754A0784FF0010928B1A179012921D06A +:105C400002294ED0A2E0A7713078472807D170789A +:105C5000502804D1B078472802D0522809D095E0C6 +:105C6000F078472804D13079412801D184F8069092 +:105C70008CE0F0784D2804D13079432801D10220FE +:105C8000A07183E0DFF8708002280CD003280FD0C9 +:105C9000042816D0052819D0062849D0072850D046 +:105CA000092855D072E01748F438FFF752FF05E095 +:105CB000307853286AD1D8F800004042C8F8000074 +:105CC00064E01048F438FFF744FF05E030785728C7 +:105CD0005CD1D8F804004042C8F8040056E063E004 +:105CE0005AE03BE08096184B35FA8E3CBC0200200F +:105CF0008C0A0020D30000204C0100205401002019 +:105D0000B0010020DC0D0020760100207801002089 +:105D1000660100207A010020FA0A00200A0B002008 +:105D20001A0B00202A0B002040420F002D310100E9 +:105D30003078302801D9012000E00020F849C872ED +:105D400024E00021F748FFF7E8FEF74908701DE05E +:105D50000021F448FFF7E1FEF44916E0072802D0DD +:105D600008280DD012E00121EE48FFF7D6FE41F2DF +:105D7000184148434FF47A71B0FBF1F0EC4904E06C +:105D80000121E848FFF7C9FEEA490880A078401CD5 +:105D9000A070E7702A2D04D020796840207100207F +:105DA000A6E584F80590FAE70029F8D0307800F0ED +:105DB0000BFB0501707800F007FB28442179C0B285 +:105DC00088426771EBD1A0790128E8D190E52DE9EF +:105DD000FF5FD949C0B291F81D1119B1012904D052 +:105DE00002297CD1FFF703FF01E0FFF730FE002816 +:105DF00075D0CC4C1034A068E06002F070F9A0605F +:105E00002020FBF721FECD484FF0000B017801293F +:105E100010D001210170C248C17A00295FD0C24967 +:105E2000097805295BD38246407830B19AF80C1086 +:105E300031B108E080F800B0EDE78AF80CB002E07C +:105E400008B1FFF76AFDBE4805218E460278BE4CB8 +:105E5000521CB2FBF1F301FB1322BA49027000207D +:105E600091F90090B64954F820306831B44D41F8AA +:105E70002030B649783593FBF1F145F82010B44D48 +:105E800000EB80074D4303EBC51342F2107593FB03 +:105E9000F5F5AEB2AA4D403525F81060A14DCC35D0 +:105EA00005EB8707A64D57F822C0603555F82080CE +:105EB00047F82230A8EB0C0C634445F8203093FBE4 +:105EC000FEF3A34D6D42694303EBC1119C4B70334C +:105ED000B9F1010F43F8201007D1B61E00E080E0B1 +:105EE000B6F5797F01D844F82010401C0228B9DBB0 +:105EF00002F0F5F8924D296A401A04F0F2FE954935 +:105F000004F09AFEA86202F0EAF82862A86A4FF04C +:105F10007E51884200DB0846A86203A902A88E4B86 +:105F2000CDE900011A1F211D8748FFF744FC0298A4 +:105F30006426B0FBF6F08949894A574608800398E1 +:105F400090FBF6F010809AF80C0018B9A1F800B098 +:105F5000A2F800B0FFF76FFC387A10B9F879002882 +:105F60003FD07749343101F1080000F11C07CDE939 +:105F700000013B1D3A46211D7348FFF71CFC231D01 +:105F8000714A391D3846FFF7FFFB6E4C94F900004B +:105F9000012828D0022824D1724F0121B7F9BE0070 +:105FA00000F0EFF9FFF71DFB97F8BA006E4A18B141 +:105FB000686C90FBF6F01080B7F8B600E96B884289 +:105FC0000BD2D5E90D01401AFFF758FA002800DC82 +:105FD000404242F21071884203DD01202070A88AFD +:105FE0001080BDE8FF9FFFF770FBFAE72DE9F0474F +:105FF0005C4C607904F075FEDFF87091494604F05E +:106000001BFE484D24352860E07B04F06AFE4946BB +:1060100004F012FE564EEE606860A07904F061FE56 +:10602000544F394604F008FE10352860207C04F0F7 +:1060300058FE494604F000FE6860A07E04F051FE60 +:10604000DFF81081414604F0F7FDC5E90206E0796A +:1060500004F047FE394604F0EFFD10352860607CFF +:1060600004F03FFE494604F0E7FD6860E07E04F07E +:1060700038FE414604F0E0FDC5E9020638E470B59B +:1060800006460325002000F06CF94FF48070FBF702 +:10609000E8FC00281FD0234C1034667002F01FF873 +:1060A000A06000206060244890F81D0100B901251F +:1060B000FFF79CFF304906EB46002B4651F82020A5 +:1060C0002E492F4802F09AF92E494860BDE87040E9 +:1060D000012000F046B970BD2DE9F041164F294D61 +:1060E000104C97F81D11244E6868103411B1012925 +:1060F0007BD10BE0617801EB410156F8211003F0F0 +:10610000EDFBBDE8F041032000F02BB903F0E9FB03 +:1061100028B120780128206937D0A8B356E064E080 +:106120008C0A0020E80C0020D3000020760100201B +:106130007801002066010020700400206401002026 +:10614000BC020020C90000204C010020809698006D +:10615000D3CEFEFF00007A445801002072010020D7 +:1061600074010020EC070020B20100200000C842AA +:106170000000FA44000020418CD10008CF5D0008E7 +:1061800000440040E008002018E0052811D200EB90 +:10619000400056F82010686803F0A0FB97F91E0134 +:1061A00000EB400006EB80004168686803F083FB69 +:1061B00014E097F81E016070022014E0607800EB94 +:1061C000400056F82010686803F088FB20698C288E +:1061D00008D28449095C686803F06AFB2069401CA6 +:1061E000206102E0032000F0BCF80020606093E42E +:1061F00010B57D4C207805282DD2DFE800F02C0367 +:10620000031C0600BDE8104066E760680521401CDD +:1062100060606078401CC0B2B0FBF1F201FB12007C +:10622000607001F05CFF7149A06000200870704947 +:10623000C87201200BE001F052FFA168401A40F63D +:10624000C411884207D92020FBF703FC0420BDE8D5 +:10625000104000F086B810BD2DE9F05FDFF888A18E +:106260000024644FDFF89081DFF890910AF1440A2E +:1062700025460AF1280B00BF27F8145028F81450BF +:1062800004EB840629F814500AEB860000F0A5F808 +:106290000BEB860000F0A1F85348943000EB860029 +:1062A00000F09BF8641C022CE6DBBDE8F09F2DE9B2 +:1062B000F0414D480078032802D04FF0FF302BE426 +:1062C0004F4C504D002061684FF00808C862C5F877 +:1062D000008010262E602F1D606803F0F9FA50B17F +:1062E000C7F80080606803F0F6FA0146206803F002 +:1062F000DFFAC5F80080206803F0EAFA0028EBD046 +:106300003E60206803F0E7FA0146606803F0D0FAC7 +:106310002E60E1E77CB53C4C026822600968616050 +:106320000068FFF7E7FAA4F1240101F10800374EF5 +:10633000CDE90001231D2246311D3046FFF73BFA0F +:10634000A4F15805331D686B68643246211D204650 +:10635000FFF71AFA686BA8632D48B0F8BC00688292 +:106360007CBD2149087000200861704710B50C46BB +:1063700004F0AEFC216804F029FCBDE8104004F0F4 +:10638000B5BC70B5204C583CE26B21B1B0EB520F5C +:106390000BD3500809E0904200D310461C4900B2CC +:1063A000B1F8BC10814200DB0846B4F9125000B2CB +:1063B000A84208DD1749A06A04F008FC04F096FC26 +:1063C000284400B2608270BD3038C0B2092801D9BB +:1063D000C01FC0B200F00F00704700210160416093 +:1063E00081607047C8D10008F80C0020D30000205D +:1063F0008C0A00200C0100202C0100202801002024 +:10640000E0080020100C0140140300204C01002083 +:10641000EC0700200000C842F0B5404A404C11781B +:10642000E9B192F805C01779032104F11C035E1845 +:1064300016F8015CFD4005F00F05072D09D213F891 +:1064400001E016F8016C06EA0C060EEB062644F88D +:106450002560891CC9B21029E9D300211170314986 +:1064600007280ED2937863B151782E4A104490F8E1 +:106470000A0149B154F820004FF4777101EB500044 +:1064800006E0B1F81401F0BD34F8200000F5777093 +:1064900080B2F0BD70B5214C01260546A67001F012 +:1064A00004FEA168421AC4E9020241F288300021C8 +:1064B000824200D9E1701A4AE0781C3215540F2844 +:1064C00002D0401CE07070BD17482670018070BD7E +:1064D00070B504461348114990F81221032007258E +:1064E0002AB1012A08D108714D71012003E002226E +:1064F0000A7148710020487001234FF4E1320B49C2 +:106500000B4801F07BFF01460A48C1600CB10A4903 +:106510002160457470BD0148007870473C0300203D +:10652000A40E002070040020D6000020956400080E +:1065300000440040E00800201964000870B57C4C5D +:1065400006460125207880B901F0C9FDA1683231E5 +:10655000884207D32570012001F0DBFD01F0BFFD6B +:10656000A06070BD20780028FBD001F0B8FDA168C4 +:1065700031448842F5D30020207001F0CAFD01F0BB +:10658000AEFD6C49A060087808B1401E08706570C7 +:1065900070BDF8B5664D8DF800008DF801108DF8CE +:1065A00002208DF80330A8791DF8001044292DD061 +:1065B0004C2929D04D2925D04E292AD03224002615 +:1065C000032806D274B12046FFF7B8FFA879032844 +:1065D00008D301F084FDA968001B884202D9554800 +:1065E000AE7106706878012801D0002C09D1A87915 +:1065F000032801D2401CA8716E702E70002001F09B +:1066000088FDF8BD6424DAE7C824D8E74FF4FA64BB +:10661000D5E70024D3E72DE9F047DFF81CA10546B4 +:10662000434C9AF80D004FF00109002610B184F890 +:10663000029000E0A6704FF40070FBF712FA3F4F93 +:1066400018B33F493F484FF0020C91F8AC30B0F915 +:10665000000003EB830282420FDA97F80180B8F161 +:10666000000F0AD084F8049091F8AD10194401EBA2 +:106670008101814201DA84F804C0824203DA797828 +:1066800009B984F804C000B926712020FBF7D4F9B9 +:1066900040B19AF80A1011B99AF80B0008B1F87ACB +:1066A000A8B1E6702079022814D0012817D0E0782C +:1066B000012817D0A078012817D0042D19D0022D59 +:1066C0001ED0012D1ED0607901281ED022E084F852 +:1066D0000390E7E74E22442311464C200DE04D2362 +:1066E0004C2208E04D234E2201E04D23532253213A +:1066F00002E044234D224D215320BDE8F04748E7F6 +:10670000442305E044234E22F5E7787810B14E2368 +:106710004D22ECE70748007818B1BDE8F047322079 +:106720000CE72670BDE8F047002001F0F2BC000045 +:106730004C030020C8000020E60A00208C0A00203C +:10674000EC070020D600002010B5D84C5E28A268C7 +:1067500007D05D280CD001461046BDE8104003F07C +:10676000A7B85D21104603F0A3F83E21A068F4E726 +:106770005D21104603F09CF83D21A068EDE72DE96E +:10678000F041132000F04AF9C94C2068002800DCD1 +:106790004042C84D90FBF5F000B200F051F91B20CB +:1067A00000F03CF92068002800DC40420A2690FBFB +:1067B000F6F042F2107790FBF7F107FB110000B200 +:1067C00000F03EF9232000F029F92068002801DAC2 +:1067D000532000E04E2000F033F9122000F01EF9A3 +:1067E0006068002800DC404290FBF5F000B200F049 +:1067F00027F91A2000F012F96068002800DC4042F6 +:1068000090FBF6F090FBF7F107FB110000B200F0EF +:1068100017F9222000F002F96068002801DA5720F9 +:1068200000E04520BDE8F04100F00AB910B54FF492 +:106830000040FBF716F9A04A9C4920B192F82901C3 +:10684000012806D002E0002082F82901086888604B +:1068500010BD9A48FBE770B5974890F8291111B917 +:10686000974A52780AB1012400E00024954D2A7815 +:10687000944209D039B914B14FF4165001E0D0F860 +:106880002001FEF7CCF82C7070BD2DE9F0478A4846 +:1068900090F8290118B98A48407800287ED08348AA +:1068A000806803F015F8002878D101F018FC854DB8 +:1068B0006968401A7D2871D301F011FC686068781E +:1068C000814F401CDFF80482DFF8049268700024D6 +:1068D00004F12400C0B200F0A1F8388804F001FAF5 +:1068E000064638F9140004F0F3F9314604F0A4F92F +:1068F000494604F06BF904F0F9F900B200F0A0F891 +:10690000641C032CE4DB00F096F868784FF0640414 +:10691000800724D1102000F081F86E4E306890FB83 +:10692000F4F000B200F08CF8212000F077F8306825 +:1069300090FBF4F104FB110000B200F081F8142088 +:1069400000F06CF86448B0F9000000F079F81C2001 +:1069500000F064F8002000F073F800F06CF868783C +:10696000400735D1022000F059F85C484FF00A0882 +:10697000B0F9001091FBF8F000B200F061F80220CD +:10698000FBF76FF8E0B100F065F855486E2100782C +:1069900048431521B0FBF1F63A2000E03CE000F05E +:1069A0003DF8B6FBF4F738B200F04AF83B2000F0AF +:1069B00035F804FB1760401DB0FBF8F000F040F81C +:1069C0002020FBF739F808B1FFF7D9FE00F033F8C3 +:1069D0006878282820D10020687001F080FB4FF4EF +:1069E0007A71B0FBF1F43C25B4FBF5F6B6FBF5F09B +:1069F00005FB1067172000F011F8380200B200F014 +:106A00001FF8182000F00AF805FB164000F018F8EF +:106A1000BDE8F04700F00FB8BDE8F08770B5234C33 +:106A200005465E21A06802F043FF2946A068BDE844 +:106A3000704002F03DBF1D485E21806802F038BF03 +:106A400010B50446C0B2FFF77FFEC4F30720BDE8CF +:106A5000104079E670B52248224E40F634020078A4 +:106A60003178184DB0FBF1F050432A22B0FBF2F020 +:106A70006A88B2FBF1F301FB13214FF6FF7202EAC1 +:106A8000011141EA0024C0F3032004430620FFF76C +:106A9000C5FF20B2FFF7D4FF68883178401C80B270 +:106AA000B0FBF1F201FB1200688070BDE00800202D +:106AB0004C010020A086010070040020FC1400207E +:106AC0008C0A002058030020820100208000002052 +:106AD00000007A4420000020B0010020E8000020DF +:106AE000D200002068010020884201DA0846704781 +:106AF0009042FCDD104670472DE9FE4F97499748BC +:106B0000E831B0F9E600B1F90050B1F9024010B92E +:106B10000DB9002C7ED0924A0021117004F0D8F8F3 +:106B2000904F394604F052F8DFF83C82414604F0B9 +:106B300083F80646284604F0CBF8394604F046F8B8 +:106B4000414604F079F80546204604F0C1F839467C +:106B500004F03CF8414604F06FF80746304604F074 +:106B6000FFFE0290304605F0E1FA0190284604F05D +:106B7000F7FE0646284605F0D9FA0546384604F0E1 +:106B8000EFFE0446384605F0D1FA009020460299FF +:106B900004F01CF881463146204604F017F8804680 +:106BA0000299009804F012F883462146019804F0F7 +:106BB0000DF88246DDE9001004F008F86B4C07463A +:106BC00086F00040C4F80080009903F0FFFFC4E99C +:106BD00001052946504603F0F9FF594603F09EFF90 +:106BE000E0602946384603F0F1FF494603F0EBFF29 +:106BF00020610198314680F0004003F0E7FF6061BA +:106C00002946484603F0E2FF394603F0DCFF2946F7 +:106C1000A06100E00BE0584603F0D8FF514603F0B6 +:106C20007DFFE0613046029903F0D0FF2062BDE8AD +:106C3000FE8F2DE9F0470546B0F90080B0F90260FB +:106C4000B0F9040004F044F8484C8246A16903F00E +:106C5000BDFF0746304604F03BF88146E16803F08B +:106C6000B5FF0646404604F033F88046216803F03D +:106C7000ADFF314603F052FF394603F04FFF04F0F9 +:106C80002FFF28805046E16903F0A0FF07464846E1 +:106C9000216903F09BFF06464046616803F096FFBA +:106CA000314603F03BFF394603F038FF04F018FF8C +:106CB00068805046216A03F089FF074648466169AB +:106CC00003F084FF06464046A16803F07FFF31468B +:106CD00003F024FF394603F021FF04F001FFA880F0 +:106CE000BDE8F087092A11D2DFE802F01005091685 +:106CF0001C21262A2E0002880A80428803E042884E +:106D00000A8002880CE04A808088888014480078D5 +:106D1000002822D108468CE7028852420A80428825 +:106D20005242F0E7428852420A800288EBE702882A +:106D300052420A8042880CE042880A80028808E0B9 +:106D400002880A80428803E0428852420A80028810 +:106D500052424A8080884042D7E770477004002042 +:106D600060030020DB0F494000003443D00E0020B8 +:106D700044490844444990F80A0151F820004FF46E +:106D8000777101EB500080B2704710B5044601F0F6 +:106D90008CF93E4902464868131A0020B3F57A6F11 +:106DA00000D948704A604A780AB90F2C0AD1087095 +:106DB00032B1354B20331344182A03F8014C02D06A +:106DC000521C4A7010BD304A2032D27D0AB90122CD +:106DD0000A70487010BD10B504462A4800212A4B9D +:106DE000B0F814014200A2F5F76200BF43F8212079 +:106DF000491C0829FADB0123254A2649264801F0C7 +:106E0000FDFA01462548C1600CB1254921600821E1 +:106E1000417410BD1D4B10B5187840B11A484FF0A1 +:106E200000022030817DC908C90702D01A700020F5 +:106E300010BD1C49401C0A8030F8011CC1F30A0433 +:106E400011490C600488C4F3CA044C600468C4F39C +:106E50008A348C60B0F80340C4F34A04CC60848860 +:106E6000C4F30A140C614468C4F3CA344C61B0F82A +:106E70000740C4F38A048C6100894009C8611A7014 +:106E8000012010BD70040020F40E002064030020D7 +:106E9000A08601008B6D000800440040E00800203F +:106EA000716D0008D60000202DE9F04106460078FB +:106EB00090B008B1012500E00025DFF8D8804046F9 +:106EC00002F0D0FE3448009000243448CDE901049B +:106ED000012725B10220CDE90304802002E0CDE99D +:106EE0000374002005904FF4807006908000079096 +:106EF000202008900002CDE909046946404602F0CE +:106F00001EFF0121404602F044FF8DF830500B94E3 +:106F10008DF831704FF46020CDE90D040DB10220E1 +:106F200000E001201C4C8DF83C004C3C0BA9204695 +:106F300002F004FE032301220421204602F053FE46 +:106F40002DB1317803230222204602F04CFE0121AC +:106F5000204602F01CFE0121204602F00EFE2046D3 +:106F600002F01FFE204602F021FE0028FAD1204642 +:106F700002F023FE204602F025FE0028FAD101216E +:106F8000204602F026FE10B0BDE8F081034931F83A +:106F900010007047080002404C2401406C030020A0 +:106FA0002DE9FF47DFF86C81814698F80000D0B3E7 +:106FB00000273E463D463C46641CE4B202AB082234 +:106FC0003221532000F063FD9DF808009DF8091060 +:106FD000202C00EB012000B207449DF80A009DF828 +:106FE0000B1000EB012000B206449DF80C009DF848 +:106FF0000D1000EB012000B205449DF80F0000F0D9 +:107000007F0001D20028D7D197FBF4F0ADF8000043 +:1070100096FBF4F0ADF8020095FBF4F0ADF8040037 +:1070200088F802401EE0FFE702AB0622322153201F +:1070300000F02DFD9DF808009DF8091000EB0120DF +:10704000ADF800009DF80A009DF80B1000EB012040 +:10705000ADF802009DF80C009DF80D1000EB01202A +:10706000ADF8040098F8012049466846FFF73AFE5B +:10707000BDE8FF8770B5274D04464FF00802287819 +:107080004FF02D0100284FF053000ED000F0F9FC16 +:107090000A223121532000F0F4FC0C222C21532031 +:1070A00000F0EFFC9022382108E000F0EAFC0A2210 +:1070B0003121532000F0E5FC0A222C21532000F05E +:1070C000E0FC154940F20910002C088000D06C70DB +:1070D00070BD38B5054600208DF800000F480C46FD +:1070E0000F49006888420AD06B46012200215320D4 +:1070F00000F0CDFC18B19DF80000E52801D000207B +:1071000038BD044928780870064820600648606049 +:10711000012038BD70030020820100200C040020F3 +:10712000001BB70075700008A16F000810B54FF480 +:107130008044204602F08AFE012805D1204602F054 +:1071400093FEB9490120087010BD70B50D46B649CF +:10715000B64A064688885389B2F91440C01A138982 +:107160005843B2F91230C013DB02044493FBF4F32A +:107170001844D06100EB8000082202EB40000411AB +:10718000886800F0D0F806B13060002D00D02C6087 +:1071900070BD38B5A44C207810B96088401C608060 +:1071A0006B460322F621772000F071FC9DF8000069 +:1071B0009DF80110000440EA01209DF802100843E8 +:1071C0009A49B1F92010C1F10801C840A06038BD4A +:1071D0009648342190F8200001EB80109249C2B209 +:1071E00000200870F421772000F04BBC38B58E4C9D +:1071F000207810B96088401C60806B460222F6211E +:10720000772000F044FCBDF8000040BAA08038BDF3 +:10721000854900202E220870F421772000F031BC2F +:107220002DE9F04304468248824985B000688842CF +:1072300003D1002005B0BDE8F083DFF8EC9199F8A8 +:10724000010008B10120F5E74FF40055ADF80C50EE +:1072500002208DF80F001020774E8DF80E0003A944 +:10726000304601F039FF6F00ADF80C7004208DF846 +:107270000E0003A9304601F02FFF35610E210220D8 +:1072800001F060FF00208DF8080008208DF809004B +:107290004FF00108019747468DF80A8001A802F0D7 +:1072A0009FFD28208DF810000F208DF811008DF81B +:1072B00012008DF8137004A802F00DFC142000F0E9 +:1072C0001DFF6B460122D021772000F0E0FB574FD5 +:1072D0009DF800000321F8753984552801D07561A7 +:1072E000A7E76B460122D121772000F0D0FB9DF863 +:1072F000000000F00F0139760009787600F05CF8A4 +:1073000089F8018041F27070208046F67810608024 +:107310004A4860604A48A0604A48E0604A482061A4 +:107320004A4860618EE770B54049CA69B1F90E40BC +:10733000A2F57A6202FB02F31D136C43E512B1F968 +:107340000240B1F90460544305EBE424B1F9005064 +:1073500004EB850591F82040A54056437213B1F91E +:107360000C601B135E4302EB2642921C9210C988EC +:1073700002F50042AD1C5143C90B4CF25032A0EB58 +:10738000A500E2405043B0F1004F03D24000B0FBF3 +:10739000F1F002E0B0FBF1F040000112494340F689 +:1073A000DE3251432A4A0914424301EB224101F6DD +:1073B000CF6100EB211070BD00B587B06B4616227F +:1073C000AA21772000F063FBBDF8000041BA1748FE +:1073D0000180BDF8021049BA4180BDF8041049BAD5 +:1073E0008180BDF8061049BAC180BDF8081049BABD +:1073F0000181BDF80A1049BA4181BDF80C1049BAA3 +:107400008181BDF80E1049BAC181BDF8101049BA8A +:107410000182BDF8121049BA4182BDF8141049BA70 +:10742000818207B000BD000074030020300F0020EF +:107430000C040020001BB70000100140117200086E +:10744000ED710008D1710008937100084B710008BC +:1074500043E3FFFF38B5044600208DF800006B467B +:1074600001220A211E2000F012FB18B19DF8000035 +:10747000482801D0002038BD0CB18D48047001208F +:1074800038BD7FB5054602AB062203211E2000F061 +:10749000FEFABDF8080040BA00B203F019FC844CB3 +:1074A000241D216803F092FB03F020FCADF80000DE +:1074B000BDF80A0040BA00B203F00AFCA16803F06C +:1074C00085FB03F013FCADF80400BDF80C0040BAD6 +:1074D00000B203F0FDFB616803F078FB03F006FCEB +:1074E000ADF80200201F294602786846FFF7FAFB34 +:1074F0007FBD2DE9F0476F4800246F49006825469D +:107500008EB02E464FF0010888420CD14FF48050C7 +:10751000ADF8280002208DF82B0004208DF82A00F9 +:107520000AA9664808E06649884207D14FF48040BE +:10753000ADF828000AA9634801F0CEFD322000F022 +:10754000DDFD112200211E2000F09BFA60220121A6 +:107550001E2000F096FA642000F0D0FD6846FFF788 +:1075600090FFDFF858A1DFF8609100270AF10C0ABC +:10757000012202211E2000F084FA322000F0BEFD1C +:107580006846FFF77EFFBDF90210BDF90400BDF9A2 +:1075900000200D4414440644814201DA0B4600E009 +:1075A0000346934201DD104602E0814200DA0846BC +:1075B000484502DC4FF0000808E0DAF8001081F0DE +:1075C0001001CAF800107F1C0A2FD1DB1222002103 +:1075D0001E2000F056FA0027012202211E2000F092 +:1075E00050FA322000F08AFD6846FFF74AFFBDF9E5 +:1075F0000020BDF90210BDF90400A41A6D1A361A54 +:10760000814201DA0B4600E00346934201DD104659 +:1076100002E0814200DA0846484502DC4FF00008EB +:1076200008E0DAF8001081F01001CAF800107F1CA1 +:107630000A2FD1DB204603F04BFB244F014638468E +:1076400003F0FAFA1A4C20F00040241D206028466E +:1076500003F03EFB0146384603F0EEFA20F000400E +:107660006060304603F034FB0146194803F0E4FA49 +:1076700020F00040A060702200211E2000F001FADE +:10768000202201211E2000F0FCF9002202211E20F0 +:1076900000F0F7F9642000F031FDB8F1000F04D1DB +:1076A0004FF07E5020606060A0600EB0BDE8F087B3 +:1076B000800300200C04002000127A00000C01401E +:1076C000001BB7000010014000F0FFFF00406F46B4 +:1076D00001C05E4630B587B005464FF44060ADF856 +:1076E000140002208DF817001C208DF8160005A943 +:1076F000FB4801F0F1FCFB4CE56000F007FAE068A4 +:1077000002F0B8FB684602F020FC00224FF4407102 +:10771000E06802F050FC0025ADF804504BF6FF7015 +:10772000ADF806004FF48040ADF80C00EE48009034 +:107730000121E06802F017FC6946E06802F0ADFB49 +:107740004FF4A06002F0C2F922208DF810008DF8ED +:1077500011508DF8125001208DF8130004A802F08A +:10776000BAF921208DF810008DF8115004A802F00C +:10777000B2F907B030BD38B5DA4CE068818A0091C3 +:1077800011F4706F01D001212170009911F4E06FA4 +:1077900025D0018B00224FF4806102F00CFC009890 +:1077A00080051CD4E0680188890518D40188C905C2 +:1077B0000CD50188C905FCD4012102F0E8FBE06882 +:1077C00001888905FCD4FFF785FF08E0012102F05C +:1077D000DEFB00224FF44071E06802F0ECFBE06851 +:1077E000818A21F4706181820020207138BDC2E756 +:1077F0002DE9F041BB4CE068818A4FF00105C9B228 +:10780000CA074FF0000627D0018821F400610180EB +:10781000012102F0C6FBE670607A20B1607860B9A1 +:10782000A079FF2809D061790022E06802F0D0FB3E +:10783000A079FF2848D0FF20C9E06570E0790228D0 +:1078400004D1E068018841F400610180617901227E +:10785000E06802F0BDFB37E08A074FF4806745D54A +:10786000BFF3508FE079012810D1607A70B1607851 +:1078700060B10021E06802F094FBBFF3508FE06834 +:10788000018B012102F083FBA57018E0E068008BFA +:10789000BFF3508FE079022808D1607A30B1607868 +:1078A00020B10021E06802F07CFB06E0E0790328CB +:1078B00005D1607A18B1607808B1002200E0012299 +:1078C0003946E06802F077FB94F90310E079401C38 +:1078D000814209D16670A07828B100224FF440712E +:1078E000E06802F068FB2671BDE8F0814A0753D5D5 +:1078F000A570627A7B494978CAB3C9B3E179022994 +:107900001FD9002102F04DFBE06802F05EFB94F904 +:10791000031062695054491CE1700121E06802F0D3 +:1079200036FBA570E06802F050FB94F90310626921 +:107930005054491CE17001223946E06802F03BFBDB +:1079400025E0012102F023FBE06802F03EFB94F900 +:10795000031062695054491CE170E06802F035FB85 +:1079600094F9031062695054891CE1700FE000E043 +:1079700000E009B9217A31B1012102F008FBE07879 +:10798000401CE07003E0012102F0F7FA6570E06846 +:107990000188C905FCD497E74A061AD502F015FB01 +:1079A00094F9031062695054491C48B2E070E179BF +:1079B000C01C814204D100223946E06802F0FBFA83 +:1079C000E17994F903008142E5D100F10100E07012 +:1079D0007AE70906DFD594F903104B1C5AB20BD095 +:1079E0002369595CE27002F0EEFAE07994F9031031 +:1079F00088423FF45AAF67E7E270A17902F0E3FAF8 +:107A0000607A00287FF451AFE0790028F1D05BE77D +:107A1000EEE6B0E6ECE670B5324C4FEA400047F2D5 +:107A200030556071A17101202072002161722361C3 +:107A30006361E27120712170E068818889050ED44C +:107A40000188C90505D401888905FCD4012102F00B +:107A500094FA01224FF44071E06802F0ACFA207908 +:107A600010B16D1EFBD104E01DB1207880F0010043 +:107A700070BD6089401C6081E068FFF72BFE00202C +:107A800070BD07B502AB0122FFF7C5FF0EBD70B593 +:107A9000144C4FEA400047F230556071A17100204C +:107AA00020720121617263612361E2712171207092 +:107AB000E068818889050ED40188C90505D401884C +:107AC0008905FCD4012102F058FA01224FF44071DB +:107AD000E06802F070FA207940B16D1EFBD10AE037 +:107AE000000C014090030020801A06001DB1207890 +:107AF00080F0010070BD6089401C6081E068FFF784 +:107B0000E9FD002070BD2A48408970472DE9F84FF3 +:107B10004FF44067ADF800704FF0020A8DF803A0F3 +:107B20001420DFF890B08DF802006946584601F045 +:107B3000D3FA204D10352F60DFF8789000262C15F1 +:107B400005F1040809F1080902E00A2000F0CAFA68 +:107B5000D9F800004005F8D5C8F800400A2000F028 +:107B6000C1FA2C600A2000F0BDFA761CF6B2082E8D +:107B7000EED34FF400694646C8F800900A2000F0A2 +:107B8000B1FA34600A2000F0ADFA2C600A2000F04F +:107B9000A9FAC5F80090ADF800708DF803A01C207C +:107BA0008DF802006946584601F096FABDE8F88F54 +:107BB00090030020000C014038B504466B460222B9 +:107BC0001B216820FFF763FFBDF8000043F29031EE +:107BD00040BA08444FF48C71B0FBF1F023302080A0 +:107BE00038BD1FB5044602AB06221D216820FFF7F1 +:107BF0004EFFBDF80800214640BA02B2D01702EB92 +:107C000090708010ADF80000BDF80A0040BA02B2D2 +:107C1000D01702EB90708010ADF80200BDF80C0098 +:107C200040BA02B2D01702EB90708010ADF8040099 +:107C30002F4842786846FFF755F81FBD70B50446D7 +:107C4000192000F05BFA002215216820FFF719FFC8 +:107C500010B9032000F0FCFA254D1621287840F0D9 +:107C600018026820FFF70DFF002217216820FFF798 +:107C700008FF01223D216820FFF703FF01223E217A +:107C80006820FFF7FEFE002C00D06C7070BD70B550 +:107C900004460D46192000F031FA00221521682013 +:107CA000FFF7EFFE00281CD01248206012486060E9 +:107CB0001248A0601248E0600D48622D12D004DC2A +:107CC0000A2D13D0142D05D10EE0BC2D06D0B5F52C +:107CD000807F01D0032102E0002100E0012101703A +:107CE000012070BD0221FAE70421F8E70521F6E73B +:107CF000A80300203D7C0008E37B0008B97B000856 +:107D000018449231FEB5064614460D46684602F008 +:107D100039FC0120ADF804000021ADF80050ADF8A9 +:107D20000610ADF80810ADF802406946304602F082 +:107D300079FBFEBD70B51646D04A02EB0015D04A5D +:107D400002EB00140122206801F003FBD4E90101D9 +:107D5000182200F087F9217B3246206800F03FF9B5 +:107D6000A07B18B10121206802F01EFC01212068CF +:107D700002F010FC207B30B1042807D008280AD07C +:107D80000C2806D10AE02068343001E02068383041 +:107D90002860284670BD20683C30F9E720684030F4 +:107DA000F6E72DE9F0410546B4480F4600EB05160D +:107DB000B348B27100EB05142822D4E9010100F0A8 +:107DC00051F9217B00222068FFF79CFF01224FF62A +:107DD000FF71204601F0DAFA3A462946204601F0C2 +:107DE0009BFA3046BDE8F08170B5A64800240289B0 +:107DF00042810181891A8BB240F68C218B4201D9D4 +:107E0000C47070BD9F49A3F2EF2540F2DB569E4A35 +:107E1000C978B5421BD2082919D2984DE0350429FA +:107E200025F8113007D2C588AB4204D90123057962 +:107E30008B402B43037103790F2B08D10471B2F9E6 +:107E40000030142B02DD143B138000E01480491C29 +:107E5000C170148070BD70B5884A894B02EB001266 +:107E600003EB0013D47918681B7B8CB15181148902 +:107E7000824D091B91819479E03525F81410002476 +:107E8000D47122461946FFF73DFF7F48048070BD3C +:107E900011810121D171BDE870400222194631E7FC +:107EA0002DE9F0470446774DE1890020E980A1796A +:107EB00001B10220617801B1401C7449DFF8D08122 +:107EC000002651F820704FF47A79BA5D02F00F0065 +:107ED00002F0F001FF2A65D0A2781AB102285ED024 +:107EE00003285CD0E2783AB1042858D0052856D04F +:107EF000062854D0072852D0E2790AB182424ED0E7 +:107F000011F0300F02D0227802B90021227932B16B +:107F1000A27922B9082801D0092800D180216279EC +:107F20002AB1A2791AB9021F032A00D88021CA06F1 +:107F300005D500225749FFF734FF082008E08A06DC +:107F400008D5AA785449FFF72CFFA87800F1010062 +:107F5000A87024E04A0612D52289B8FBF2F1A28962 +:107F600089B202B94A46FFF7E5FE0146434A28783E +:107F7000F03242F8201000F1010028700FE00906ED +:107F80000DD56289B8FBF2F189B24A46FFF7D2FEFD +:107F90000146424A687842F82010401C6870761CFE +:107FA0000E2E92DB0020BDE8F087364A1278904210 +:107FB00005D23A4A303A52F82000006801807047F2 +:107FC000304A5278904204D2344A52F82000006875 +:107FD000018070473149403931F8100070477FB552 +:107FE000064615460C46684602F0C2FA7020ADF807 +:107FF00000000120ADF802000020ADF804000220CE +:10800000ADF80800C001ADF80650ADF80C0074B131 +:10801000042C15D0082C1CD00C2C07D169463046F6 +:1080200002F04CF90821304602F0E7FA7FBD6946BC +:10803000304602F098F80821304602F0C8FA7FBDB9 +:108040006946304602F0C4F80821304602F0C5FA0D +:108050007FBD6946304602F0F7F80821304602F04D +:10806000C6FA7FBD08B5ADF800108DF802200221D8 +:108070008DF80310694601F02FF808BD540F002059 +:10808000C8D20008AA030020D60000208CD2000825 +:1080900040420F00E97D0008577E00087410002060 +:1080A00080484168491C4160704710B57D484FF0D9 +:1080B000E02341689A694468A142FAD103680068E4 +:1080C00003EB4304C4EBC313C2EBC302B2FBF0F0F7 +:1080D00001EB4102C2EBC11100EBC10010BD7148C0 +:1080E0004068704730B50546FFF7DFFF4FEA0004F0 +:1080F000FFF7DBFF001BA842FAD330BD30B50446C2 +:108100004FF47A7502E02846FFF7ECFF641EFAD2BE +:1081100030BD6449896808474FF4805108B162480E +:1081200001E06148001F016070474FF4805110B1B9 +:108130005D48001F00E05C48016070472DE9F04F8A +:108140008DB018225949684602F041FC032701F01E +:1081500016FC0121564801F0A1FF012144F61D2023 +:1081600001F093FF0121084601F086FF01F0B1FF05 +:108170004FF6FF70ADF818004B484FF0000A8DF82D +:108180001AA006A9143800F0A7FF06A9494800F074 +:10819000A3FF06A9484800F09FFF4848416841F006 +:1081A00000714160464DDFF81C813E4E2968414513 +:1081B00001D1454800E04548B0600020FFF7A9FF25 +:1081C0003C4908201031086010200860A9460024AE +:1081D00083466D46D9F80010414506D105EBC40031 +:1081E0008179142901D180F806B005EBC401091D7D +:1081F00055F8340000F070FF641CBC42EAD307A8B5 +:1082000001F0F4FE32490798B0FBF1F030603148DC +:108210004FF47A710068B0FBF1F0B0F1807F0CD2BE +:1082200020F07F414FF0E020491E41612A4AF021B1 +:108230001170C0F818A0072101612848FFF74AFA19 +:1082400000F0C9FF6420FFF759FF0DB0BDE8F08FC3 +:10825000184A1021143211600821121F11600446BF +:10826000151F40F2DB104443286880F0100028609E +:10827000286880F008002860A01EFFF73FFF01205B +:10828000FFF747FF1920FFF739FF0020FFF741FFF5 +:10829000EAE710B11349124808600F49124817392C +:1082A00008607047B8030020140801409CD2000801 +:1082B00007004000000C0140001001400000014098 +:1082C0000C040020001BB7002B8100081981000856 +:1082D00040420F000804002023ED00E00058004059 +:1082E000EFBEADDEF04F00200400FA057CB5FA4C7D +:1082F0000D46FA492160A060A4F53070606100F578 +:108300008070A0614FF48070E0602061F4482063C9 +:10831000F348012114386063880301F0B6FE02209F +:108320008DF803000002ADF8000018208DF802005F +:10833000EC4EA80703D56946304600F0CDFE4FF459 +:108340008060ADF8000048208DF80200E80703D0F7 +:108350006946304600F0C0FE0E208DF80400012072 +:108360008DF805008DF806008DF8070001A801F0D2 +:10837000B2FB20467CBD2DE9FC41D74C0D464C3468 +:10838000D6492160A0608020E06040202061A4F5F3 +:10839000867060618030A061D3480121A0644804E8 +:1083A00001F07CFE02268DF803600420ADF8000089 +:1083B00018208DF80200CB4FA80703D56946384630 +:1083C00000F08AFE0820ADF8000048208DF8020079 +:1083D000E80703D06946384600F07EFE26208DF877 +:1083E000040001208DF805008DF806608DF8070067 +:1083F00001A801F070FB2046BDE8FC812DE9F043A7 +:1084000089460646B9490024B7488FB01D4617462D +:108410008E4204D119461046FFF768FF05E08642F8 +:1084200004D119461046FFF7A6FF04464FF0000896 +:10843000C4F82080C4F81C80C4F82880C4F82C90AC +:10844000C4F82480A6642571A760ADF83080ADF82B +:1084500034800B97ADF83280ADF83880ADF83680B7 +:10846000E80702D00420ADF83600A80705D5BDF80E +:10847000360040F00800ADF836000BA9304602F097 +:10848000E3F80121304602F037F9684601F074FC48 +:10849000301D00904FF48050CDE909088020CDF8C0 +:1084A0001080CDE905084746CDF81C80E80723D0A9 +:1084B000206BD8B1E068CDE9027020200890606997 +:1084C0000190206B01F0CEFB6946206B01F037FC78 +:1084D0000121206B01F05DFC01224021304602F0B9 +:1084E0002DF9206B01F06AFC206405E0012240F2C6 +:1084F0002551304602F00AF9A80724D5606BE0B197 +:1085000020690390102008970290606B01F0AAFB8D +:108510006946606B01F013FC01220221606B01F0DF +:1085200043FC0021606B01F047FC606B4760012257 +:108530008021304602F002F905E0012240F2277165 +:10854000304602F0E3F80FB02046BDE8F0837FB577 +:1085500004460020ADF80400ADF808000091ADF825 +:108560000600ADF80C00ADF80A0020790D46C007F2 +:1085700002D00420ADF80A002079800705D5BDF8A7 +:108580000A0040F00800ADF80A006946A06C02F04D +:108590005BF8A5607FBD826A81691144426BD1603E +:1085A000D0E9092100238A4205D9511A426B516052 +:1085B000416A816204E00269511A426B5160836230 +:1085C00080F84430406B012101F0E3BB016B11B135 +:1085D0004968006C01E01C3003C8814201D00120D1 +:1085E000704700207047416B11B190F8440070470C +:1085F000243003C8814201D1012070470020704718 +:1086000010B50146036BC268406943B10B6CD21AC6 +:10861000805C5B1E0B6401D1CA680A6410BD0B6AE2 +:10862000C05C5B1CB3FBF2F402FB14320A6210BDA7 +:10863000436A8269D154416A0269491CB1FBF2F371 +:1086400002FB13114162416B19B10968C90706D1D8 +:10865000A1E7806C012240F2277102F057B8704701 +:1086600010B51D4C4FF4005001F0ABFB0021606BC6 +:1086700001F08FFBD4E90901884203D02046BDE810 +:10868000104088E7012084F8440010BD1249886C2E +:10869000028812060ED5D1E909329A420BD08B69B5 +:1086A0009A5C8280886A0A69401CB0FBF2F302FB84 +:1086B000130088627047002240F2277102F026B84A +:1086C00070B5054C4C34A06C0588A9061CD5808873 +:1086D000E16A69B1884717E054130020B4D200085A +:1086E00058000240000801400044004000380140AA +:1086F000E26961698854E069E16800F10100B0FB5A +:10870000F1F201FB1200E06128060FD5D4E909104F +:1087100088420CD0A169085CA16C8880A06A21699C +:10872000401CB0FBF1F201FB1200A06270BDA06C16 +:10873000BDE87040002240F2277101F0E7BF000061 +:10874000FEB52C4C0125207878B1012823D00228D1 +:1087500020D164208DF8000027488DF801500026B4 +:108760004078E0B38DF802503CE07A208DF80000AC +:1087700022486B460222B0F90000FF21C0F1B4008C +:1087800000EBD070C0F347008DF801006D20FFF7BB +:1087900042F92570FEBD1A4E79208DF80000B6F919 +:1087A00000000A2590FBF5F05A30B4220021FEF7B4 +:1087B0009BF98DF80100B6F90200B42290FBF5F0A8 +:1087C0005A300021FEF790F98DF802006B46032223 +:1087D000FF216D20FFF71FF902202070FEBDFFE78B +:1087E0008DF802606B460322FF216D20FFF713F91D +:1087F0002670F3E7C40300208C0A0020B00100209B +:10880000340000201FB5044602AB06224321682035 +:10881000FFF73DF9BDF80800214640BA02B2D01773 +:1088200002EB90708010ADF80000BDF80A0040BA6D +:1088300002B2D01702EB90708010ADF80200BDF8C4 +:108840000C0040BA02B2D01702EB90708010ADF865 +:1088500004007C4842786846FEF744FA1FBD38B5EC +:1088600004464FF40050ADF8000002208DF80300DC +:1088700004208DF80200744874490068884202D1CF +:108880006946734804E07349884203D169467248D7 +:1088900000F022FC80226B216820FFF7F2F805200F +:1088A000FFF72CFC002219216820FFF7EAF80322C9 +:1088B0006B216820FFF7E5F8022237216820FFF7D7 +:1088C000E0F8604D1A2168202A78FFF7DAF81822BC +:1088D0001B216820FFF7D5F810221C216820FFF724 +:1088E000D0F8002C00D06C7038BD1FB5044602AB28 +:1088F00006223B216820FFF7CAF8BDF80800214690 +:1089000040BAADF80000BDF80A0040BAADF8020068 +:10891000BDF80C0040BAADF804004A4882786846B9 +:10892000FEF7E0F91FBD47494C4ACB7813B14FF42D +:10893000FF6301E04FF480531380002800D088705B +:1089400070472DE9FE4F8146984692460D462320FA +:10895000FFF7D4FB6B46012275216820FFF797F8DB +:10896000002804D09DF80000682802D00020BDE84F +:10897000FE8F062201AB11466820FFF788F89DF8AC +:1089800009009DF80710C007400F01F0010140EAFF +:1089900041009DF805102B4C01F0010108434FF0F8 +:1089A00001064FF0000704D0012833D002280DD073 +:1089B0002CE06B4601220C216820FFF768F89DF837 +:1089C000000010F00F0021D0042823D0E7702449C4 +:1089D000C9F8001023492448C9F804102860234826 +:1089E00068602348E860B8F1000F02D0E17888F8A9 +:1089F00000105046BAF1620F19D00DDC05281ED0C8 +:108A00000A281AD0BAF1140F0BD114E00520FFF791 +:108A10001FFCDCE7E670DAE7BC2806D0BAF5807FF9 +:108A200001D0032004E0277003E0267001E002205B +:108A3000207001209BE70420FAE70520F8E70620D4 +:108A4000F6E70000C50300200C04002000127A00A5 +:108A5000000C0140001BB700001001408201002003 +:108A600027890008EB8800085F880008058800084F +:108A7000194492311FB5044602AB062201211C2085 +:108A8000FFF705F8BDF80800214640BA40F38D0213 +:108A9000D01702EB90708010ADF80000BDF80A000E +:108AA00040BA40F38D02D01702EB90708010ADF801 +:108AB0000200BDF80C0040BA40F38D02D01702EB63 +:108AC00090708010ADF80400334802786846FEF7D5 +:108AD00009F91FBD38B504462020ADF8000002207A +:108AE0008DF8030004208DF8020069462B4800F041 +:108AF000F3FA00222A211C20FEF7C3FF02220E21D6 +:108B00001C20FEF7BEFF03220F211C20FEF7B9FF39 +:108B100012222B211C20FEF7B4FF02222C211C2044 +:108B2000FEF7AFFF01222D211C20FEF7AAFF002235 +:108B30002E211C20FEF7A5FF05222A211C20FEF76E +:108B4000A0FF17494FF48070002C088001D0124814 +:108B5000047038BD38B5044600208DF80000114877 +:108B60001149006888420CD06B4601220D211C205F +:108B7000FEF78DFF28B19DF800002A2803D01A289F +:108B800001D0002038BD09492160094961600249CE +:108B90004870012038BD0000C903002000080140D2 +:108BA000820100200C040020001BB700D58A0008B9 +:108BB000758A0008434810B50068434CA1880842F4 +:108BC00003D0FFF772FAA0600AE0FFF76EFAA1681F +:108BD000884205D9401A3B2190FBF1F06169086099 +:108BE000E068BDE8104001F03FB9E3E7E2E7FEB519 +:108BF0000125354C022110B1012810D109E04FF4B4 +:108C0000807060804000A080E06009202070172004 +:108C100004E06580A180E1602570072060706088B5 +:108C2000ADF800001026274F8DF802608DF8031074 +:108C3000083F6946384600F04FFAA088ADF80000BA +:108C400004208DF802006946384600F045FA217884 +:108C5000012000F077FAE06801F006F9E068019081 +:108C600000208DF808008DF809608DF80A5001A8E1 +:108C700001F0B6F894F9010000F01F018D404009A1 +:108C80004FF0E02101EB8000C0F80051FFF727FA18 +:108C90003C382061FEBD70B50546FFF720FA0A4C4E +:108CA00021693C3188420CD3C4E904050549608838 +:108CB000083108600B20FFF715FA024960880C3173 +:108CC000086070BD080C0140CC0300201FB50446AD +:108CD00002AB0622A8216820FEF7D9FEBDF80800E5 +:108CE000214640BA02B2D01702EB90708010ADF866 +:108CF0000000BDF80A0040BA02B2D01702EB907033 +:108D00008010ADF80200BDF80C0040BA02B2D017D6 +:108D100002EB90708010ADF8040026484278684657 +:108D2000FDF7E0FF1FBD70B504466420FFF7E6F9CC +:108D3000F02223216820FEF7A4FE10B90320FFF7DC +:108D400087FA0520FFF7DAF91A4D2021287840F03C +:108D50000F026820FEF795FE002C00D06C7070BDED +:108D600038B504460D461920FFF7C8F96B460122B5 +:108D70000F216820FEF78BFE9DF80000D32801D05C +:108D8000002038BD0C4820600C4860600C48E06052 +:108D90000848362D05D04E2D07D05D2D07D0002177 +:108DA00000E040210170012038BD8021FAE7C02198 +:108DB000F8E70000E4030020278D0008CD8C0008B0 +:108DC000DDE9A7312DE9F04FB74C83468E46608927 +:108DD00026890102B5484FF0000A4068421AA6FBF6 +:108DE000027CA0884FEAE2754FEA10414FEA004347 +:108DF0000AFB02C006FB05064FEAD71040EA4660B0 +:108E000013EB000941EBE611E6886388A6FB02C874 +:108E10004FEA53404FEAC3370AFB028306FB05368D +:108E20004FEA1C2343EA0663FB1840EB2620A68981 +:108E3000A6FB027C0AFB02C206FB05244FEAD752BE +:108E400042EA44224FF4FA654FEAE454521944F1DD +:108E50000004A246551B74F1000448DA944D5519DC +:108E6000A5FB05674AF1FF3404FB057705FB047C8D +:108E70000525A6FB05480CFB0585002706FB0755C5 +:108E80006F104FEA340CB9EB0C0961EB0701A40831 +:108E900044EA85741B1B60EBA500864D551B7AF1D7 +:108EA000FF3424DA40F2DC555619A6FB06474AF196 +:108EB000000505FB067706FB05750726A4FB06C81B +:108EC00005FB0686002704FB0767B9EB0C0961EB7D +:108ED00007010B27A4FB07C805FB0785002604FB39 +:108EE000065464104FEA3C055B1B60EB04006F4CBA +:108EF000A5680024A5FB036704FB037305FB003092 +:108F0000740D44EAC0244015B4EB090360EB010082 +:108F1000410441EAD330BBF1000F01D0CBF800008F +:108F2000BEF1000F01D0CEF80020BDE8F08F10B5E3 +:108F300000F072F85D49886010BD5C48012200783D +:108F40004030C1B27720FEF79CBD10B500F064F848 +:108F50005649486010BD5548012200785030C1B2D2 +:108F60007720FEF78EBD2DE9FE4305465248534952 +:108F7000006888420FD04FF40054ADF80040022042 +:108F80008DF8030010204E4E8DF8020069463046E1 +:108F900000F0A2F874610A20FFF7B0F801AB0122DB +:108FA000A0217720FEF773FD002823D001221E2187 +:108FB0007720FEF766FD4FF42F60FFF793F800244B +:108FC000DFF8E4802646A02707EB4400C1B202ABDD +:108FD000022277200296FEF75AFDBDF8080040BA3B +:108FE00028F81400641C082CEEDB2F4800F026F84B +:108FF00010B10020BDE8FE8342F210702880688026 +:10900000304868603048A8603048E86030482861DF +:10901000304868610120EDE708B56B460322002166 +:109020007720FEF734FD9DF800009DF80110000444 +:1090300040EA01209DF80210084308BDF0B5C2893E +:10904000002102F47F4502F00F040123C5810A4686 +:1090500030F8126006B10023521C082AF8DB4FF0EA +:10906000FF36F3B90022D30722F0010302D0C35C1C +:10907000594002E0C35A81EA132108230F0401D5A5 +:1090800081F4C05149005B1E002BF7DC521C102AF2 +:10909000E9DB2543C581C1F30330844201D10020BF +:1090A000F0BD3046F0BD0000EC130020E8030020C6 +:1090B00030F8FFFF24FAFFFF0C040020001BB7006C +:1090C00000100140578F00084B8F00083B8F0008AD +:1090D0002F8F0008C58D0008F0B500234FF0010C5C +:1090E0000A880CFA03F52A4228D04FEAD30200EB93 +:1090F00082064FEA437491F802E04FEAD46734687D +:109100000EF00F025FEACE6E03D591F803E04EEA4F +:1091100002024FF00F0E0EFA07FE24EA0E04BA40C8 +:10912000224332608A78282A02D0482A03D005E0F8 +:10913000C268AA4301E0C2682A43C2605B1C102BCC +:10914000CED3F0BD10B58A0721F003040649130FF2 +:1091500021440F228C689A4094438C608A6898401E +:1091600002438A6010BD0000000001404FF48051AE +:1091700008B14E4801E04D48001F016070472DE9DD +:10918000F04104464A4817460D460088484E0C3EBA +:109190001CE015B115F8010B00E0FF20804602210C +:1091A000304601F0D9FB0028F9D04146304601F0A5 +:1091B000CFFB0121304601F0CFFB0028F9D030462B +:1091C00001F0C8FBC0B20CB104F8010B7F1EE0D265 +:1091D0000120BDE8F081F0B501218C0389B0204663 +:1091E00000F05CFF0121204600F06AFF18208DF896 +:1091F00016004FF42040ADF814002C4E03208DF8DB +:109200001700143E05A93046FFF766FFADF814407D +:1092100004208DF8160005A93046FFF75DFFA01069 +:10922000ADF8140010258DF8165005A93046FFF74B +:1092300053FF1F4E0C3E304601F040FB4FF482704E +:10924000ADF8020068010024ADF80A000720ADF86F +:109250001000ADF804400220ADF80E40ADF8060055 +:109260000127ADF80040ADF80870ADF80C50694624 +:10927000304601F047FB0121304601F05FFB0DA0B5 +:10928000006806900120FFF771FF042206A907A8D5 +:10929000FFF775FF0020FFF769FF9DF81D00EF281D +:1092A00002D0204609B0F0BD3846FBE7140C01405F +:1092B0000C3800409F0000002DE9F04180461D461B +:1092C00016460C46084600F0E7F80746404600F010 +:1092D000D8F807EB8000C0B2102805D2734901EB23 +:1092E0000010856004710673BDE8F08151B1042956 +:1092F0000BD008290CD00C290DD101225FF01001F0 +:1093000001F05DB901220221FAE701220421F7E709 +:1093100001220821F4E7704770B50D460446017B31 +:10932000134600682A46FFF7C7FF217B2068BDE887 +:109330007040DBE708B58DF8000000208DF80100D3 +:1093400001208DF802008DF80300684600F0C3FB91 +:1093500008BDFEB5064614460D46684601F0FFF806 +:1093600053486D1E44435348ADF8045069460068A5 +:10937000B0FBF4F0401EADF800000020ADF8060090 +:10938000ADF80200304600F0B5FEFEBD10B5044653 +:109390000068FFF7DEFF0121206801F0FBF8607B29 +:1093A000BDE81040C6E770B50546084600F074F801 +:1093B0000446284600F065F804EB80003B49C0B243 +:1093C00001EB001070BD70B50546022101F028F9CF +:1093D000012825D00421284601F022F901282CD0AB +:1093E0000821284601F01CF9012833D01021284615 +:1093F00001F016F901283AD11021284601F01CF994 +:109400000C212846FFF7CFFF0446284601F005F956 +:10941000A2680146002A2AD0207BBDE87040104790 +:109420000221284601F008F900212846FFF7BBFF7A +:109430000446284601F0EBF8EAE70421284601F04B +:10944000FBF804212846FFF7AEFF0446284601F04A +:10945000E0F8DDE70821284601F0EEF8082128466B +:10946000FFF7A1FF0446284601F0D5F8D0E770BD0C +:109470001148A8E74FF08040A5E71048A3E710483F +:10948000A1E7014600200F4A01E0401CC0B252F89B +:1094900020308B42F9D17047014600200A4A01E092 +:1094A000401CC0B2135C8B42FAD17047FC13002001 +:1094B00040420F0008040020002C0140000400403E +:1094C00000080040F4030020A8D30008016B4A689C +:1094D000926889680A4290F8441204D0002000295A +:1094E00000D10120704701200029FBD100207047E6 +:1094F000D0F8343101299A685B6801D021B107E0C6 +:1095000090F8440230B103E090F84402012801D001 +:109510005A6170471A6170470189406889B24822D0 +:1095200000F052B970B5044601EB4100AC49164653 +:10953000B1FBF0F081B21D4603222046FFF726FF63 +:109540002A4631462046BDE87040FFF7E5BE018956 +:10955000406889B2102200F037B900B503460320F5 +:1095600083F83C021846FFF7B1FF30B1B3F8400270 +:1095700093F839120843A3F8400293F839024000E7 +:1095800083F8390293F83E02401E10F0FF0083F882 +:109590003E0205D1012083F83802022083F83C0204 +:1095A00000BDC268016A521E914201D3002100E051 +:1095B000491C0162704710B50124034680F83C4203 +:1095C000FFF784FF01280FD1002083F8380283F8C9 +:1095D0003A4293F84002A3F840021A6A5969885443 +:1095E000BDE810401846DCE710BD00B50346FFF7A4 +:1095F0006DFF012101280BD003F23A2300201870DF +:10960000D880042098700820187103F8011C00BD50 +:1096100083F83C1200BD90F83C12491E11F0FF0186 +:1096200080F83C1208D190F83A1201B1DDE790F8C9 +:10963000381201B1BFE790E77047D0E909108142C5 +:1096400001D1012070470020704730B5044690F8E2 +:109650003B020025F8B194F83D02401E10F0FF00D7 +:1096600084F83D0216D1B4F8420200F0010140082E +:10967000A4F842022046FFF73BFF032084F83D0296 +:1096800094F83F02401E10F0FF0084F83F0201D121 +:1096900084F83B5230BD2046FFF7CFFF0028F9D1B8 +:1096A000A16AA269481CA062515C2269904200D361 +:1096B000A5624FF4007004F23B2440EA4100A4F894 +:1096C00007000A2020710120A070207030BD00EB3F +:1096D000C00101EB801010B5424901EBC0042046E7 +:1096E000FFF7B3FF2046BDE8104094E770B53D4C4E +:1096F00006463D48206003202071A66084F844128D +:109700003A4820631030C4F83401002504F13401D4 +:10971000256261614FF48070E060206104F59C7106 +:10972000C4E90615A562656284F83B52012084F8FD +:109730003A0284F8385284F83C02206BFFF7ECFEC2 +:10974000D4F83401FFF703FF01212046FFF7D0FED4 +:109750003220FEF7D3FCAFF289032A463146206B54 +:10976000BDE87040DEE6D0E90721914202D14FF01A +:109770000000704702D9A1EB020003E0C068084472 +:10978000A0EB0200C0B2704700B50346FFF7EBFF45 +:1097900000280BD05969D869095CDA68521E9042DA +:1097A00001D2401C00E00020D861084600BD436A99 +:1097B0008269D154416A0269491CB1FBF2F302FB90 +:1097C000131141627047704708B5ADF800108DF86D +:1097D000022002218DF803106946FFF77DFC08BDC9 +:1097E000C0C62D00FC140020ACD3000808D300082C +:1097F0001FB5044602AB062202211820FEF747F9E6 +:109800009DF808009DF80910800800EB0120ADF8D4 +:1098100000009DF80A009DF80B10800800EB012065 +:10982000ADF802009DF80C009DF80D10800800EBCB +:109830000120ADF804001A48214602786846FDF779 +:1098400051FA1FBD10B5044608220F211820FEF75B +:1098500018F90E2210211820FEF713F911494FF4C0 +:109860008050002C088001D00D48047010BD38B520 +:10987000044600208DF8000001466B4601221820A6 +:10988000FEF705F918B19DF80000FB2801D0002073 +:1098900038BD0548206005486060012038BD0000E3 +:1098A000040400208201002045980008F197000878 +:1098B00002681268104770B50C46054603E02A6836 +:1098C00028461268904714F8011B0029F7D170BD93 +:1098D0000168496808470168896808470268D268D2 +:1098E00010470168096908476E48016841F00101A5 +:1098F000016041686C4A1140416001686B4A114047 +:109900000160016821F480210160416821F4FE01B9 +:1099100041604FF41F0181606549C00308607047D2 +:10992000604A10B55068634B10F00C01624803D0D8 +:10993000042903D0082903D0036016E0416813E02E +:109940005168536801F470114FF0020413F4803F22 +:1099500004EB914106D053689B03436800D55B0834 +:109960004B43E9E7554B594301605168524AC1F3F3 +:1099700003110832515C0268CA40026010BD3EB457 +:10998000002100914FF4E01301914648CDE90131E7 +:109990004B4A046844F480340460846944F0100441 +:1099A00084614FF4A064056805F400350195009DBD +:1099B0006D1C0095019D15B9009DA542F3D1056868 +:1099C000AD0301D5022114E0056845F001050560ED +:1099D0000091016801F0020101910099491C009178 +:1099E000019911B90099A142F3D10168890739D5CC +:1099F0000121029133490C6844F010040C600C689A +:109A000024F003040C600C6844F002040C6041680C +:109A1000416041684160416841F480614160116882 +:109A200021F070411160244C22496160416821F4A9 +:109A30007C114160116841F0004111602049091F0B +:109A4000CA6822F40042CA608968090403D51E4925 +:109A50004FF48013616002990193012908D0022913 +:109A60000AD100E0FEE7416843F48032114302E08E +:109A7000416841F460114160016841F0807101600A +:109A800001688901FCD5416821F00301416041680A +:109A900041F0020141604168C1F381010229FAD11C +:109AA0003EBC3DE7001002400000FFF8FFFFF6FE5D +:109AB00008ED00E000127A000804002000093D00D3 +:109AC0000410014000200240001BB7001849084361 +:109AD000184908607047F0B50F21C4780278012357 +:109AE0004FF0E026DCB1134C2468457804F4E064C0 +:109AF000C4F5E064240AC4F10407E1408478BD4061 +:109B00000C402C4321010C4C1155007800F01F0132 +:109B10008B40400906EB8000C0F80031F0BD02F038 +:109B20001F008340500906EB8000C0F88031F0BD73 +:109B30000000FA050CED00E000E400E010B542681A +:109B4000464B0C791A400B6842EA042213434360E7 +:109B50008368434A1340D1E9024222434C7943EAE5 +:109B600044031A438260C26A097C22F47002491ECF +:109B7000C9B242EA0151C16210BD0029816802D018 +:109B800041F0010101E021F00101816070470029ED +:109B9000816802D041F4807101E021F4807181601C +:109BA0007047816841F008018160704701460020DC +:109BB0008968090700D501207047816841F00401D8 +:109BC00081607047014600208968490700D501205F +:109BD00070470029816802D041F4A00101E021F41E +:109BE000A0018160704770B5072409290AD9C568AA +:109BF000A1F10A0606EB4606B440A543B3401D4357 +:109C0000C56007E0056901EB4106B440A543B340D8 +:109C10001D4305611F23072A09D2446B521E02EB24 +:109C2000820293409C4391400C43446370BD0D2AD3 +:109C300009D2046BD21F02EB820293409C439140F5 +:109C40000C43046370BDC46A0D3A02EB8202934078 +:109C50009C4391400C43C46270BD0000FFFEF0FFC6 +:109C6000FDF7F1FF01684FF6FE721140016000211F +:109C7000016041608160C1605749574A083990428C +:109C800003D1486840F00F0006E0534A1432904276 +:109C900004D1486840F0F000486070474E4A2832CE +:109CA000904203D1486840F47060F5E74A4A3C327C +:109CB000904203D1486840F47040EDE7464A503284 +:109CC000904203D1486840F47020E5E7424A64328C +:109CD000904203D1486840F47000DDE73E4A783294 +:109CE000904203D1486840F07060D5E73B4A111FAD +:109CF000904203D1086840F00F0006E0374A143262 +:109D0000904204D1086840F0F00008607047334A80 +:109D10002832904203D1086840F47060F5E72F4A7A +:109D20003C32904203D1086840F47040EDE72B4A82 +:109D300050329042EAD1086840F47020E5E730B52F +:109D4000036847F6F07293430C6A8A682243D1E9AC +:109D500004452C4322438C692243CC6922434C6A3C +:109D600022438C6A22431A430260CA6842600A682E +:109D700082604968C16030BD00210160416081603E +:109D8000C160016141618161C161016241628162C1 +:109D900070470029016802D041F0010102E04FF64E +:109DA000FE72114001607047002A026801D00A4328 +:109DB00000E08A430260704741607047406880B2AB +:109DC0007047C10003D50549091F08607047024963 +:109DD000083948607047000008000240080402404B +:109DE00030B523498379026853B30B6893430B6002 +:109DF0000A1D13680468A343136002790A441368B8 +:109E00000468234313601A4A083213680468A343A2 +:109E10001360131D1C680568AC431C604479102C4A +:109E200005D021440A68006802430A6030BD116809 +:109E3000046821431160196800680143196030BD4E +:109E40000079084401689143016030BD084A014629 +:109E500000201268064B0A4014331B680B4202D0E4 +:109E6000002A00D001207047014914310860704772 +:109E7000000401405A4910B588424FF0010101D158 +:109E80004C0501E04FF48004204600F019F920460B +:109E9000BDE81040002100F013B970B50446808879 +:109EA00086B00D4620F03F06684600F09FF84D4909 +:109EB0000298B0FBF1F189B20E43A680228822F00D +:109EC00001022280484B2A689A421CD85200B0FBFB +:109ED000F2F080B2042800D20420491C2184A0831F +:109EE000208840F00100208021884FF6F5300140A5 +:109EF000A8886A89104308432080A88929890843D3 +:109F0000208106B070BDEB88A3F53F46FF3E05D12A +:109F100002EB4202B0FBF2F080B208E002EBC203B7 +:109F200003EB0212B0FBF2F080B240F48040020575 +:109F300001D140F001004FF4967251434FF47A7210 +:109F4000B1FBF2F140F40040C7E741F28831016013 +:109F5000002181804BF6FF72C280018141814FF464 +:109F60008041818170470029018802D041F00101C0 +:109F700001E021F00101018070470029018802D031 +:109F800041F4807101E021F4807101807047002963 +:109F9000018802D041F4007101E021F400710180D8 +:109FA00070470029018802D041F4806101E021F46A +:109FB000806101807047002A828801D00A4300E056 +:109FC0008A438280704701827047008AC0B270471E +:109FD00012B141F0010101E001F0FE010182704780 +:109FE0000054004040420F00A086010030B53C49BB +:109FF0004A683C4B12F00C0405D03B4A042C126812 +:10A0000003D0082C24D0036000E002604A680F23CC +:10A0100003EA1212354B9C5C0268E24042604C68D5 +:10A02000072505EA14241C5D22FA04F484604C68B8 +:10A0300005EAD4241B5DDA40C2604968032303EAC1 +:10A0400091312A4B1B1F595CB2FBF1F1016130BD0C +:10A050004B684C6803F470134FF0020514F4803F12 +:10A0600005EB934305D04C68A40300D552085A432E +:10A07000CBE71F4A5343C6E7194A0029516901D06B +:10A08000014300E0814351617047154A00299169FD +:10A0900001D0014300E0814391617047104A0029DB +:10A0A000D16901D0014300E08143D16170470C4A7E +:10A0B0000029D16801D0014300E08143D16070479D +:10A0C000074A0029116901D0014300E08143116171 +:10A0D00070470348416A41F0807141627047000057 +:10A0E0000010024000127A000C040020240400201A +:10A0F00000093D0030B50288FD4BFE4C98420DD062 +:10A10000A0420BD0B0F1804F08D0FB4DA84205D043 +:10A11000FA4DA84202D0FA4DA84203D122F07005B0 +:10A120004A882A43F74DA84206D0F74DA84203D0EB +:10A1300022F44075CA882A4302808A8882850A8868 +:10A14000028598420AD0A04208D0F04A904205D039 +:10A15000EF4A904202D0EF4A904201D1097A01863B +:10A160000121818230BD30B5028C22F001020284CF +:10A17000028C8388048B22F0020224F073050C8881 +:10A180002C430D8915434A882A43D94DA8420BD048 +:10A19000D84DA84208D0DD4DA84205D0DC4DA842DC +:10A1A00002D0DC4DA8420DD122F008054A8923F4E3 +:10A1B00040732A4322F004058A882A438D891D436F +:10A1C000CB892B4383800483C9888186028430BD78 +:10A1D00070B5028C22F010020284028C8488038BFA +:10A1E0000D8823F4E6464FF6FF7303EA0525354351 +:10A1F0000E8922F0200203EA061616434A8803EA73 +:10A2000002123243BA4EB04202D0BA4EB04215D119 +:10A2100022F080064A8924F4406403EA02123243A1 +:10A2200022F040068A8803EA021232438E8903EA4A +:10A2300086062643CC8903EA84043443848005835C +:10A24000C9880187028470BD70B5028C22F48072C7 +:10A250000284028C8488838B0D8823F073031D4352 +:10A2600022F400730E894FF6FF7202EA06261E439F +:10A270004B8802EA032333439D4EB04202D09D4EE9 +:10A28000B04215D123F400664B8924F4405402EA0D +:10A290000323334323F480668B8802EA032333438A +:10A2A0008E8902EA06162643CC8902EA0414344356 +:10A2B00084808583C9888187038470BD70B5028CD2 +:10A2C00022F480520284048C8288838B0D8823F4CC +:10A2D000E6464FF6FF7303EA0525354324F400569E +:10A2E0000C8903EA043434434E8803EA06362643D5 +:10A2F0007F4CA04202D07F4CA04205D122F4804482 +:10A300008A8903EA8212224382808583C988A0F861 +:10A310004010068470BD828B22F440628283828B5F +:10A320004FF6FF7303EA01210A4382837047828B51 +:10A3300022F00C028283828B0A4382837047028B55 +:10A3400022F440620283028B4FF6FF7303EA01217D +:10A350000A4302837047F0B5048C24F0100404848F +:10A36000078B048C4FF6FF7527F4734705EA033318 +:10A370003B4305EA02221A435D4B05EA0116984267 +:10A380000ED05C4B98420BD0B0F1804F08D05A4BA6 +:10A39000984205D0594B984202D0594B984205D16A +:10A3A00024F02001314341F0100104E024F0A00327 +:10A3B0000B4343F0100102830184F0BD028B22F0B5 +:10A3C0000C020283028B0A430283704770B5048C2F +:10A3D00024F001040484058B048C4FF6FF7606EA12 +:10A3E0000313134325F0F305414A2B4390420ED04B +:10A3F000404A90420BD0B0F1804F08D03E4A904284 +:10A4000005D03E4A904202D03D4A904202D124F00B +:10A41000020201E024F00A020A4342F00101038330 +:10A42000018470BD2DE9F05F0D4604460888304F69 +:10A43000DFF8C0C0DFF8C0804988AA882B894FF0B8 +:10A44000804960B3042832D04FF6FF7E082836D00A +:10A45000208C9B4620F480502084A38B268C704651 +:10A4600000EA022223F473431A4300EA0B3010433C +:10A470000EEA013EBC420BD0644509D04C4507D0E2 +:10A48000444505D01D4A944202D01D4B9C425AD1EE +:10A4900026F4005141EA0E0141F4805158E0204673 +:10A4A000FFF794FFE9882046BDE8F05F86E7204685 +:10A4B000FFF751FFE9882046BDE8F05F3FE7208CB9 +:10A4C00020F480702084B4F81CA0208C0EEA0313C2 +:10A4D00013432AF0F30A0EEA012B43EA0A03BC42B3 +:10A4E00020D064451ED04C451CD044451AD013E002 +:10A4F000002C0140003401400004004000080040EE +:10A50000000C0040001000400014004000400140DA +:10A510000044014000480140494A944202D0494A5F +:10A52000944204D120F4007040EA0B0002E020F4D1 +:10A530002060084340F48070A3832084E98820468B +:10A54000BDE8F05FF3E626F402420A4342F480518C +:10A55000A08320462184E988BDE8F05FDBE64FF662 +:10A56000FF71818000210180C180418001727047AC +:10A570000021018041808180C180018141818181F0 +:10A58000C181704700210180418001228280C18009 +:10A59000018170470029018802D041F0010101E0EA +:10A5A00021F0010101807047002930F8441F02D0DA +:10A5B00041F4004101E0C1F30E0101807047002A1F +:10A5C000828901D00A4300E08A4382817047028B6E +:10A5D00022F008020A4302837047028B4FF6FF7392 +:10A5E00022F4006203EA0121114301837047828B48 +:10A5F00022F008020A4382837047828B4FF6FF7372 +:10A6000022F4006203EA0121114381837047808EA6 +:10A610007047008F7047808F7047B0F840007047D8 +:10A6200002460020138A92890B4202EA010202D0FC +:10A63000002A00D001207047C94301827047000002 +:10A6400000080040000C004030B50446008A85B088 +:10A650000D464CF6FF710840E98801432182A1892B +:10A660004EF6F3100140A8882A8910436A890A43EC +:10A670001043A081A08A4FF6FF410840A9890143F9 +:10A68000A1826846FFF7B2FC3048844201D10398AA +:10A6900000E00298A1890904002900EBC00101EB48 +:10A6A0000010296802DA4FEA410101E04FEA810116 +:10A6B000B0FBF1F06422B0FBF2F14FEA01114FEA76 +:10A6C00011136FF018056B4300EB8300A3891D0481 +:10A6D0004FF0320306D503EBC000B0FBF2F000F000 +:10A6E000070005E003EB0010B0FBF2F000F00F00F4 +:10A6F0000843208105B030BD0029818902D041F492 +:10A70000005101E021F400518181704710B5C1F37F +:10A71000421301F01F040121A140012B07D0022B9D +:10A7200007D01430002A026805D00A4304E00C3038 +:10A73000F8E71030F6E78A43026010BD002A828AEB +:10A7400001D00A4300E08A4382827047003801400A +:10A750003948384941603949416070473648016994 +:10A7600041F080010161704733490420CA68D20773 +:10A7700001D001207047CA68520701D502207047F6 +:10A78000C968C906FBD50320704700B50346FFF72B +:10A79000EBFF02E0FFF7E8FF5B1E012803D0002B70 +:10A7A00000D1052000BD002BF4D1FAE770B50546B5 +:10A7B0004FF430263046FFF7E8FF042811D11E4C35 +:10A7C000206940F0020020616561206940F040008E +:10A7D00020613046FFF7D9FF216941F6FD72114033 +:10A7E000216170BDF8B5064600204FF4005C009072 +:10A7F0000D466046FFF7C9FF042816D10E4C2069AC +:10A8000040F00100206135806046FFF7BEFF41F651 +:10A81000FE77042806D1B61C280C009630806046CE +:10A82000FFF7B3FF216939402161F8BD0249C860D3 +:10A83000704700002301674500200240AB89EFCD3F +:10A8400014481549026800608A4203D013488047C3 +:10A8500013480047134E4FF009003060124801685A +:10A8600021F07061016041020160104C18202060ED +:10A870000F49104808601048D0F800D040680047E1 +:10A88000FEE7FEE7FEE7FEE7FEE7FEE7FEE7FEE7A0 +:10A89000FEE7FEE7F04F0020EFBEADDEE9980008CE +:10A8A000ED0000081810024004000140140C0140A3 +:10A8B000000C01404434434400F0FF1F2A4910B506 +:10A8C00088420AD1841401212046FFF7F0FB20467C +:10A8D000BDE810400021FFF7EABB2449884202D1BD +:10A8E0000121041404E0224988420AD10121C41341 +:10A8F0002046FFF7E5FB2046BDE810400021FFF7AA +:10A90000DFBB10BD30B502884C8802F441530A8881 +:10A91000CD8822438C882C4322430C8922434C89C6 +:10A9200022438C892243CC8922431A430280828BA2 +:10A9300022F400628283098A018230BD00290188E5 +:10A9400002D041F0400101E021F040010180704758 +:10A9500081817047808970470246002012890A422F +:10A9600000D0012070470000003001400038004056 +:10A97000003C00400048704784D50008A0F1610108 +:10A98000192900D8203870472DE9F05F99461546FF +:10A990000F4683464FF0FF36DDF828A011E0A819D6 +:10A9A000441009FB047080460146584652469047C1 +:10A9B000002802D004DA254603E04046BDE8F09FB7 +:10A9C0002646A5EB06000128E9DC0020F6E740EA70 +:10A9D00001039B0703D009E008C9121F08C0042A1D +:10A9E000FAD203E011F8013B00F8013B521EF9D204 +:10A9F0007047D2B201E000F8012B491EFBD270472C +:10AA00000022F6E710B513460A4604461946FFF73A +:10AA1000F0FF204610BD421E12F8013F002BFBD173 +:10AA200011F8013B02F8013B002BF9D1704730B51A +:10AA300005462A460B4612F8010B13F8014B08B1E4 +:10AA4000A042F8D01CB1002802D06D1CF1E72846C6 +:10AA500030BD10B5044604E00B7800F8013B03B1AB +:10AA6000491C521EF8D2204610BDCAB2401E10F832 +:10AA7000011F8A4202D00029F9D100207047421CF0 +:10AA800010F8011B0029FBD1801A704770B50F4DDB +:10AA900000B92868002412E00A4602E09E4203D072 +:10AAA000521C1378002BF9D1DAB2224305D02BB116 +:10AAB00024B1002100F8011B04E00446401C067884 +:10AAC000002EE9D12860204670BD0000340400202B +:10AAD0002DE9F0410546002090460E46044600E070 +:10AAE000641C44450BD2285D00F058F90746305DE0 +:10AAF00000F054F9381A02D1295D0029F0D1BDE8DF +:10AB0000F08170B5064600F059FC046805460A223B +:10AB10000021304600F048F92C6070BDF0B480EAA6 +:10AB20000102D40F4200B2EB410F02D202460846A6 +:10AB300011464A0042D0C30DDDB2C1F3C752AD1A6F +:10AB4000202D35DAC1F3160141F4000204B152425E +:10AB5000C5F1200602FA06F12A411044B3EBD05F9A +:10AB600023D0C4B1012DA0EBC35009DCF0BC4FF0E1 +:10AB7000004202EAC35200F50000DBB200F055B912 +:10AB8000400000F1807000EBC350A0F1807040EAFB +:10AB9000D170490009E0490841EAC071A0EBC350F7 +:10ABA00000F50000400800EBC350F0BC00F034B9E1 +:10ABB0006142012202EB4101001BF6E7F0BC704745 +:10ABC00081F00041AAE780F00040A7E780EA010297 +:10ABD00010B502F00043400026D04A0023D04FEACF +:10ABE000106101EB1261C0F35600C2F3560240F44B +:10ABF000000042F40002A0FB0220A1F17F014FEA15 +:10AC00000040140401D000F1010050EA124001D4C8 +:10AC10004000491EC2B20C0604EBD010401C400894 +:10AC2000802A02D003E0002010BD20F0010000299E +:10AC300000DA0020184310BD30B480EA010202F0AF +:10AC4000004530F0004221F0004015D0A0B1C0F323 +:10AC5000C753C2F3C754C2F31601C0F31600E41A77 +:10AC600041F4000140F400027D34914201D3641CA0 +:10AC700000E04900002C02DA30BC002070474FF49D +:10AC800000000023914201D3891A034340084FEA90 +:10AC90004101F7D151B1914202D14FF0004105E09D +:10ACA00002D24FF0010101E06FF0010103EBC4504B +:10ACB000284430BC00F0B0B8420005D0C0F3C75201 +:10ACC0005242914201DC0020704700EBC1507047B6 +:10ACD000C10F80EAE0700844CA079623002100F003 +:10ACE000A4B896230022114600F09FB800F000425D +:10ACF00020F00040C10DC0F3160040F400007F2991 +:10AD000001DA00207047962903DCC1F19601C840A2 +:10AD100001E096398840002AF4D04042704720F084 +:10AD20000040C10DC0F3160040F400007F2901DA95 +:10AD300000207047962903DCC1F19601C840704796 +:10AD40009639884070470000002801DBC0F10040C0 +:10AD5000002901DBC1F1004181427047002801DB7D +:10AD6000C0F10040002901DBC1F100418842704779 +:10AD700030B50B46014600202022012409E021FACB +:10AD800002F59D4205D303FA02F5491B04FA02F5C8 +:10AD90002844151EA2F10102F1DC30BDA0F14101F1 +:10ADA000192900D8203070472DE9F04791460F4609 +:10ADB00080460446002614F8015B2DB1FFF7DAFD4A +:10ADC0000068405DC007F6D12B2D02D02D2D18D084 +:10ADD000641E4A463946204600F0E1F927B1396839 +:10ADE000A14201D1C7F8008071054FF002040BD5D4 +:10ADF0004042002803DD00F0E1FA0460A007BDE84E +:10AE0000F08746F48066E4E70028F8DA00F0D6FA26 +:10AE100004606FF00040F2E70029A8BF7047401CB3 +:10AE2000490008BF20F00100704710B4B0FA80FC60 +:10AE300000FA0CF050EA010404BF10BC704749B19D +:10AE4000CCF1200421FA04F411FA0CF118BF01210D +:10AE500021430843A3EB0C01CB1D0106000A002B84 +:10AE6000BEBF002010BC704700EBC3501044002947 +:10AE7000A4BF10BC7047401C490008BF20F001006F +:10AE800010BC7047F0B4002802DCF0BC0020704712 +:10AE9000C0F3C751C0F3160040F40000CA0701D147 +:10AEA0004000491E3F2202EB6105002211464FF48B +:10AEB000000626FA01F31344D418844201D8001B7B +:10AEC0001A464000491C1729F3DD5100814202D285 +:10AED0004FF0FF3100E0002102EBC550F0BCFFF75E +:10AEE0009BBF10B541000CD0C0F3C751962908DCB8 +:10AEF0007E2909DC06DB410204D000F0004040F06E +:10AF00007E5010BD002010BDC1F19604C4F1200197 +:10AF100000FA01F1E040FFF77FFFA04010BD2DE9EE +:10AF2000FE4F804681EA0300C00F0C46009021F0DE +:10AF3000004123F00045B8EB0200A94105D240468C +:10AF4000214690461C460B46024623F00040104323 +:10AF500004D14046214603B0BDE8F08F270DC7F36A +:10AF60000A00C3F30A510290401A0190402866DAA1 +:10AF7000C3F3130040F4801B0098924620B10023D5 +:10AF8000D2EB030A63EB0B0B01985946C0F1400268 +:10AF9000504600F0D3F806460D4650465946019AF1 +:10AFA00000F0EBF810EB08006141002487EA115231 +:10AFB00084EAE7731A433BD0009A3AB3019A012A14 +:10AFC0004FEA075210DC001B61EB02014FF0004218 +:10AFD00002EA0752CDE90042001C41F580113246D9 +:10AFE0002B4600F038F9B6E7001B61EB0201001CAC +:10AFF00041F5801300185B412018A2F5001747EBBC +:10B00000030140EAD570B6196D4111E06D084FEAB1 +:10B01000360645EAC0754FEA0752001B61EB020194 +:10B02000001C41F5801149084FEA300000195141D8 +:10B0300032462B4603B0BDE8F04F00F0FFB8009851 +:10B04000012240000023D0EB020263EBE073009882 +:10B0500021464FEAE074B8EB000061EB0401E9E738 +:10B0600083F000435BE781F0004158E710B500F042 +:10B07000004420F00040C20DC0F3160040F4000070 +:10B080007F2A07DA7D2A00DA7D22763A00FA02F179 +:10B09000002008E0962A09DCA2F1760100FA01F10D +:10B0A000C2F19602D040FFF7B7FE01E0963A904019 +:10B0B000002C00D0404210BD00F0004230F00040B3 +:10B0C0000AD0C10D01F56071C0F3160042EA0151CA +:10B0D000C20840071143704700200146704701F045 +:10B0E000004330B421F0004150EA010206D00A0DBD +:10B0F000A2F56072C1F31301002A02DC30BC00200B +:10B100007047440F44EAC104C100E01830BC00EBB2 +:10B11000C250FFF781BE0000064C074D06E0E06814 +:10B1200040F0010394E8070098471034AC42F6D38E +:10B13000F4F7E0FF1CDF00083CDF0008202A04DBF6 +:10B14000203A00FA02F1002070479140C2F120033A +:10B1500020FA03F3194390407047202A04DB203A79 +:10B1600021FA02F00021704721FA02F3D040C2F127 +:10B1700020029140084319467047202A06DBCB176E +:10B18000203A41FA02F043EAE07306E041FA02F3A2 +:10B19000D040C2F1200291400843194670472DE982 +:10B1A000F05F82460078002715468B460AF10104BD +:10B1B000B946302801D09DB113E014F8010B0127E6 +:10B1C000782803D0582801D045B10AE00DB1102DE0 +:10B1D00007D10027102514F8010B02E0082500E034 +:10B1E0000A250026B0460EE005FB080005FB06F127 +:10B1F000012701EB10461FFA80F8B6F5803F00D317 +:10B20000B94614F8010B294600F077F80028EBDA6C +:10B21000BBF1000F05D00FB1641E00E05446CBF81F +:10B220000040B9F1000F06D000F0C8F8022101601B +:10B23000C81EBDE8F09F48EA0640FAE710B5002BAB +:10B2400008DA401C41F1000192185B411A4301D118 +:10B2500020F0010010BD2DE9F04D92469B4611B142 +:10B26000B1FA81F202E0B0FA80F220329046FFF7A4 +:10B2700065FF04460F4640EA0A0041EA0B015346C7 +:10B280005A46084303D120463946BDE8F08D1146A1 +:10B2900053EA010015D0C8F140025046FFF75DFFA8 +:10B2A00005460E46504659464246FFF747FF0843BB +:10B2B00001D0012000E00020054346EAE0762C435F +:10B2C00037430A984FEA4453A0EB08004FEAD424CE +:10B2D0000A304FF0000244EA47544FEAD72502D51E +:10B2E00000200146D1E7010510196941DDE9084553 +:10B2F00000196941BDE8F04DA0E73A2800D2303886 +:10B3000020F02002412A01D3A2F13700884201D364 +:10B310004FF0FF30704770B501EB020410F8015B8D +:10B3200015F0070301D110F8013B2A1106D110F8DE +:10B33000012B03E010F8016B01F8016B5B1EF9D1E2 +:10B340002B0705D40023521E0FD401F8013BFAE766 +:10B3500010F8013B02F10202A1EB030303E013F832 +:10B36000015B01F8015B521EF9D5A142D6D3002042 +:10B3700070BD00000FB4054B10B503A9044A029834 +:10B3800000F0E8F810BC5DF814FB0000C5240008CC +:10B39000380400204100080218BF04200A0E18BF1C +:10B3A00040F001004FF07F4232EA010108BF40F057 +:10B3B0000200012808BF05207047000000487047C0 +:10B3C0003C0400206FF05E010807FFF775BC000029 +:10B3D0002DE9F04D0E4614464FF07F41B1EB440F7E +:10B3E0009EBF4FF0FF313160BDE8F08D4FF000405F +:10B3F00040EA0421C4F3C7507838431100F01F001D +:10B40000DFF814C1C0F12002FC445CF823500CEBBF +:10B4100083038540D3F804C02CFA02F72F439D68BC +:10B420000CFA00FC25FA02F8DB6805FA00F023FAB2 +:10B4300002F240EA02054CEA080CA7FB0132ACFB21 +:10B4400001C0A5FB015101EB0C058D4234BF4FF04B +:10B45000010C4FF0000CC1186144BCF1000F02D088 +:10B46000814202D903E0814201D2012000E00020A4 +:10B47000104400F120024FEA92188006CA0C40EAFC +:10B4800042304F03C6F80080FFF722FC8246384660 +:10B49000FFF727FC6FF01201FFF70EFC0746284666 +:10B4A000FFF71FFC6FF02501FFF706FC83463946C6 +:10B4B0005046FFF733FB5946FFF730FB00F50065B8 +:10B4C0006FF30B0551462846FFF77AFB3946FFF725 +:10B4D00077FB5946FFF777FB1049FFF777FB0746E5 +:10B4E0000F492846FFF772FB3946FFF717FB07465F +:10B4F0000C492846FFF76AFB3946FFF70FFB14F0AB +:10B50000004F08BFBDE8F08DC8F1805180F00040C9 +:10B510003160BDE8F08D00007C210000DB0FC92FF9 +:10B5200022AAFD290000C92F02E008C8121F08C185 +:10B53000002AFAD170477047002001E001C1121FB4 +:10B54000002AFBD1704700000149086070470000E5 +:10B550003C0400202DE9FF4F8BB09A460F4605466C +:10B560000026C9E0252837D100246D1C6649A04675 +:10B5700001222B78203B02FA03F0084202D0044358 +:10B580006D1CF6E728782E2817D115F8010F44F026 +:10B5900004042A280ED06FF02F022878A0F1300181 +:10B5A00009290AD808EB880102EB410100EB0108E8 +:10B5B0006D1CF2E757F8048B6D1C287869283FD082 +:10B5C00006DC002871D063280CD0642804D137E051 +:10B5D000732811D075284ED052460D99904706F128 +:10B5E000010688E017F8040B8DF8000000208DF8A4 +:10B5F0000100E946012003E057F8049B4FF0FF30BB +:10B6000061074FF0000401D40AE0641C44450DDAE0 +:10B610008442FADB19F804100029F6D106E0641C14 +:10B620008442FCDB19F804100029F8D1264404E018 +:10B6300019F8010B52460D999047641EF8D25AE052 +:10B6400001CF4FF00A0B002804DAC0F100004FF0E0 +:10B650002D0102E0210504D52B218DF824100121B4 +:10B6600003E0E10705D02021F7E70DF1200908915B +:10B670000CE00021F9E701CF4FF00A0BF9E759463A +:10B68000FFF776FB01F1300209F8012D0028F6D111 +:10B69000ADEB090000F1200B600701D44FF0010869 +:10B6A000D84503DDA8EB0B0001E029E0002080462F +:10B6B000002406E009A85246005D0D999047761CCB +:10B6C000641C08988442F5DB04E0302052460D9952 +:10B6D0009047761CB8F10001A8F10108F5DC05E0FF +:10B6E00019F8010B52460D999047761CBBF10001E9 +:10B6F000ABF1010BF4DC6D1C287800287FF432AF2D +:10B700000FB03046BDE8F08F092801002DE9F04761 +:10B710004FF0684202EB40030C460546B3F1654F1B +:10B720003CBF02EB4102B2F1654F3FD34FF07F4285 +:10B73000B2EB400F28BFB2EB410F03D2BDE8F04798 +:10B74000FFF7ECB940EA01035B0008BF44F0FF419A +:10B750000AD0B2EB400F08BFB2EB410F06D125F083 +:10B76000804024F0804105460C461FE0B2EB400FBC +:10B7700012BF5FEA410245F0FF4004F0004115D0DE +:10B780004FEA410292EA400310D4002AB4BF4FF0BE +:10B790003E564FF09F463146FFF718FA05463146B0 +:10B7A0002046FFF713FA044628462146C0F3C75344 +:10B7B000C1F3C7529A1A1B2A06DD10F0004F14BFBE +:10B7C00054485548BDE8F08712F11A0F17DA11F006 +:10B7D000004F06D010F0004F0CBF50485048BDE855 +:10B7E000F08721462846FFF727FA0446FFF7D2FDE7 +:10B7F000042808BFFFF7E6FD2046BDE8F0874200B9 +:10B80000B2EB410F25D910F0004F19BF454F464EFE +:10B81000464F474E224685F0004415460A4680F0C2 +:10B82000004110460A1A5200B2F1807F3ED24840D1 +:10B830004049DFF804A110F0004F18D04FF03F4806 +:10B840003846FFF7BDF9074651463046FFF7B8F9CD +:10B8500017E011F0004F04BF00263746E2D010F089 +:10B86000004F19BF354F364E364F374EDAE74FF09F +:10B870007C583846FFF752F9074651463046FFF7E5 +:10B880004DF9064641462846FFF7A0F92146FFF745 +:10B8900045F9824621464046FFF798F92946FFF7C9 +:10B8A00092F95146FFF7C8F9044604E021462846BC +:10B8B000FFF7C2F904460146FFF788F9804623499D +:10B8C000FFF784F92249FFF729F94146FFF77EF98E +:10B8D0002049FFF723F94146FFF778F91E49FFF7A2 +:10B8E0001DF94146FFF772F91C49FFF717F90546A4 +:10B8F00041462046FFF76AF92946FFF767F93146C6 +:10B90000FFF70CF92146FFF709F93946BDE8F04782 +:10B91000FFF704B9DB0FC9BFDB0FC93FDB0F49409D +:10B92000DB0F49C00000C9BF22AAFDB90000C93F12 +:10B9300022AAFD390060ED3EC30ACE37000049C09F +:10B9400022AA7DBA0000494022AA7D3A2DAD65BDEC +:10B950008FB8D53D0FB511BE61C84C3EA8AAAABE8E +:10B960002DE9F8430446024650486946B0EB420FC1 +:10B9700009D94FF0E640B0EB420F94BF00204FF0E2 +:10B98000FF30009034E04A4B22F0004083422BD934 +:10B9900048492046FFF71AF9FFF7A3FA8046FFF758 +:10B9A000A5F900F00300009043494046FFF70EF967 +:10B9B000054642494046FFF709F9064640494046D8 +:10B9C000FFF704F907463F494046FFF7FFF82146D5 +:10B9D000FFF7F9F83946FFF7F3F83146FFF7F0F8CB +:10B9E0002946FFF7EDF802E01046FFF7F1FC0446A8 +:10B9F0002546009C002C18DA6800B0F17F4F3CBF50 +:10BA00004FF07E50BDE8F88309D14FF00100FFF7F9 +:10BA10009BFDBDE8F84300210846FFF70DB9284615 +:10BA2000BDE8F8430121FFF747B9294614F0010F9B +:10BA300008461CD0FFF7CAF806462349FFF7C6F8A8 +:10BA40002249FFF7C0F83146FFF7C0F82049FFF759 +:10BA500065F83146FFF7BAF82946FFF7B7F82946E7 +:10BA6000FFF75CF814F0020F1CD0BDE8F883FFF775 +:10BA7000ADF805461749FFF7A9F81749FFF74EF843 +:10BA80002946FFF7A3F81549FFF748F82946FFF7BD +:10BA90009DF84FF07E51FFF741F814F0020F08BFF8 +:10BAA000BDE8F88380F00040BDE8F883B61F927EC1 +:10BAB000490E494683F9223F1A61342C0020A233F3 +:10BAC00000A0FD390000C93F336D4C39DA82083CD3 +:10BAD000A0AA2ABEB93AB2BACA9F2A3DDDFFFFBE6C +:10BAE00070B50546FFF7C2FA04464000801C0DD130 +:10BAF0002846FFF7F6F905462046FFF7E9F82946FC +:10BB0000FFF722F91CBF0120FFF71EFD204670BD84 +:10BB10002DE9F04D0F460E46A0F500018046044683 +:10BB20004FF0007084B04FF07E554FF0000B00EBEB +:10BB300047004FF07F4AB1F1FE4F04D2B0F1804F81 +:10BB400080F0018141E0B0F1804F3ED304F1FF402D +:10BB5000B0F1FE4F1FD200BF28F00048C6F3C75017 +:10BB600044467F2809DB97287DDAC0F19600012141 +:10BB700001FA00F0411E314209D00120FFF7E4FC38 +:10BB800004B00021BDE8F04D0846FFF755B830423B +:10BB900018BFFE4DD7E0600000281CBF4FF080703A +:10BBA000B0EB440F0BD91B214046FFF785F88046C8 +:10BBB00004466FF01A0B10F0004FCDD1C3E0A4F58E +:10BBC0000000B0F1FE4F1BD2BDE0B0F1007F11D3F9 +:10BBD00000213846FFF7B8F806D16000002818BFEA +:10BBE000BAEB440F71D8B1E706F0004040F0FC56C4 +:10BBF0003746ABE7B0F1807F38BFA6F50007A5D385 +:10BC000024F000406FF0FF42E14B8118994210D3BD +:10BC100026F000410A449A420BD3B4F17E5F18BF6C +:10BC20005FEA460251D0B0F1FF4F98BFB1F1FF4F2C +:10BC300006D904B039464046BDE8F04DFEF76EBF68 +:10BC4000B4F1FF4F10D0C6F3C7507F2809DB972807 +:10BC500012DAC0F19600012101FA00F0411E3142D2 +:10BC600006D0002009E06EE016F0004F5DD127E01D +:10BC7000304218BF012000D1022014F5000F13D06C +:10BC800024B3B4F1004F27D014F1814F56D04FF0B8 +:10BC9000FE40B0EB440F94BF01200020012101EBD6 +:10BCA000E671884241D10BE016F0004F02D0012826 +:10BCB0003FD03AE0012802BFB64804B0BDE8F08D9D +:10BCC0004FF0FF4004B0BDE8F08D37E016F00040C3 +:10BCD0000ED104B0BDE8F08DB6F1FF4F25D016F5BA +:10BCE000000F05D016F0004F18D008B101280AD077 +:10BCF0000220FFF729FC04B00021BDE8F04D4FF011 +:10BD00007E50FEF799BF0220FFF71EFC04B04146AB +:10BD1000BDE8F04D4FF07E50FEF78EBF002804BF07 +:10BD200004B0BDE8F08D012803D004B00020BDE8C8 +:10BD3000F08D04B04FF00040BDE8F08D04B04FF03E +:10BD40007E50BDE8F08D94482044B0F5005F44D8A3 +:10BD50004046FFF7B1F90022904BFFF781F9FFF75A +:10BD6000BEF904466FF00101FEF7A6FF8C49FEF70D +:10BD70002AFF2146FEF72AFF4FF07C51FEF723FFF2 +:10BD8000064621460846FEF721FF80F00040314676 +:10BD9000FEF71CFF804683492046FEF717FF064644 +:10BDA00081494046FEF712FF804680492046FEF753 +:10BDB0000DFF4146FEF7B2FE044601463046FEF74F +:10BDC000ADFE00F5006B6FF30B0B59463046FEF7E6 +:10BDD000F7FE2146FEF7A2FED4E004F58020C00C59 +:10BDE00000F00F06C0F307107F38A4EBC054834463 +:10BDF0003046FEF76DFF6FF00301FEF75DFF4FF079 +:10BE00007E51FEF78BFE014602902046FEF7D8FEDB +:10BE1000019020460299FEF781FE00F500686FF35D +:10BE20000B08009041460298FEF7CAFE2146FEF735 +:10BE300075FE02904FF07E500099FEF7FDFE014620 +:10BE400000900198FEF7C2FE00F500646FF30B044A +:10BE500020460299FEF7BAFE029041462046FEF7C0 +:10BE6000B5FE0199FEF7AFFE0299FEF7A9FE009913 +:10BE7000FEF7ACFE014600902046FEF74FFE01465D +:10BE8000FEF7A4FE80464A49FEF7A0FE4449FEF7AD +:10BE900045FE4146FEF79AFE804600212046FEF709 +:10BEA0000BFF019020460099FEF738FE4146FEF751 +:10BEB0008DFE044600210098FEF7FEFE2146FEF7A7 +:10BEC0002DFE804601460198FEF728FE00F500642D +:10BED0006FF30B0421460198FEF772FE4146FEF710 +:10BEE0001DFE804633492046FEF770FE0090324921 +:10BEF0004046FEF76BFE804630492046FEF766FE60 +:10BF00004146FEF70BFE804601460098FEF706FE0E +:10BF100000F500646FF30B0421460098FEF750FE15 +:10BF20004146FEF7FBFD80462548784450F8361020 +:10BF300000EBC600019146684FEA0B10FEF7C8FE01 +:10BF4000009031464046FEF7E9FD2146FEF7E6FD4A +:10BF50000199FEF7E3FD0099FEF7E0FD00F5006BA7 +:10BF60006FF30B0B58460099FEF72AFE0199FEF776 +:10BF700027FE2146FEF724FE3146FEF721FE41460C +:10BF8000FEF721FE804607F500641BE0000080BF3D +:10BF9000FFFF3F00000080FF001080C00000F03F66 +:10BFA000ABAAAA3E00B0B8413BAAB841D49A38BB6C +:10BFB0007EE24C3E00B038423BAA3842D49AB8BB2D +:10BFC000921400006FF30B0421463846FEF7F8FD8B +:10BFD000074621465846FEF7F9FD064639462046F3 +:10BFE000FEF79CFD4146FEF7F1FD044639465846F2 +:10BFF000FEF7ECFD2146FEF791FD0746014630466F +:10C00000FEF78CFD00F500646FF30B04214630460B +:10C01000FEF7D6FD3946FEF781FD804601462046F3 +:10C02000FEF77CFDFFF722F807460611FEF750FEEB +:10C030002146FEF7C8FD4146FEF770FD044635492E +:10C04000FEF7C4FD3449FEF769FD2146FEF7BEFD4B +:10C050003249FEF763FD2146FEF7B8FD0146304840 +:10C0600007F00F04784450F82400FEF7AFFD2D4987 +:10C07000794451F82410FEF751FD2B49794451F8C9 +:10C080002410FEF74BFD06F17D01FC2908D2314654 +:10C09000FEF712FE04B02946BDE8F04DFEF796BD4E +:10C0A00006F1BF01B1F5BF7F16D83146FEF704FE99 +:10C0B0002946FEF78BFD0446BAEB440F1AD0600008 +:10C0C0000CD02046FFF766F9042808BFFFF77AF97D +:10C0D000204604B0BDE8F08D002E0BDA0220FFF7F9 +:10C0E00033FAFFF76FF90146284604B061F31E00EA +:10C0F000BDE8F08D0220FFF727FA61214FF0E04004 +:10C10000FEF7DAFD0146284604B061F31E00BDE8E3 +:10C11000F08D0000FC596337C9FF753A1872313D44 +:10C12000581400000C140000C01300002DE9F8435F +:10C130000446024653486946B0EB420F09D94FF016 +:10C14000E640B0EB420F94BF00204FF0FF3000906C +:10C1500034E04D4B22F0004083422BD94B4920461E +:10C16000FEF734FDFEF7BDFE8046FEF7BFFD00F092 +:10C170000300009046494046FEF728FD0546454924 +:10C180004046FEF723FD064643494046FEF71EFDA6 +:10C19000074642494046FEF719FD2146FEF713FDCA +:10C1A0003946FEF70DFD3146FEF70AFD2946FEF73A +:10C1B00007FD02E01046FFF70BF904462546009CF8 +:10C1C000002C1DDA6800B0F17F4F09D22846FFF736 +:10C1D000E1F8042808BFFFF7F5F82846BDE8F88322 +:10C1E00008D10120FFF7B0F9BDE8F8430021084667 +:10C1F000FEF722BD2846BDE8F8430121FEF75CBDED +:10C20000294614F0010F08461ED0FEF7DFFC054654 +:10C210002349FEF7DBFC2349FEF780FC2946FEF7A5 +:10C22000D5FC2149FEF77AFC2946FEF7CFFC4FF0FA +:10C230007E51FEF773FC14F0020F08BFBDE8F883CF +:10C2400080F00040BDE8F883FEF7C0FC06461749C1 +:10C25000FEF7BCFC1649FEF7B6FC3146FEF7B6FC0D +:10C260001449FEF75BFC3146FEF7B0FC2946FEF7A9 +:10C27000ADFC2946FEF752FC14F0020FE0D1BDE8F8 +:10C28000F8830000B61F927E490E494683F9223F8B +:10C290001A61342C0020A23300A0FD390000C93FF0 +:10C2A000B93AB2BACA9F2A3DDDFFFFBE336D4C39A1 +:10C2B000DA82083CA0AA2ABE70B50546FEF7E2FD68 +:10C2C000044620F00040C0F1FF40C00F08D025F028 +:10C2D0000040C0F1FF40C00F04BF0120FFF734F958 +:10C2E000204670BD41D600089ED60008FCD6000846 +:10C2F0003ED6000845D60008DDD50008D8D5000890 +:10C300002CD60008CDD50008F6D60008E0D50008E8 +:10C31000AFD600080BD70008F7D500086FD6000885 +:10C3200008D60008C6D5000838D6000891D60008FF +:10C33000D7D60008CAD6000868D60008000000005A +:10C340007DD60008E6D600084CD6000802D70008C3 +:10C35000A4D60008EBD6000814D6000823D600089F +:10C36000E2D60008EED50008B9D6000815D70008B7 +:10C37000BFD6000881D60008EBD500085DD60008BE +:10C38000000000008CD60008E7D5000887D600081A +:10C3900004D60008B9D60008E2D6000800D6000886 +:10C3A000000000009ADD0008D0D50008B7D50008CD +:10C3B0005ADD0008BFD5000872D800080000000050 +:10C3C00075DD000808DD00083303000870DD000893 +:10C3D000FCDB00088703000855DC0008B6DC000819 +:10C3E000A9060008CCDB0008E3DA00085B070008B8 +:10C3F00083DC00089ADD0008D10800089BD80008FB +:10C400004EDA0008F5080008B6D9000805DA000879 +:10C41000C1090008C7DB00089ADD0008D909000837 +:10C42000C3DB0008D1DB0008050A00080ADC0008AD +:10C43000D3DC0008D50C000842DC000810D9000845 +:10C440005B0D000823D80008A8D50008EB0D0008F4 +:10C450002BD90008A6DC0008AB0800087FDC000828 +:10C46000E6DC0008250E000878DC00086CDC00081B +:10C47000690F000820DB00089ADD0008131000088F +:10C4800069D80008020000007C04002000000000C1 +:10C490002823000029D7000802000000840500209E +:10C4A000B0040000A406000051D8000802000000FB +:10C4B0004005002000000000D00700005DD8000803 +:10C4C000020000004205002000000000D00700002C +:10C4D000D3D700080200000044050020000000003F +:10C4E000D0070000E4D90008020000008605002003 +:10C4F00000000000D0070000EDD900080200000095 +:10C500008805002000000000D00700004BDD000877 +:10C51000020000004605002000000000D0070000D7 +:10C52000A6D9000802000000480500200000000015 +:10C53000D00700002FD70008020000004A050020A5 +:10C5400000000000D00700002BD800080200000007 +:10C550004C05002000000000D0070000CAD80008E9 +:10C56000020000004E05002032000000F201000031 +:10C57000BBD8000802000000500500203200000077 +:10C58000F2010000D6DA0008000000008A05002051 +:10C59000000000000100000058D700080000000063 +:10C5A0008B0500200000000064000000EBD80008AC +:10C5B0000400000090050020B004000000C201004B +:10C5C000E7D8000804000000940500208025000042 +:10C5D000004B000064D70008000000009805002010 +:10C5E000000000000100000077D8000800000000F3 +:10C5F0008D0500200000000003000000FBD80008AB +:10C60000010000008E050020FFFFFFFF0400000076 +:10C6100080D8000800000000820500200000000013 +:10C62000020000001FDA0008000000009905002049 +:10C63000000000000100000019D800080000000000 +:10C64000760500200A000000C8000000F1D70008AD +:10C6500000000000770500200A0000003200000002 +:10C66000DED7000800000000780500200A00000066 +:10C670003200000062DA00080000000079050020A6 +:10C68000000000000900000087DB00080000000037 +:10C690005205002000000000080000001FD700081D +:10C6A000000000005305002000000000080000000A +:10C6B00056D90008000000005405002000000000CA +:10C6C00008000000A9DA0008030000005605002059 +:10C6D0004CFFFFFF6801000075D90008030000004F +:10C6E000580500204CFFFFFF680100002FDD000807 +:10C6F000030000005A0500204CFFFFFF6801000006 +:10C7000038DB0008010000005C050020FFFFFFFF90 +:10C71000010000008ED80008000000005D05002028 +:10C72000000000000500000080D7000800000000A5 +:10C730006805002000000000800000004DD90008BE +:10C74000020000005E050020000000000001000063 +:10C750001FDC0008020000006005002064000000EB +:10C76000E803000030DC0008020000006205002041 +:10C7700064000000E8030000EDDB0008000000009A +:10C78000EC0700200000000001000000CAD70008EC +:10C7900000000000520800200000000020000000FF +:10C7A000C7D7000800000000530800200000000068 +:10C7B0006400000034DA0008000000005408002083 +:10C7C00001000000FA00000004D80008000000008A +:10C7D0005508002000000000010000005CDB00089C +:10C7E0000000000056080020000000006400000067 +:10C7F000A3D80008000000000B0800200000000083 +:10C80000FA00000076DB0008000000000C080020A1 +:10C81000000000006400000078D70008000000005D +:10C820000D08002000000000640000007EDB00080E +:10C83000000000000E08002000000000640000005E +:10C84000ABD80008000000000F0800200000000026 +:10C850006400000008D90008000000001008002053 +:10C86000000000006400000079DD00080000000006 +:10C870009808002000000000C800000088DD0008C3 +:10C88000000000009908002000000000C80000001F +:10C890003FD80008020000009A080020E8030000CA +:10C8A000D007000090D70008020000009C0800207C +:10C8B00064000000D007000074DA000801000000E6 +:10C8C0008C05002000000000040000004EDB000882 +:10C8D000010000009E080020FFFFFFFF0100000094 +:10C8E00092DB0008010000009F080020000000000B +:10C8F0000100000048DC000800000000A008002043 +:10C9000000000000FF00000010DC00080000000034 +:10C910001808002000000000FA000000AAD7000854 +:10C92000000000001A080020000000006400000061 +:10C93000B9D700080000000019080020000000001E +:10C9400064000000F6D9000800000000280800205C +:10C9500000000000010000008FD900080300000063 +:10C9600016080020D4FEFFFF2C010000C1DA0008E9 +:10C970000300000014080020D4FEFFFF2C0100007B +:10C9800030D90008000000001B0800200000000053 +:10C99000300000003ED90008050000001C080020FF +:10C9A000000000000100000085DA0008050000001A +:10C9B0002008002000000000010000008EDC0008BC +:10C9C0000500000024080020000000000100000015 +:10C9D00028DB00080300000012080020B0B9FFFFA8 +:10C9E00050460000AFDB000800000000F107002007 +:10C9F00000000000C8000000D0D9000800000000BE +:10CA0000FB07002000000000C800000044D7000819 +:10CA1000000000000508002000000000C800000021 +:10CA2000A4DB000800000000F20700200000000066 +:10CA3000C8000000C5D9000800000000FC07002065 +:10CA400000000000C800000039D700080000000006 +:10CA50000608002000000000C8000000B9DB000844 +:10CA600000000000F307002000000000C8000000E4 +:10CA7000DAD9000800000000FD07002000000000D7 +:10CA8000C80000004ED70008000000000708002082 +:10CA900000000000C80000005EDC0008020000008A +:10CAA000A208002000000000D007000060D90008A4 +:10CAB00000000000A60800200000000001000000A7 +:10CAC00012DB000802000000A80800200A00000095 +:10CAD000D007000062DD000802000000AA08002064 +:10CAE0000A000000D0070000D9D8000800000000AC +:10CAF000A508002000000000640000009ED9000886 +:10CB000000000000EE07002000000000C800000048 +:10CB100087D9000800000000F8070020000000008E +:10CB2000C80000007FD900080000000002080020B3 +:10CB300000000000C8000000CFDA0008000000007C +:10CB4000ED07002000000000C8000000BADA00086D +:10CB500000000000F707002000000000C8000000EF +:10CB6000B3DA000800000000010800200000000007 +:10CB7000C800000045DD000800000000EF070020AD +:10CB800000000000C80000003FDD000800000000B9 +:10CB9000F907002000000000C800000039DD00088F +:10CBA000000000000308002000000000C800000092 +:10CBB000A0DC000800000000F007002000000000DA +:10CBC000C80000009ADC000800000000FA070020FE +:10CBD00000000000C800000088DC00080000000021 +:10CBE0000408002000000000C8000000A1DA0008CE +:10CBF00000000000F407002000000000C800000052 +:10CC000099DA000800000000FE0700200000000084 +:10CC1000C800000091DA00080000000008080020A9 +:10CC200000000000C8000000414552543132333446 +:10CC3000000000000000803F00000000A8AAAA3FFA +:10CC4000000000000000803F000080BFB0AA2ABFA3 +:10CC5000000000000000803F0000803FB0AA2ABF13 +:10CC6000000000000000803F000000000000803F46 +:10CC7000000080BF0000803F000080BF0000000077 +:10CC80000000803F0000803F0000803F0000000067 +:10CC90000000803F0000803F00000000000080BFD7 +:10CCA000000080BF0000803F000080BF0000803F88 +:10CCB000000080BF0000803F000080BF000080BFF8 +:10CCC0000000803F0000803F0000803F0000803F68 +:10CCD0000000803F0000803F0000803F000080BFD8 +:10CCE000000080BF0000803F0000803F0000000087 +:10CCF000000000000000803F000080BF0000000036 +:10CD0000000000000000803F00000000A8AAAA3F29 +:10CD10000000803F0000803F000080BFB0AA2ABF13 +:10CD2000000080BF0000803F0000803FB0AA2ABF03 +:10CD3000000080BF0000803F00000000A8AAAA3FBA +:10CD4000000080BF0000803F000080BFB0AA2ABF63 +:10CD50000000803F0000803F0000803FB0AA2ABF53 +:10CD60000000803F0000803F000080BFD0B35D3FE7 +:10CD70000000803F0000803F000080BFD0B35DBF57 +:10CD8000000080BF0000803F0000803FD0B35D3FC7 +:10CD90000000803F0000803F0000803FD0B35DBFB7 +:10CDA000000080BF0000803F00000000D0B35DBFE6 +:10CDB0000000803F0000803F00000000D0B35D3FD6 +:10CDC000000080BF0000803F000000000000803FA6 +:10CDD000000080BF0000803F000080BF000080BFD7 +:10CDE000000000000000803F000000000000803FC5 +:10CDF0000000803F0000803F0000803F000080BFB7 +:10CE0000000000000000803FD0B35DBF0000803F05 +:10CE10000000803F0000803FD0B35DBF000080BFB6 +:10CE20000000803F0000803FD0B35D3F0000803FA6 +:10CE3000000080BF0000803FD0B35D3F000080BF96 +:10CE4000000080BF0000803FD0B35DBF0000000045 +:10CE5000000080BF0000803FD0B35D3F00000000B5 +:10CE60000000803F0000803F000080BF0000803F46 +:10CE7000000080BF0000803F000080BF000080BF36 +:10CE80000000803F0000803F0000803F0000803FA6 +:10CE90000000803F0000803F0000803F000080BF16 +:10CEA000000080BF0000803F000080BF0000803F86 +:10CEB0000000803F0000803F000080BF000080BF76 +:10CEC000000080BF0000803F0000803F0000803FE6 +:10CED000000080BF0000803F0000803F000080BF56 +:10CEE0000000803F0000803FF704353FF70435BF66 +:10CEF0000000803F0000803FF70435BFF70435BFD6 +:10CF00000000803F0000803FF70435BFF704353F45 +:10CF10000000803F0000803FF704353FF704353FB5 +:10CF20000000803F0000803F00000000000080BF44 +:10CF3000000080BF0000803F000080BF00000000B4 +:10CF4000000080BF0000803F000000000000803F24 +:10CF5000000080BF0000803F0000803F0000000014 +:10CF6000000080BF0000803F0000803F000000BF45 +:10CF70000000803F0000803F000000BF000080BF35 +:10CF80000000803F0000803F000080BF0000003FA5 +:10CF90000000803F0000803F0000003F0000803F15 +:10CFA0000000803F0000803F0000003F000080BF85 +:10CFB000000080BF0000803F000080BF000000BF75 +:10CFC000000080BF0000803F000000BF0000803FE5 +:10CFD000000080BF0000803F0000803F0000003F55 +:10CFE000000080BF0000803F000000000000803F84 +:10CFF0000000803F0000803F000080BF000080BF35 +:10D00000000000000000803F000000000000803FA2 +:10D01000000080BF0000803F0000803F000080BF14 +:10D02000000000800000803F000080BF0000803FC3 +:10D03000000080BF0000803F000080BF000080BF74 +:10D040000000803F0000803F0000803F0000803FE4 +:10D050000000803F0000803F0000803F000080BF54 +:10D06000000080BF0000803F0000000000000000C2 +:10D07000000000000000803F0000000000000000F1 +:10D08000000000000000803F0000000000000000E1 +:10D09000000080BF0000803F000000000000000092 +:10D0A0000000803F000000000000000003010000BD +:10D0B00034CC00080400000064CC00080400000028 +:10D0C000A4CC000802010000E4CC0008000100002C +:10D0D000000000000600000004CD0008060000006B +:10D0E00064CD000801010000000000000400000001 +:10D0F000C4CD00080600000004CE000808000000AF +:10D1000064CE000808000000E4CE0008080000001B +:10D1100064CF0008010100000000000000010000D1 +:10D1200000000000000100000000000004000000FA +:10D13000E4CF00080600000024D000080001000031 +:10D14000000000000201000084D00008010100007E +:10D15000000000000000000000000000524F4C4C96 +:10D160003B50495443483B5941573B414C543B5039 +:10D170006F733B506F73523B4E6176523B4C45563A +:10D18000454C3B4D41473B56454C3B0000C20100DE +:10D19000E1DE000804DF000800E10000BFDE000857 +:10D1A000ABDE00080096000075DE000897DE000880 +:10D1B000004B000053DE00083FDE00088025000021 +:10D1C0009ADD00089ADD0008B56206010300F0054B +:10D1D00000FF19B56206010300F00300FD15B562FA +:10D1E00006010300F00100FB11B56206010300F027 +:10D1F0000000FA0FB56206010300F00200FC13B54F +:10D200006206010300F00400FE17B5620601030088 +:10D210000102010E47B562060103000103010F4937 +:10D22000B56206010300010601124FB56206010353 +:10D23000000112011E67B56206160800030703000D +:10D24000510800008A41B56206080600C8000100C6 +:10D250000100DE6A1048494A4B4C4D44454647FFA1 +:10D26000202122232425262748494A4B4C4DFF10D4 +:10D2700048498A8B8C8D84858687FF202122232430 +:10D2800025262748498A8B8C8DFF000060D2000834 +:10D2900054D200087BD200086FD20008000C014075 +:10D2A00008001002000C01401000100200080140AC +:10D2B0000010140231860008CD85000801860008A0 +:10D2C0004F850008E7850008000000400008014085 +:10D2D00001000000001C00000000004000080140A8 +:10D2E00002000000041C0000000000400008014093 +:10D2F00004000000081C000000000040000801407D +:10D30000080000000C1C0000000400400008014060 +:10D3100040000000001D0000000400400008014023 +:10D3200080000000041D000000040040000C0140CB +:10D3300001000000081D000000040040000C014036 +:10D34000020000000C1D0000002C014000080140FC +:10D3500000010000001B0100002C014000080140FA +:10D36000000800000C1B010000080040000C0140F8 +:10D3700040000000001E000000080040000C0140BA +:10D3800080000000041E000000080040000C014066 +:10D3900000010000081E000000080040000C0140D1 +:10D3A000000200000C1E00000004080CAF970008EB +:10D3B0006797000889970008C79700083B96000800 +:10D3C00000000000000000000000B33FB2BE7D3A44 +:10D3D00000002E40DFCF513800007E40BF51FABA26 +:10D3E00000E0A44019DAC3BA00E0C840C2ED8AB92F +:10D3F0000040EB40CD1F2CBA001006412AFFFABABC +:10D4000000C01541DFCFD13700D024419A97703A40 +:10D410000050334189478E3600404141E75B9D38DB +:10D4200000B04E41C00A98B900A05B41558F943AB4 +:10D4300000306841DA92C0BA0040744162B3C63A23 +:10D440000000803F00A0853F00908B3F00C0913FCF +:10D450000030983F00F09E3F00F0A53F0050AD3FE8 +:10D460000000B53F0000BD3F0060C53F0020CE3F3B +:10D470000040D73F00C0E03F00C0EA3F0020F53F3A +:10D48000000000007D36AC397D3C3839EBDCF438E7 +:10D49000320A7E39124C26399B6AED39A4EE833963 +:10D4A0007F661E39F6398A392B426539A4821139D3 +:10D4B0005B991F39C3EECD39DDE7C637A5A22F39F9 +:10D4C0000000803FC3AA853FC2958B3FD3C3913FE5 +:10D4D000F037983F32F59E3FD7FEA53F3F58AD3F0E +:10D4E000F304B53FA408BD3F2A67C53F8C24CE3F57 +:10D4F000FD44D73FDFCCE03FC7C0EA3F7D25F53F85 +:10D500000040404040404040404041414141414056 +:10D51000404040404040404040404040404040400B +:10D52000400502020202020202020202020202029A +:10D53000022020202020202020202002020202029F +:10D5400002029090909090901010101010101010F7 +:10D550001010101010101010101010100202020203 +:10D560000202888888888888080808080808080847 +:10D570000808080808080808080808080202020243 +:10D580004000000001D50008000000006E83F9A2F1 +:10D590002915444ED15727FCC0DD34F5999562DB3F +:10D5A0004190433CAB6351FE696E6465782028303E +:10D5B00020746F203229004D5055363035300042EE +:10D5C0004D4132383000565441494C3400593400F2 +:10D5D0004144584C333435004845583600593600DC +:10D5E0004F43544F583800414343003344004641B1 +:10D5F000494C5341464500414952504C414E45002B +:10D600004750532B4D41470048454C495F39305FE7 +:10D61000444547004759524F5F534D4F4F54484977 +:10D620004E47004C45445F52494E4700464C5949CD +:10D630004E475F57494E47004845583648004249D3 +:10D64000005452490047494D42414C00494E464C16 +:10D65000494748545F4143435F43414C00534F4661 +:10D660005453455249414C00435553544F4D004883 +:10D67000454C495F3132305F4343504D0050504D6F +:10D6800000564152494F004241524F004759524FB4 +:10D690000050504D5F544F5F534552564F00515507 +:10D6A000414450004D4F544F525F53544F50004F20 +:10D6B00043544F464C41545000534F4E415200503A +:10D6C0004F5745524D455445520053494E474C45DE +:10D6D000434F50544552004455414C434F505445DC +:10D6E0005200475053005642415400534552564F42 +:10D6F0005F54494C540048455836580051554144F0 +:10D70000580053455249414C5258004F43544F46DC +:10D710004C4154580054454C454D455452590061B4 +:10D720006C69676E5F616363006D69647263006E4C +:10D7300065757472616C3364006770735F706F73CA +:10D74000725F64006770735F706F735F640067700F +:10D75000735F6E61765F6400666C6170735F737097 +:10D7600065656400736F667473657269616C5F6987 +:10D770006E766572746564007468725F6D696400CA +:10D780006D6F726F6E5F7468726573686F6C640042 +:10D790006661696C736166655F6465746563745F17 +:10D7A0007468726573686F6C640061636378795F35 +:10D7B0006465616462616E64006163637A5F64657D +:10D7C000616462616E64007961776465616462615D +:10D7D0006E64006D696E636F6D6D616E640076627C +:10D7E00061746D696E63656C6C766F6C746167658E +:10D7F00000766261746D617863656C6C766F6C74D1 +:10D8000061676500616C745F686F6C645F6661730B +:10D81000745F6368616E67650076626174736361EB +:10D820006C650070726F66696C6500646561646246 +:10D83000616E6433645F7468726F74746C650066E3 +:10D8400061696C736166655F7468726F74746C652E +:10D85000006D696E7468726F74746C65006D6178C8 +:10D860007468726F74746C65006C6F6F7074696D3E +:10D8700065004E6F6E65006770735F747970650048 +:10D8800073657269616C72785F7479706500616349 +:10D89000635F686172647761726500666561747563 +:10D8A00072650072635F7261746500726F6C6C5FA9 +:10D8B00070697463685F7261746500736572766F16 +:10D8C0005F70776D5F72617465006D6F746F725F0A +:10D8D00070776D5F72617465006E61765F736C6501 +:10D8E000775F7261746500736F66747365726961E6 +:10D8F0006C5F6261756472617465006770735F620A +:10D900006175647261746500796177726174650034 +:10D910006765742F736574206D6F746F72206F75F7 +:10D92000747075742076616C75650073617665003E +:10D930006261726F5F7461625F73697A65006261D0 +:10D94000726F5F6E6F6973655F6C70660067797286 +:10D950006F5F6C706600616C69676E5F6D61670018 +:10D960006E61765F636F6E74726F6C735F68656112 +:10D9700064696E6700616C69676E5F626F61726493 +:10D980005F706974636800695F70697463680061DF +:10D9900063635F7472696D5F706974636800705F60 +:10D9A0007069746368006465616462616E643364A5 +:10D9B0005F68696768006770737061737374687219 +:10D9C0006F756768006770735F706F73725F69006F +:10D9D0006770735F706F735F69006770735F6E610C +:10D9E000765F69006D696E636865636B006D617871 +:10D9F000636865636B006163635F756E61726D651B +:10DA00006463616C00706173737468726F756768CA +:10DA10002067707320746F2073657269616C007485 +:10DA2000656C656D657472795F736F66747365722A +:10DA300069616C00616C745F686F6C645F746872BC +:10DA40006F74746C655F6E65757472616C006C697F +:10DA50007374206F72202D76616C206F7220766156 +:10DA60006C00706F7765725F6164635F6368616E9D +:10DA70006E656C00727373695F6175785F6368616E +:10DA80006E6E656C006261726F5F63665F76656C77 +:10DA900000645F6C6576656C00695F6C6576656CCB +:10DAA00000705F6C6576656C00616C69676E5F62C3 +:10DAB0006F6172645F726F6C6C00695F726F6C6C27 +:10DAC000006163635F7472696D5F726F6C6C00708C +:10DAD0005F726F6C6C0072657461726465645F6123 +:10DAE000726D007072696E7420636F6E666967751F +:10DAF0007261626C652073657474696E6773206906 +:10DB00006E2061207061737461626C6520666F7253 +:10DB10006D006E61765F73706565645F6D696E0040 +:10DB200076657273696F6E006D61675F6465636CC3 +:10DB3000696E6174696F6E007961775F636F6E748F +:10DB4000726F6C5F646972656374696F6E0079618E +:10DB5000775F646972656374696F6E007468726F71 +:10DB600074746C655F616E676C655F636F7272651C +:10DB70006374696F6E0072635F6578706F007468BC +:10DB8000725F6578706F00616C69676E5F6779724C +:10DB90006F007472695F756E61726D65645F736545 +:10DBA00072766F006770735F706F73725F7000677B +:10DBB00070735F706F735F70006770735F6E617614 +:10DBC0005F70006D61700068656C700064756D70E9 +:10DBD000006D617070696E67206F662072632063EC +:10DBE00068616E6E656C206F726465720070696446 +:10DBF0005F636F6E74726F6C6C65720064657369DD +:10DC0000676E20637573746F6D206D69786572003F +:10DC10006163635F6C70665F666163746F720067F7 +:10DC200079726F5F636D70665F666163746F7200B7 +:10DC30006779726F5F636D70666D5F666163746F45 +:10DC400072006D6F746F720067696D62616C5F6600 +:10DC50006C6167730064656661756C7473006770EE +:10DC6000735F77705F7261646975730073686F7753 +:10DC70002073797374656D207374617475730073A8 +:10DC80006574006578697400645F616C740062613A +:10DC9000726F5F63665F616C7400695F616C7400D2 +:10DCA000705F616C74007361766520616E642072D0 +:10DCB00065626F6F7400726573657420746F2064A1 +:10DCC000656661756C747320616E64207265626F45 +:10DCD0006F74006D69786572206E616D65206F727A +:10DCE000206C697374006E616D653D76616C75655D +:10DCF000206F7220626C616E6B206F72202A20662A +:10DD00006F72206C69737400666561747572655F0B +:10DD10006E616D6520617578666C6167206F722039 +:10DD2000626C616E6B20666F72206C697374006147 +:10DD30006C69676E5F626F6172645F7961770069B9 +:10DD40005F79617700705F79617700646561646213 +:10DD5000616E6433645F6C6F77004D4D41383435CC +:10DD600078006E61765F73706565645F6D617800E1 +:10DD7000636D697800617578006661696C736166CE +:10DD8000655F64656C6179006661696C7361666585 +:10DD90005F6F66665F64656C61790043414D535403 +:10DDA00041423B0043414C49423B004750532048CD +:10DDB0004F4C443B0048454144465245453B004199 +:10DDC0004E474C453B0047505320484F4D453B0084 +:10DDD0004D41473B0043414D545249473B00484564 +:10DDE000414441444A3B0041524D3B00484F524957 +:10DDF0005A4F4E3B00564152494F3B004241524F11 +:10DE00003B004245455045523B00474F5645524E18 +:10DE10004F523B004C4C49474854533B00504153F0 +:10DE200053544852553B004C45444C4F573B004FD0 +:10DE300053442053573B004C45444D41583B00242C +:10DE4000504D544B3235312C31393230302A323248 +:10DE50000D0A0024505542582C34312C312C3030CE +:10DE600030332C303030312C31393230302C302AB4 +:10DE700032330D0A0024505542582C34312C312CA9 +:10DE8000303030332C303030312C33383430302C8B +:10DE9000302A32360D0A0024504D544B3235312C85 +:10DEA00033383430302A32370D0A0024504D544B69 +:10DEB0003235312C35373630302A32430D0A0024C2 +:10DEC000505542582C34312C312C303030332C30DA +:10DED0003030312C35373630302C302A32440D0A70 +:10DEE0000024505542582C34312C312C30303033F2 +:10DEF0002C303030312C3131353230302C302A3129 +:10DF0000450D0A0024504D544B3235312C313135FA +:10DF10003230302A31460D0A000000003CDF000894 +:10DF2000000000204004000016B300082CE00008A8 +:10DF3000400400205025000038B500080196032059 +:10DF40007A44CBDC050281023701136934025C0894 +:10DF5000021A030936B3914BE7DDBC29491ABF0CFD +:10DF6000290832021AEC0C2908297C1AFC0C290811 +:10DF700032041AF50C290832051AD00C2908320689 +:10DF80001AB50C290832071ADE0C290829591A9BE0 +:10DF90000C290832091AD50C2908320A1AC60C298C +:10DFA00008320B1AAB0C2908320C131DDE2A0808A4 +:10DFB0002A0D88190C2908320E1A370C2908320F3D +:10DFC0001A270C290832101A140C290832111AA425 +:10DFD0004829082A12641918290832131A2F0C2903 +:10DFE00008721402A7FF021001E20452038B803F63 +:10DFF0000401165A03494AD931E91D12010A1C02CB +:10E0000085C208342C01401A408C1A40193A405BF2 +:10E0100014A24A048B127A33380B02030406070851 +:0CE02000090204063B29106914C100002D :04000005080000ED02 :00000001FF diff --git a/src/mixer.c b/src/mixer.c index 9af75496a..f0c0ecf2c 100755 --- a/src/mixer.c +++ b/src/mixer.c @@ -263,10 +263,6 @@ void writeServos(void) } break; - case MULTITYPE_AIRPLANE: - - break; - case MULTITYPE_FLYING_WING: pwmWriteServo(0, servo[3]); pwmWriteServo(1, servo[4]); @@ -282,6 +278,7 @@ void writeServos(void) pwmWriteServo(1, servo[5]); break; + case MULTITYPE_AIRPLANE: case MULTITYPE_SINGLECOPTER: pwmWriteServo(0, servo[3]); pwmWriteServo(1, servo[4]); From b12e98316c0f24f9c059f07341e22e47cbc38711 Mon Sep 17 00:00:00 2001 From: Moritz Ulrich Date: Mon, 25 Nov 2013 02:18:50 +0100 Subject: [PATCH 52/56] Fix telemetry altitude. Frsky assumes a positive after-decimal uint16. Signed-off-by: Moritz Ulrich --- src/telemetry.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/telemetry.c b/src/telemetry.c index 0e92ecb22..1ab9cabd3 100644 --- a/src/telemetry.c +++ b/src/telemetry.c @@ -96,7 +96,7 @@ static void sendBaro(void) sendDataHead(ID_ALTITUDE_BP); serialize16(BaroAlt / 100); sendDataHead(ID_ALTITUDE_AP); - serialize16(BaroAlt % 100); + serialize16(abs(BaroAlt % 100)); } static void sendTemperature1(void) From 5c733665de0bc47204b3a9edb69e52e0a2b22e6e Mon Sep 17 00:00:00 2001 From: Moritz Ulrich Date: Mon, 25 Nov 2013 02:57:53 +0100 Subject: [PATCH 53/56] Telemetry: Send opentx variometer values. Signed-off-by: Moritz Ulrich --- src/telemetry.c | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/src/telemetry.c b/src/telemetry.c index 1ab9cabd3..39c251539 100644 --- a/src/telemetry.c +++ b/src/telemetry.c @@ -45,6 +45,8 @@ #define ID_GYRO_Y 0x41 #define ID_GYRO_Z 0x42 +#define ID_VERT_SPEED 0x30 //opentx vario + // from sensors.c extern uint8_t batteryCellCount; @@ -135,6 +137,16 @@ static void sendGPS(void) serialize16(GPS_coord[LON] < 0 ? 'W' : 'E'); } +/* + * Send vertical speed for opentx. ID_VERT_SPEED + * Unit is cm/s + */ +static void sendVario(void) +{ + sendDataHead(ID_VERT_SPEED); + serialize16(vario); +} + /* * Send voltage via ID_VOLT * @@ -246,6 +258,7 @@ void sendTelemetry(void) // Sent every 125ms sendAccel(); + sendVario(); sendTelemetryTail(); if ((cycleNum % 4) == 0) { // Sent every 500ms From 49727709071da8bfa3eae2f6932b0f6b44cf1ff4 Mon Sep 17 00:00:00 2001 From: dongie Date: Tue, 26 Nov 2013 11:31:23 +0900 Subject: [PATCH 54/56] correction of calculation for throttle angle correction (should really just replace with cosf() at some point --- src/imu.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/imu.c b/src/imu.c index d4a738006..e14fb3280 100755 --- a/src/imu.c +++ b/src/imu.c @@ -315,7 +315,7 @@ static void getEstimatedAttitude(void) acc_calc(deltaT); // rotate acc vector into earth frame if (cfg.throttle_angle_correction) { - int cosZ = EstG.V.Z / acc_1G * 100.0f; + int cosZ = EstG.V.Z / (acc_1G * 100.0f); throttleAngleCorrection = cfg.throttle_angle_correction * constrain(100 - cosZ, 0, 100) / 8; } } From 7fec1b3a695839ef3047d3afe9ae720c0de7b6e3 Mon Sep 17 00:00:00 2001 From: dongie Date: Tue, 26 Nov 2013 11:59:18 +0900 Subject: [PATCH 55/56] git fucking shit up again. been building with wrong gyroscale for weeks. way to fucking go. everyone upgrade to this. --- obj/baseflight.hex | 4788 ++++++++++++++++++++++---------------------- 1 file changed, 2395 insertions(+), 2393 deletions(-) diff --git a/obj/baseflight.hex b/obj/baseflight.hex index dc203401f..9eacc8022 100644 --- a/obj/baseflight.hex +++ b/obj/baseflight.hex @@ -1,20 +1,20 @@ :020000040800F2 -:100000009029002041A8000881A800081F270008A7 -:1000100085A8000887A8000889A80008000000003B -:100020000000000000000000000000008BA8000895 -:100030008DA80008000000008FA80008A18000081B -:1000400093A8000893A8000893A8000893A80008A4 -:1000500093A8000893A8000893A80008EB8B000859 -:1000600093A8000893A8000893A8000893A8000884 -:1000700093A8000893A800086186000893A80008C8 -:1000800093A8000893A8000893A8000893A8000864 -:1000900093A8000893A8000893A80008ED8B000817 -:1000A00093A8000893A8000893A80008719400087A -:1000B000759400087B9400087F940008117A00086A -:1000C000EF770008157A0008137A000893A8000853 -:1000D00093A800088D860008C186000893A8000830 -:1000E0002D71000893A8000893A80008DFF80CD031 -:1000F0000BF012F800480047E12400089029002086 +:10000000902900205DA800089DA800081F2700086F +:10001000A1A80008A3A80008A5A8000800000000E7 +:10002000000000000000000000000000A7A8000879 +:10003000A9A8000800000000ABA80008BD800008C7 +:10004000AFA80008AFA80008AFA80008AFA8000834 +:10005000AFA80008AFA80008AFA80008078C0008E8 +:10006000AFA80008AFA80008AFA80008AFA8000814 +:10007000AFA80008AFA800087D860008AFA8000858 +:10008000AFA80008AFA80008AFA80008AFA80008F4 +:10009000AFA80008AFA80008AFA80008098C0008A6 +:1000A000AFA80008AFA80008AFA800088D9400080A +:1000B00091940008979400089B9400082D7A0008FA +:1000C0000B780008317A00082F7A0008AFA80008E2 +:1000D000AFA80008A9860008DD860008AFA80008C0 +:1000E00049710008AFA80008AFA80008DFF80CD0DD +:1000F0000BF020F800480047E12400089029002078 :1001000070B51546B0FBF5F40646A84203D3204669 :10011000FFF7F6FF014605FB1460FCA2105C0870B7 :10012000481C70BD70B50C46911E232900D30A22CD @@ -23,61 +23,61 @@ :10015000044600E0641C20782028FBD00928F9D050 :100160004FF07E58C1B247462D2902D02B2801D02E :1001700001E0F04F641C0026DFF8BC930CE000BFE8 -:100180000AF0A6FD0546494630460AF01FFD2946FD -:100190000AF0C4FC0646641C207830380928EFD9E0 -:1001A00020782E2815D14D460EE000BF0AF090FDB4 -:1001B00029460AF041FD31460AF0B0FC06464946A0 -:1001C00028460AF003FD054614F8010F30380928C7 +:100180000AF0B4FD0546494630460AF02DFD2946E1 +:100190000AF0D2FC0646641C207830380928EFD9D2 +:1001A00020782E2815D14D460EE000BF0AF09EFDA6 +:1001B00029460AF04FFD31460AF0BEFC0646494684 +:1001C00028460AF011FD054614F8010F30380928B9 :1001D000ECD921784046652901D0452935D114F85C :1001E000011F4FF000082D2902D02B2902D002E078 :1001F0004FF00108641C00256FF02F0206E000BFDD :1002000005EB850302EB4303CD18641C2178A1F1B3 :100210003003092BF4D94FF49A718D4204D90D465D -:10022000C6490AF0D3FC083D082DF9D203E049463F -:100230000AF0CCFC6D1E002DF9D1B8F1000F04D0EE -:10024000014630460AF0F8FC03E0014630460AF069 -:10025000BDFC3946BDE8F0470AF0B8BCF0B587B040 +:10022000C6490AF0E1FC083D082DF9D203E0494631 +:100230000AF0DAFC6D1E002DF9D1B8F1000F04D0E0 +:10024000014630460AF006FD03E0014630460AF05A +:10025000CBFC3946BDE8F0470AF0C6BCF0B587B024 :1002600000260D46B74900960196B5A70296B0F54F -:10027000000F02DB0AF052FC01E00AF0A1FCB249D7 -:100280000AF0A4FC0AF032FD041E00DC60420A22DF +:10027000000F02DB0AF060FC01E00AF0AFFCB249BB +:100280000AF0B2FC0AF040FD041E00DC60420A22C3 :1002900003A9FFF747FF002C01DB202000E02D2001 -:1002A0008DF8000003A80AF0EAFB302401280AD0E8 -:1002B00003A80AF0E4FB02280CD003A80AF0DFFB35 +:1002A0008DF8000003A80AF0F8FB302401280AD0DA +:1002B00003A80AF0F2FB02280CD003A80AF0EDFB19 :1002C00003280CD00DE08DF801408DF802408DF828 :1002D000034006E08DF801408DF8024001E08DF802 -:1002E000014003A968460AF096FB68460AF0C7FB7E -:1002F000C01EC4B22246694628460AF0AAFB2E5503 -:10030000394628460AF087FB0DEB040128460AF01F -:1003100082FB07B02846F0BD70B505460C4608685C -:100320000AF0ADFB024621682868BDE870400AF07B -:10033000CFBB70B506460AF0A2FB844D10F0FF0F4C -:100340000FD030460AF0DDFB0446142815DA2021D0 -:1003500030460AF08AFB0AF0D4FB05EB4401C8875B +:1002E000014003A968460AF0A4FB68460AF0D5FB62 +:1002F000C01EC4B22246694628460AF0B8FB2E55F5 +:10030000394628460AF095FB0DEB040128460AF011 +:1003100090FB07B02846F0BD70B505460C4608684E +:100320000AF0BBFB024621682868BDE870400AF06D +:10033000DDBB70B506460AF0B0FB844D10F0FF0F30 +:100340000FD030460AF0EBFB0446142815DA2021C2 +:1003500030460AF098FB0AF0E2FB05EB4401C8873F :1003600070BD002405EB44002146C28F78A00BF03D -:1003700001F8641C142CF5DB70BDBDE8704014213D -:1003800076A00AF0F7BF2DE9F041002588B00746B6 -:100390002E460AF074FB7B4C10F0FF0FA84652D09B -:1003A000052279A138460AF093FB00287ED004226A -:1003B00077A138460AF08CFB002878D038460AF03E -:1003C000A0FB461E0C2E73DA202138460AF04DFBA6 +:100370000FF8641C142CF5DB70BDBDE8704014212F +:1003800076A00BF005B82DE9F041002588B00746AE +:100390002E460AF082FB7B4C10F0FF0FA84652D08D +:1003A000052279A138460AF0A1FB00287ED004225C +:1003B00077A138460AF09AFB002878D038460AF030 +:1003C000AEFB461E0C2E73DA202138460AF05BFB8A :1003D000070007D0781C0746FFF7B8FE04EB0611AC -:1003E00001250861202138460AF03FFB070007D0AD +:1003E00001250861202138460AF04DFB070007D09F :1003F000471C3846FFF7AAFE04EB06116D1C486146 -:10040000202138460AF031FB070007D0471C384648 +:10040000202138460AF03FFB070007D0471C38463A :10041000FFF79CFE04EB06116D1C88612021384615 -:100420000AF023FB30B1401CFFF790FE04EB0611ED +:100420000AF031FB30B1401CFFF790FE04EB0611DF :100430006D1CC861042D67D057A000BF01F045F8BE :1004400008B0BDE8F08163A001F03FF85FF000055F :1004500004EB0517386910F0FF4F2BD0761C691C90 -:1004600067A00AF087FF03A93869FFF7F7FE014686 -:1004700065A00AF07FFF03A97869FFF7EFFE014648 -:1004800061A00AF077FF03A9B869FFF7E7FE01460C -:100490005DA00AF06FFF03A9F869FFF7DFFE0146D0 -:1004A0005AA00AF067FF6D1C0C2D02E0C8E0D0E0F6 +:1004600067A00AF095FF03A93869FFF7F7FE014678 +:1004700065A00AF08DFF03A97869FFF7EFFE01463A +:1004800061A00AF085FF03A9B869FFF7E7FE0146FE +:100490005DA00AF07DFF03A9F869FFF7DFFE0146C2 +:1004A0005AA00AF075FF6D1C0C2D02E0C8E0D0E0E8 :1004B000F5E0CDDBCDF80880CDF804800025CDF83F -:1004C000008011E004EB0517009879690AF026FB1B -:1004D0000090B96901980AF021FB0190F96902982E -:1004E0000AF01CFB6D1C0290B542EBDB49A000F04A +:1004C000008011E004EB0517009879690AF034FB0D +:1004D0000090B96901980AF02FFB0190F969029820 +:1004E0000AF02AFB6D1C0290B542EBDB49A000F03C :1004F000ECFF4C4E00246D4655F8240020F00040DF :10050000B04202DD48A092E0C4E08FE030313233E7 :100510003435363738394142434445464748494ADD @@ -100,68 +100,68 @@ :100620003A0900000AD7233C4E470900FEA000F01B :100630004CFF641C032CFFF65FAFAFF24000FDE6F9 :100640000020414604EB0012401C11610C28F9DB2C -:10065000F6E6202138460AF008FA0028F8D0401CB7 -:1006600006460AF00CFAF14DC7B2002455F82410E2 -:1006700031B13A4630460AF02BFA18B1641CF5E75E +:10065000F6E6202138460AF016FA0028F8D0401CA9 +:1006600006460AF01AFAF14DC7B2002455F82410D4 +:1006700031B13A4630460AF039FA18B1641CF5E750 :10068000EBA0DBE6204602F006F955F82410EEA0B8 -:100690000AF070FEAFF26810FFF775FED0E60C218D -:1006A000EEA00AF067FECBE610B5F6A000F00DFF55 +:100690000AF07EFEAFF26810FFF775FED0E60C217F +:1006A000EEA00AF075FECBE610B5F6A000F00DFF47 :1006B000012001F0B2F9FAA000F007FF0A2007F0CC -:1006C0001DFDBDE81040002007F0E3BD7CB50446E9 +:1006C0002BFDBDE81040002007F0F1BD7CB50446CD :1006D0000D4600790021062814D2DFE800F0030659 :1006E0000A0D111EA06801780CE0A06890F90010B6 :1006F00008E0A068018805E0A068B0F9001001E0FA -:10070000A0680168EAA00AF035FE002D04D0D4E903 -:100710000312E8A00AF02EFE7CBDA06869460068BE -:10072000FFF79CFD0146E5A00AF024FE002DF3D062 -:10073000E0680AF0CDFA6946FFF790FD0146E0A0B7 -:100740000AF018FE20690AF0C3FA6946FFF786FD31 -:100750000146DBA00AF00EFE7CBD2DE9FF47D9A0C3 -:100760000AF008FED1A0FFF7E4FDE24DAF49687939 -:1007700001EB800050F8041CDFA00AF0FBFD2869A3 +:10070000A0680168EAA00AF043FE002D04D0D4E9F5 +:100710000312E8A00AF03CFE7CBDA06869460068B0 +:10072000FFF79CFD0146E5A00AF032FE002DF3D054 +:10073000E0680AF0DBFA6946FFF790FD0146E0A0A9 +:100740000AF026FE20690AF0D1FA6946FFF786FD15 +:100750000146DBA00AF01CFE7CBD2DE9FF47D9A0B5 +:100760000AF016FED1A0FFF7E4FDE24DAF4968792B +:1007700001EB800050F8041CDFA00AF009FE286994 :1007800010F0FF4F4CD0DFF87CA3002405EB0410E1 :10079000066916F0FF4F3FD0D0E90598C769611C84 -:1007A000D9A00AF0E7FD564502D3D9A00AF0E2FD30 -:1007B00069463046FFF752FD0146C0A00AF0DAFD57 -:1007C0005646B14502D3D2A00AF0D4FD6946484648 -:1007D000FFF744FD0146B9A00AF0CCFDB04502D3B5 -:1007E000CBA00AF0C7FD69464046FFF737FD01463A -:1007F000B2A00AF0BFFDB74202D3C5A00AF0BAFD0D +:1007A000D9A00AF0F5FD564502D3D9A00AF0F0FD14 +:1007B00069463046FFF752FD0146C0A00AF0E8FD49 +:1007C0005646B14502D3D2A00AF0E2FD694648463A +:1007D000FFF744FD0146B9A00AF0DAFDB04502D3A7 +:1007E000CBA00AF0D5FD69464046FFF737FD01462C +:1007F000B2A00AF0CDFDB74202D3C5A00AF0C8FDF1 :1008000069463846FFF72AFD0146AFF200200AF09C -:10081000B1FD641C0C2CB9DB611CBEA00AF0AAFD62 +:10081000BFFD641C0C2CB9DB611CBEA00AF0B8FD46 :1008200001F02CF9814E002407465C3656F824105E -:1008300021B1BDA00AF09EFD641CF7E700244FF033 +:1008300021B1BDA00AF0ACFD641CF7E700244FF025 :10084000010800BF56F8241041B108FA04F03842FC -:1008500002D0B9A00AF08EFD641CF3E7BA4A00206A +:1008500002D0B9A00AF09CFD641CF3E7BA4A00205C :1008600069462C18135C94F80A41401C08280B5563 -:10087000F7DB00220A54B5A00AF07CFDB64D002437 +:10087000F7DB00220A54B5A00AF08AFDB64D002429 :1008800004EB840005EB800655F82010B3A00AF0B5 -:1008900071FD00213046FFF719FF6FA000F015FE33 +:100890007FFD00213046FFF719FF6FA000F015FE25 :1008A000641C622CECD3BDE8FF8710B5AEA000F04D :1008B0000CFE0121002000F0FAFEAEA000F005FEC3 -:1008C0000A2007F01BFCBDE81040002007F0E1BC47 +:1008C0000A2007F029FCBDE81040002007F0EFBC2B :1008D00010B50446ABA000F0F8FDB048002101704F :1008E000AF480160AF48017001F052FF2046BDE8FB -:1008F0001040DAE72DE9F04706460AF0C0F8054651 +:1008F0001040DAE72DE9F04706460AF0CEF8054643 :1009000001F0BCF8DFF8248107464FF0010908F137 -:100910005C0855B12A46A4A130460AF0D9F8C8B1FE +:100910005C0855B12A46A4A130460AF0E7F8C8B1F0 :10092000307800272D2824D026E0A1A000F0CDFDAE :1009300000244D464FEA080656F8241041B105FA46 -:1009400004F0384202D09FA00AF014FD641CF3E7C3 +:1009400004F0384202D09FA00AF022FD641CF3E7B5 :1009500041A01EE09CA000F0B8FD00244FEA08056D -:1009600055F824100029F3D096A00AF003FD641C6A +:1009600055F824100029F3D096A00AF011FD641C5C :10097000F6E70127761C6D1E5FF0000458F824107E -:1009800031B12A4630460AF0A3F830B1641CF5E7CD +:1009800031B12A4630460AF0B1F830B1641CF5E7BF :1009900093A0BDE8F04700F098BD09FA04F01FB13C :1009A00001F067F895A002E000F0E2FE96A000F0EA -:1009B0008CFD58F82410BDE8F04761A00AF0DABCBD +:1009B0008CFD58F82410BDE8F04761A00AF0E8BCAF :1009C00010B505F074FC401C04D092A0BDE81040A6 :1009D00000F07BBD97A0F9E770B500249FA000F060 :1009E00074FD5D4DB5F1C00504EB440005EB8001DD -:1009F0004A6855F820109FA00AF0BCFC641C102C1B -:100A0000F2D370BD3EB505460AF039F8082809D181 -:100A10000024285D09F0B2FF2855641C082CF8D387 -:100A200000242BE140E100004F4B0900E4C2000824 +:1009F0004A6855F820109FA00AF0CAFC641C102C0D +:100A0000F2D370BD3EB505460AF047F8082809D173 +:100A10000024285D09F0C0FF2855641C082CF8D379 +:100A200000242BE140E100004F4B090000C3000807 :100A3000496E76616C6964206D697865722074799D :100A400070652E2E2E0D0A004C6F616465642025A2 :100A500073206D69782E2E2E0D0A00004D6F746F75 @@ -179,8 +179,8 @@ :100B100020000000636D697820256420302030209B :100B20003020300D0A000000666561747572652022 :100B30002D25730D0A0000006665617475726520CD -:100B400025730D0A0000000028CC00086D6170209C -:100B500025730D0A0000000080C40008736574202E +:100B400025730D0A0000000044CC00086D61702080 +:100B500025730D0A000000009CC400087365742012 :100B60002573203D20000000536176696E672E2EAC :100B70002E0000000D0A5265626F6F74696E672E59 :100B80002E2E00000D0A4C656176696E6720434C7D @@ -199,73 +199,73 @@ :100C5000532066697273740D0A0000004176616961 :100C60006C61626C6520636F6D6D616E64733A0DCB :100C70000A00000025730925730D0A00295DFB4851 -:100C800009F0F3FE28B12819295D401C09F0EDFE9A +:100C800009F001FF28B12819295D401C09F0FBFE7D :100C900018B1F7A000F019FC3EBD641C082CFFF44D :100CA000C0AE284600F04EFCF9A000F00EFCEF4B61 :100CB000FD4A0020694615181C5C95F80A51401C35 :100CC00008284C55F7D300220A54AFF28C100AF0D2 -:100CD00051FB3EBD2DE9F041804609F0D0FEF24FB8 +:100CD0005FFB3EBD2DE9F041804609F0DEFEF24F9C :100CE000F24D060012D00246AFF24411404609F020 -:100CF000EFFE90B15FF0000455F82410F1B13246D8 -:100D0000404609F0E5FEF8B1641CF5E7787905EB9B +:100CF000FDFE90B15FF0000455F82410F1B13246CA +:100D0000404609F0F3FEF8B1641CF5E7787905EB8D :100D1000800050F8041CE6A01BE0EAA000F0D5FB20 :100D20005FF0000455F8241029B1AFF268100AF002 -:100D300021FB641CF6E7AFF2E02001E0AFF21030D7 +:100D30002FFB641CF6E7AFF2E02001E0AFF21030C9 :100D4000BDE8F04100F0C1BB601C787155F824107B -:100D5000E1A0BDE8F0410AF00DBB2DE9F04100250E -:100D600007462C462E4609F08AFE18B1AFF26021E4 +:100D5000E1A0BDE8F0410AF01BBB2DE9F041002500 +:100D600007462C462E4609F098FE18B1AFF26021D6 :100D7000384610E0DDA02BE016B1012E07D103E0CC -:100D800009F0BFFE054602E009F0BBFE0446761CF2 -:100D9000AFF28421002009F079FE0028ECD10C2D5F -:100DA00005D3BDE8F0410C21DFA00AF0E3BAE84F1B +:100D800009F0CDFE054602E009F0C9FE0446761CD6 +:100D9000AFF28421002009F087FE0028ECD10C2D51 +:100DA00005D3BDE8F0410C21DFA00AF0F1BAE84F0D :100DB000022E07DA37F915202946BDE8F041E5A0F3 -:100DC0000AF0D8BAA4F57A70B0F57A7F04D9E7A012 -:100DD000BDE8F0410AF0CEBA22462946ECA00AF05E -:100DE000C9FA27F81540BDE8F08170B5054609F04D -:100DF00046FEAD4C10F0FF0F0CD0284609F081FEE6 +:100DC0000AF0E6BAA4F57A70B0F57A7F04D9E7A004 +:100DD000BDE8F0410AF0DCBA22462946ECA00AF050 +:100DE000D7FA27F81540BDE8F08170B5054609F03F +:100DF00054FEAD4C10F0FF0F0CD0284609F08FFECA :100E000002280ED884F878030021084600F04FFC31 :100E1000A4A0EBE794F87813BDE87040E3A00AF0D3 -:100E2000A9BA70BD2DE9F047824609F028FEE54DCC +:100E2000B7BA70BD2DE9F047824609F036FEE54DB0 :100E3000060029D0012E03D19AF800002A2823D0D9 -:100E4000E1A1504609F0F3FD00286FD0401C044694 -:100E500009F057FE81462046FFF778F980460026C4 -:100E600006EB860705EB870455F8270009F007FE17 -:100E7000024655F82710504609F02AFEF8B1761CB4 +:100E4000E1A1504609F001FE00286FD0401C044685 +:100E500009F065FE81462046FFF778F980460026B6 +:100E600006EB860705EB870455F8270009F015FE09 +:100E7000024655F82710504609F038FEF8B1761CA6 :100E8000622EEDD3D1A04DE0D8A000F01EFB0024CF :100E900004EB840005EB800755F82010AFF24030DA -:100EA0000AF068FA31463846FFF710FCAFF25840B6 +:100EA0000AF076FA31463846FFF710FCAFF25840A8 :100EB00000F00BFB641C622CEAD3BDE8F08706EB64 -:100EC000860605EB8607F86809F002FF414609F03F -:100ED0003BFF26D8386909F0FBFE414609F03EFF8A +:100EC000860605EB8607F86809F010FF414609F031 +:100ED00049FF26D8386909F009FF414609F04CFF5F :100EE0001FD83979052907D0484606290ED2DFE8F0 :100EF00001F0050508080B0B4046F6E7A1680870ED :100F000004E0A168088001E0A168086055F8261097 -:100F1000BCA00AF02FFA2046BDE8F0470021FFF7F9 +:100F1000BCA00AF03DFA2046BDE8F0470021FFF7EB :100F2000D5BBBBA0BDE8F04700F0CFBA5FF000042E -:100F300004EB8406514655F8260009F078FD78B197 -:100F400055F8261005EB8607AFF2EC300AF012FADE -:100F500000213846FFF7BAFBAFF204500AF00AFA54 -:100F6000641C622CE4D3A8E72DE9F04107F0B7F840 +:100F300004EB8406514655F8260009F086FD78B189 +:100F400055F8261005EB8607AFF2EC300AF020FAD0 +:100F500000213846FFF7BAFBAFF204500AF018FA46 +:100F6000641C622CE4D3A8E72DE9F04107F0C5F832 :100F70004FF47A71B0FBF1F1AF480378AF480278D3 -:100F8000AFA00AF0F7F900F069FD0646BC48BD497C -:100F90000068B0FBF1F1BCA00AF0ECF9434F00246B +:100F8000AFA00AF005FA00F069FD0646BC48BD496D +:100F90000068B0FBF1F1BCA00AF0FAF9434F00245D :100FA0000125A03757F8241051B105FA04F030425A -:100FB00003D0AFF2F0300AF0DDF9641CE4B2F1E7DF +:100FB00003D0AFF2F0300AF0EBF9641CE4B2F1E7D1 :100FC000022000F039FDA0B1B74C38482178C0307C -:100FD00050F82110B5A00AF0CDF92078022808D1E8 +:100FD00050F82110B5A00AF0DBF92078022808D1DA :100FE000B548007C08B16F2100E06E21B3A00AF083 -:100FF000C1F9AFF29C5000F068FA06F084FD024699 +:100FF000CFF9AFF29C5000F068FA06F092FD02467D :10100000AF484FF45F730188BDE8F041ADA00AF02E -:10101000B1B9B9A000F059BA2DE9FF5FDFF8089324 +:10101000BFB9B9A000F059BA2DE9FF5FDFF8089316 :1010200099F8000038B9012189F80010BFA000F03C :101030004CFA00F056FADFF82CB3DFF87CA25446E5 -:10104000DAF8000008F044FC00280CD0206808F012 -:1010500042FC092808D03F2806D0DBF800105C4687 -:10106000002902D0D0E12EE27EE1CBE128CC0008BD +:10104000DAF8000008F052FC00280CD0206808F004 +:1010500050FC092808D03F2806D0DBF800105C4679 +:10106000002902D0D0E12EE27EE1CBE144CC0008A1 :101070004D75737420626520616E79206F726465AE :1010800072206F662041455452313233340D0A00CC :1010900043757272656E742061737369676E6D65F6 -:1010A0006E743A200000000070040020E4C20008C2 +:1010A0006E743A20000000007004002000C30008A5 :1010B00043757272656E74206D697865723A202589 :1010C000730D0A00417661696C61626C65206D691F :1010D000786572733A2000004D69786572207365F7 @@ -283,7 +283,7 @@ :1011900053657474696E67206D6F746F7220256477 :1011A00020746F2025640D0A0000000043757272E0 :1011B000656E742070726F66696C653A2025640DE7 -:1011C0000A00000080C400083D0000004552523A69 +:1011C0000A0000009CC400083D0000004552523A4D :1011D00020556E6B6E6F776E207661726961626CFE :1011E00065206E616D650D0A000000004375727226 :1011F000656E742073657474696E67733A200D0AA6 @@ -304,14 +304,14 @@ :1012E00025642C20636F6E6669672073697A653A9E :1012F0002025640D0A0000004166726F33322043DE :101300004C492076657273696F6E20322E32204E02 -:101310006F762031342032303133202F2031383A6B -:1013200033313A3537000000B50100200D0A456E13 +:101310006F762032362032303133202F2031313A6F +:1013200035333A3530000000B50100200D0A456E16 :10133000746572696E6720434C49204D6F64652C5B :1013400020747970652027657869742720746F2070 :1013500072657475726E2C206F72202768656C70D0 :10136000270D0A0000000020614F0024254607F1E8 :10137000C008DBF800600BE0DBF8002022B15D481C -:10138000396809F0A5FB10B904B93C463D460C3755 +:10138000396809F0B3FB10B904B93C463D460C3747 :101390004745F1D394B1574F5946226808682B68E6 :1013A000125C1B5C9A4209D192B92E2810D22022DD :1013B0003A54401C0021CBF800003954DBF80000FF @@ -325,31 +325,31 @@ :101430003048BDE8F05FFFF74BBA31A000F045F847 :1014400027E0AFF6EC1000F040F82A4E20680025A7 :101450000C2335542D48CDE900061022244902956D -:1014600001A809F091FA070007D0386809F007FBD6 +:1014600001A809F09FFA070007D0386809F015FBBA :101470003044B968401C884702E025A000F025F8F8 -:1014800030211C4809F0BCFA256099F800000028BA +:1014800030211C4809F0CAFA256099F800000028AC :1014900019D000F026F8D2E50BE00029FBD0154A60 :1014A000491E0020CBF80010505422A000F00DF887 :1014B000C5E52028EFD00F4A5054491CCBF8001046 :1014C00000F011F8BBE5BDE8FF9F70B504461A4D6A -:1014D00003E0641C286807F0ABF821780029F8D1F4 -:1014E00070BD16A0F1E701461348006807F0A0B8E8 -:1014F000C0C30008400400200D1B5B4B000000002F +:1014D00003E0641C286807F0B9F821780029F8D1E6 +:1014E00070BD16A0F1E701461348006807F0AEB8DA +:1014F000DCC30008400400200D1B5B4B0000000013 :101500001B5B324A1B5B313B31480000190300086A :101510004552523A20556E6B6E6F776E20636F6D39 :101520006D616E642C20747279202768656C702759 :101530000000000008200800E00800200D0A232019 :10154000000000002DE9F04105460446FD4EFE4F27 -:1015500009E0FC4809F089FA20B1611B801B38447E +:1015500009E0FC4809F097FA20B1611B801B384470 :1015600080F80A11641C21780029F2D1BDE8F081CD :10157000F64800210278372A12D14288B2F55F7FFF :101580000ED10279BE2A0BD190F87923EF2A07D128 :1015900000F55F7210F8013B59409042FAD309B14F :1015A00000207047012070472DE9F05FFFF7E0FF52 -:1015B00010B90A2006F04CFE4FF45F72E349E2488E -:1015C00009F005FAE04C94F87803022802D90020CB +:1015B00010B90A2006F05AFE4FF45F72E349E24880 +:1015C00009F013FAE04C94F87803022802D90020BD :1015D00084F87803C0B200EB001101EB401004EB7B -:1015E000800101F59671C422D94809F0F0F9D84A72 +:1015E000800101F59671C422D94809F0FEF9D84A64 :1015F000D84F002092F8201092F81F5040F6C416E1 :1016000000FB00F3193B4B4303F6C41343436B4306 :1016100093FBF6F327F81030401CC0B20728EFD335 @@ -365,18 +365,18 @@ :1016B000F047A54D8146372028704FF45F7400270E :1016C0006C80BE202871EF2085F879033E4685F8AE :1016D0007A7369B195F87803C42200EB001101EB2D -:1016E000401005EB800000F59670994909F06FF9FC +:1016E000401005EB800000F59670994909F07DF9EE :1016F0009548974903E000BF10F8012B57408842F6 -:10170000FAD385F87A73914F4FEA040809F020F86C -:10171000342009F08BF8384609F048F804280FD136 -:101720000024E019295909F05DF8042805D009F0D2 -:1017300015F8761C032EE9DB02E0241D4445F0D3A6 -:1017400009F00CF8032E02D0FFF712FF10B90A209F -:1017500006F07EFDFFF728FFB9F1000F06D0BDE8C7 +:10170000FAD385F87A73914F4FEA040809F02EF85E +:10171000342009F099F8384609F056F804280FD11A +:101720000024E019295909F06BF8042805D009F0C4 +:1017300023F8761C032EE9DB02E0241D4445F0D398 +:1017400009F01AF8032E02D0FFF712FF10B90A2091 +:1017500006F08CFDFFF728FFB9F1000F06D0BDE8B9 :10176000F047012214210F2001F00EBCBDE8F087E4 :1017700075498A6802438A6070472DE9FC5F77A14A :10178000D1E90001CDE900014FF45F716E4809F025 -:1017900037F9C4216E4809F033F96B4B3720002527 +:1017900045F9C4216E4809F041F96B4B372000250B :1017A00018700320587102209D60FFF7E1FF83F855 :1017B00078534FF41670A3F8F000FA20A3F8F20063 :1017C000D0332A20D8835D859D85DD859D74DD74A9 @@ -403,7 +403,7 @@ :10191000164860631648A063012084F83C0015A0B7 :10192000FFF710FE84F8665084F8675084F868600A :10193000012084F8690084F86A5004F8AC8FC82349 -:1019400063701DE028CC00087004002000F8010836 +:1019400063701DE044CC00087004002000F801081A :10195000EC070020C00A0020CE0A00201E1E64648E :1019600064646464031414009A99193F52B87E3F6A :101970003333733F41455452313233340000000059 @@ -415,7 +415,7 @@ :1019D00006B0C77180F80890A0F80AA08181C6817E :1019E0000020294D014600BF05EB0012401C11618B :1019F0000C28F9DB5FF0000404EB041000EB44104A -:101A000005EB800000F59670C4221E4908F0DFFF48 +:101A000005EB800000F59670C4221E4908F0EDFF3A :101A1000641C032CF0DBBDE8FC9F10B50446FFF707 :101A2000A7FD641E204206D1FFF7A7FE0021BDE8F6 :101A3000104008463BE610BD14490968014201D038 @@ -424,110 +424,110 @@ :101A6000704709498968014201D001207047002070 :101A7000704705498A6882438A60704702488068D7 :101A800070470000EC0700207004002004000020D4 -:101A900070B5FE4809F064FF0446FD48008809F06F -:101AA00020F90546214609F091F809F01FF9F94C93 -:101AB00029462080F84809F0BFF8F84909F0BCF839 +:101A900070B5FE4809F072FF0446FD48008809F061 +:101AA0002EF90546214609F09FF809F02DF9F94C69 +:101AB00029462080F84809F0CDF8F84909F0CAF81D :101AC000E0650820FFF7B8FF002803D0BDE87040AC :101AD00002F0F0BD70BD002801DD024600E0424288 :101AE0008A4201DA00207047002802DDA0EB0100E5 :101AF0007047FDDA084470472DE9F04F91B0D0E906 -:101B00000045814686688846086809F029FF0490E8 -:101B1000D8F800000AF00AFB0590D8F8040009F094 -:101B20001FFF0190D8F804000AF000FB0746D8F820 -:101B3000080009F015FF8246D8F808000AF0F6FA06 -:101B400083465046049909F041F8079050460199A0 -:101B500009F03CF880465846049909F037F8069099 -:101B60005146059809F032F808905946059809F051 -:101B70002DF803900198594680F0004009F026F8AE -:101B800082463946089809F021F8069908F0C6FF00 -:101B900010903946039809F019F8079909F013F8DD -:101BA0000E900598019980F0004009F00FF805901B -:101BB0003946079809F00AF8039909F004F80290E9 -:101BC0003946069809F002F8089908F0A7FF8346FD -:101BD0000499019808F0FAFF04903046029908F041 -:101BE000F5FF01902846109908F0F0FF009041465B -:101BF000204608F0EBFF009908F090FF019908F0EB -:101C00008DFFC9F800005946304608F0DFFF8346D3 -:101C100028460E9908F0DAFF80465146204608F023 -:101C2000D5FF414608F07AFF594608F077FFC9F81A -:101C300004003046049908F0C9FF06462846059975 -:101C400008F0C4FF05463946204608F0BFFF294684 -:101C500008F064FF314608F061FFC9F8080011B0D0 +:101B00000045814686688846086809F037FF0490DA +:101B1000D8F800000AF018FB0590D8F8040009F086 +:101B20002DFF0190D8F804000AF00EFB0746D8F804 +:101B3000080009F023FF8246D8F808000AF004FBE9 +:101B400083465046049909F04FF807905046019992 +:101B500009F04AF880465846049909F045F806907D +:101B60005146059809F040F808905946059809F043 +:101B70003BF803900198594680F0004009F034F892 +:101B800082463946089809F02FF8069908F0D4FFE4 +:101B900010903946039809F027F8079909F021F8C1 +:101BA0000E900598019980F0004009F01DF805900D +:101BB0003946079809F018F8039909F012F80290CD +:101BC0003946069809F010F8089908F0B5FF8346E1 +:101BD0000499019809F008F804903046029909F038 +:101BE00003F801902846109908F0FEFF0090414646 +:101BF000204608F0F9FF009908F09EFF019908F0CF +:101C00009BFFC9F800005946304608F0EDFF8346B7 +:101C100028460E9908F0E8FF80465146204608F015 +:101C2000E3FF414608F088FF594608F085FFC9F8F0 +:101C300004003046049908F0D7FF06462846059967 +:101C400008F0D2FF05463946204608F0CDFF294668 +:101C500008F072FF314608F06FFFC9F8080011B0B4 :101C6000BDE8F08F2DE9F04380468A4887B0843084 :101C7000016881F000410391406880F000400490C9 -:101C80008748B0F9000009F023F8864908F09EFF64 -:101C9000804C05907834B4F9000009F019F80090F0 -:101CA000B4F9020009F014F80190B4F9040009F045 -:101CB0000FF8029003A96846FFF71EFF7A4D783CA3 -:101CC00095F83C00012804D07148008809F009F813 +:101C80008748B0F9000009F031F8864908F0ACFF48 +:101C9000804C05907834B4F9000009F027F80090E2 +:101CA000B4F9020009F022F80190B4F9040009F037 +:101CB0001DF8029003A96846FFF71EFF7A4D783C95 +:101CC00095F83C00012804D07148008809F017F805 :101CD00017E0764840780028206B0CD1C11700EB44 -:101CE0009161A0EBA11008F0F3FF029908F016FF34 -:101CF00008F0FCFF2063C11700EB9160801108F031 -:101D0000E7FF029908F05FFF0290616B894608F0D7 -:101D100057FF0746404608F0E4FF0646644908F0CE -:101D2000FDFE0146304608F087FF394608F04EFFB9 -:101D3000494608F0F3FE606309F0D2FE15F82D1F46 -:101D4000FFF7C9FE08F0C4FF0290009809F0C8FE32 -:101D50006978FFF7C0FE08F0BBFF0090019809F01A -:101D6000BFFE6978FFF7B7FE08F0B2FF0190E168A7 +:101CE0009161A0EBA11009F001F8029908F024FF1E +:101CF00009F00AF82063C11700EB9160801108F029 +:101D0000F5FF029908F06DFF0290616B894608F0BB +:101D100065FF0746404608F0F2FF0646644908F0B2 +:101D20000BFF0146304608F095FF394608F05CFF8E +:101D3000494608F001FF606309F0E0FE15F82D1F29 +:101D4000FFF7C9FE08F0D2FF0290009809F0D6FE16 +:101D50006978FFF7C0FE08F0C9FF0090019809F00C +:101D6000CDFE6978FFF7B7FE08F0C0FF0190E1688B :101D700001EB0800E0602069401C2061009809F038 -:101D8000AFFE4C4C216808442060019809F0A8FE81 -:101D9000616808446060029809F0A2FEA1680844E6 +:101D8000BDFE4C4C216808442060019809F0B6FE65 +:101D9000616808446060029809F0B0FEA1680844D8 :101DA000A06007B0BDE8F0832DE9F05F394D04462F -:101DB0008435286809F0D4FD834628680AF0B6F90E -:101DC0008246686809F0CCFD814668680AF0AEF981 -:101DD0000546D4F808802946404608F0F7FE5946E3 -:101DE00008F0F4FE676806465146384608F0EEFEF5 -:101DF000294608F0EBFE05464946206808F0E6FE55 -:101E0000294608F08BFE314608F088FE044651460C -:101E1000404608F0DBFE05465946384608F0D6FE37 -:101E2000294608F0CDFE214609F070FC224908F051 -:101E3000CDFE224908F000FF1649896A08F06EFEBF -:101E40001F4908F0F9FE09F04BFE00B2002802DA43 +:101DB0008435286809F0E2FD834628680AF0C4F9F2 +:101DC0008246686809F0DAFD814668680AF0BCF965 +:101DD0000546D4F808802946404608F005FF5946D4 +:101DE00008F002FF676806465146384608F0FCFED8 +:101DF000294608F0F9FE05464946206808F0F4FE39 +:101E0000294608F099FE314608F096FE04465146F0 +:101E1000404608F0E9FE05465946384608F0E4FE1B +:101E2000294608F0DBFE214609F07EFC224908F035 +:101E3000DBFE224908F00EFF1649896A08F07CFE95 +:101E40001F4908F007FF09F059FE00B2002802DA26 :101E500000F5B47000B2BDE8F09F2DE9F04F8DB0F1 -:101E6000002606F022F9DFF82CB005465C46DBF8C8 -:101E70003800281A099008F034FF1249C96808F0A0 -:101E8000A5FE0490A56300241EE00000F366DF3E7B +:101E6000002606F030F9DFF82CB005465C46DBF8BA +:101E70003800281A099008F042FF1249C96808F092 +:101E8000B3FE0490A56300241EE00000F366DF3E6D :101E900082010020080000200AE81C4100401C4686 :101EA000B001002035FA8EBCEC0700208C0A00201F :101EB0003661023CC80800200000E144DB0F4940C5 :101EC000000020416C0C00200BF1720A0AF106059B :101ED0004FF07E58FE4890F82C70FE4830F9140000 -:101EE00008F0F6FE049908F071FE06A941F82400F6 -:101EF00017B3384608F0F5FE0146404608F09CFE50 -:101F000081460B903AF9140008F0E2FE494608F0C9 -:101F10005DFE814641460B9808F055FEEE4951F8AA -:101F2000241008F053FE494608F0F8FDEA4941F84C -:101F3000240008F0DBFE01E03AF8140025F8140054 +:101EE00008F004FF049908F07FFE06A941F82400D9 +:101EF00017B3384608F003FF0146404608F0AAFE33 +:101F000081460B903AF9140008F0F0FE494608F0BB +:101F10006BFE814641460B9808F063FEEE4951F88E +:101F2000241008F061FE494608F006FEEA4941F82F +:101F3000240008F0E9FE01E03AF8140025F8140046 :101F400035F91400641C00FB0066032CC5D3DFF8D0 :101F50008CA364204643BAF8000006A9404396FBD0 :101F6000F0F4DD481830FFF7C7FD0820FFF764FDE7 :101F700006A910B1D8480C3801E0D6482030FFF748 :101F8000BBFDA0B24938DFF858933C2827D2002483 -:101F9000B9F8F00008F0A5FE45464146059008F066 -:101FA000BDFD0146284608F047FECB4E05461836D3 -:101FB000C8480C3030F9140008F08AFE074656F87D -:101FC0002410059808F002FE394608F0A7FD2946BE -:101FD00008F0FCFD46F82400641C032CE8D308201C +:101F9000B9F8F00008F0B3FE45464146059008F058 +:101FA000CBFD0146284608F055FECB4E05461836B7 +:101FB000C8480C3030F9140008F098FE074656F86F +:101FC0002410059808F010FE394608F0B5FD2946A2 +:101FD00008F00AFE46F82400641C032CE8D308200D :101FE000FFF72AFD48B34546BB4EDFF8E8820024E0 -:101FF0000C3E08F11208B9F8F20008F072FE8146B2 -:10200000294608F08BFD0146284608F015FE0546D6 -:1020100038F9140008F05CFE0746484656F82410CC -:1020200008F0D4FD394608F079FD294608F0CEFDC8 +:101FF0000C3E08F11208B9F8F20008F080FE8146A4 +:10200000294608F099FD0146284608F023FE0546BA +:1020100038F9140008F06AFE0746484656F82410BE +:1020200008F0E2FD394608F087FD294608F0DCFD9E :1020300046F82400641C032CEAD35E46BBF900007A -:1020400008F046FEA44C1834A16808F07DFE01D2C9 +:1020400008F054FEA44C1834A16808F08BFE01D2AD :10205000012100E00021A3484173D4E9010109F006 -:1020600055FB9C4D18352860A068014608F0AEFD70 -:1020700007466068014608F0A9FD394608F04EFDA4 -:102080000AF01AF90146206880F0004009F03EFB92 -:10209000DFF8548268604146286808F097FD09F02F -:1020A0001FFDA5F1580741463880686808F08EFD8D -:1020B00009F016FD78800820FFF7BEFC8B4D10B1AB +:1020600063FB9C4D18352860A068014608F0BCFD54 +:1020700007466068014608F0B7FD394608F05CFD88 +:102080000AF028F90146206880F0004009F04CFB76 +:10209000DFF8548268604146286808F0A5FD09F021 +:1020A0002DFDA5F1580741463880686808F09CFD71 +:1020B00009F024FD78800820FFF7BEFC8B4D10B19D :1020C00085480C3801E083482030FFF76DFE2880FA :1020D0000998FFF7C7FD7E4D95F86A0000281BD0D0 -:1020E000BAF8000008F0FDFD0146A06808F0A4FD64 -:1020F0007F4908F06BFD08F0F9FDC0F1640064222F -:10210000002104F0F1FC95F86A104843C11700EB78 +:1020E000BAF8000008F00BFE814908F07DFD0146BA +:1020F000A06808F0AFFD08F007FEC0F1640064229C +:10210000002104F0FFFC95F86A104843C11700EB6A :10211000517040F3CF0070800DB0A1E52DE9F04182 :1021200002F0BFFA0220FFF787FC20B102F0BCF9F1 :10213000FFF793FE05E067480021801D0180418084 @@ -542,57 +542,57 @@ :1021C00000EB4400032490FBF4F088809080188892 :1021D000088058884880DEE73F4900200C310860BD :1021E000486088603B496C390861C86070472DE9D8 -:1021F000F84F05F05AFF374C46F2A8126C3CE16BE1 +:1021F000F84F05F068FF374C46F2A8126C3CE16BD3 :10220000A0EB0108904502D20020BDE8F88F394FBD :10221000E0632F4D3888DFF8E090DFF8E0A0DFF8CA :10222000E0B04FF07E5640B3206D6269C11700EBFD :102230005171A0EBE10095F82F10491EB2FBF1F1AE -:102240000844C117206500EB5170C01008F040FD34 -:10225000494608F0F1FC514609F05AFC314608F0B5 -:10226000B2FC594608F0B2FC08F040FDE0640020E2 +:102240000844C117206500EB5170C01008F04EFD26 +:10225000494608F0FFFC514609F068FC314608F099 +:10226000C0FC594608F0C0FC08F04EFDE0640020B8 :10227000206460643888401E388095F82F006169BA -:10228000401EB1FBF0F008F02CFD494608F0D4FCEC -:10229000514609F03DFC4FF07E5108F094FC594640 -:1022A00008F094FC09F01CFCE16C2F6B461A3946CF -:1022B0004FF07E5008F084FC8146304608F008FD5F -:1022C000494608F083FC0646A06908F001FD19E0C4 +:10228000401EB1FBF0F008F03AFD494608F0E2FCD0 +:10229000514609F04BFC4FF07E5108F0A2FC594624 +:1022A00008F0A2FC09F02AFCE16C2F6B461A3946B3 +:1022B0004FF07E5008F092FC8146304608F016FD43 +:1022C000494608F091FC0646A06908F00FFD19E0A8 :1022D000EC07002074000020BC08002082010020D0 :1022E000700400208C0A00204C3D0F44B0010020F7 :1022F0000000C842AE01002080E6C547B1DC423E86 -:10230000D048874A394608F061FC314608F006FC9F -:1023100009F0E6FB8346A061E06808F0E2FC0746AE -:10232000654908F053FC0646206908F0D1FC814657 -:102330006248806808F0CCFCE16D08F047FC394643 -:1023400008F044FC494608F077FC0746206C31460B -:10235000009008F03BFC81464FF0FF31384608F012 -:10236000ABFC314608F032FC494608F0D7FB616C03 -:1023700008F0D4FBD5F83890824649464FF07E509D -:1023800008F01EFC0646584608F0A2FC314608F04C -:102390001DFC06464946504608F018FC314608F038 -:1023A000BDFB606408F0A2FC60653946009808F047 -:1023B000B5FB2064FFF710FFD4E915104FF49677B2 -:1023C000401AC7F100093A46494604F08DFB0A213C +:10230000D048874A394608F06FFC314608F014FC83 +:1023100009F0F4FB8346A061E06808F0F0FC074692 +:10232000654908F061FC0646206908F0DFFC81463B +:102330006248806808F0DAFCE16D08F055FC394627 +:1023400008F052FC494608F085FC0746206C3146EF +:10235000009008F049FC81464FF0FF31384608F004 +:10236000B9FC314608F040FC494608F0E5FB616CD9 +:1023700008F0E2FBD5F83890824649464FF07E508F +:1023800008F02CFC0646584608F0B0FC314608F030 +:102390002BFC06464946504608F026FC314608F01C +:1023A000CBFB606408F0B0FC60653946009808F02B +:1023B000C3FB2064FFF710FFD4E915104FF49677A4 +:1023C000401AC7F100093A46494604F09BFB0A212E :1023D000FFF781FB297906467143C81701EB50606E -:1023E000C822C011514204F07FFBE061A97B4CF28E +:1023E000C822C011514204F08DFBE061A97B4CF280 :1023F00050327143C81701EB9060216A01EBA010C5 -:102400005142206204F070FBC117206200EBD150F2 -:10241000E16901EB6020E061404608F062FC804623 -:10242000A669A06C301A08F053FC254908F0CEFBD1 -:10243000414608F001FC08F059FC3A464946A664BA -:1024400004F052FB0A21FFF746FB6F6B80463946CA -:102450004FF07E5008F0B4FB0646404608F038FCCA -:10246000314608F0B3FB06463946206C08F0AEFB57 -:10247000314608F053FB206408F038FC4FF47A72C0 -:10248000514204F031FB08F023FC206409F028FBE2 +:102400005142206204F07EFBC117206200EBD150E4 +:10241000E16901EB6020E061404608F070FC804615 +:10242000A669A06C301A08F061FC254908F0DCFBB5 +:10243000414608F00FFC08F067FC3A464946A6649E +:1024400004F060FB0A21FFF746FB6F6B80463946BC +:102450004FF07E5008F0C2FB0646404608F046FCAE +:10246000314608F0C1FB06463946206C08F0BCFB3B +:10247000314608F061FB206408F046FC4FF47A72A4 +:10248000514204F03FFB08F031FC206409F036FBB8 :102490000521FFF720FB6062297E96224143C81781 -:1024A00001EB107000116FF0950104F01DFBE16964 +:1024A00001EB107000116FF0950104F02BFBE16956 :1024B000081AE0610120A8E6BD378635C80800206B -:1024C0000024744970B5994D0446286807F009FA4C -:1024D0000028FAD0E1B2286807F0EAF9204670BD7A -:1024E00086B005F02BFE0020FFF797FAFFF75CF8A7 +:1024C0000024744970B5994D0446286807F017FA3E +:1024D0000028FAD0E1B2286807F0F8F9204670BD6C +:1024E00086B005F039FE0020FFF797FAFFF75CF899 :1024F0008F4C002594F8090118B101281ED0092835 -:102500001CD08DF8105084F8095104A804F0CCFCBC -:1025100004F0F2FA0E20FFF797FA00F050F9607914 +:102500001CD08DF8105084F8095104A804F0DAFCAE +:1025100004F000FB0E20FFF797FA00F050F9607905 :1025200001260E280DD008280BD08DF8065000BFCC :102530004FF48070FFF795FA50B905E08DF8100060 :10254000E3E78DF80660F3E70820FFF78AFA00B1A9 @@ -604,25 +604,25 @@ :1025A000E000ADF80A004FF48040FFF75AFA08B196 :1025B000B4F8DA00ADF80C00B7F8B000ADF80E00D2 :1025C00094F80901012823D0092824D08DF8075058 -:1025D000684605F065FC5849002040F2DE5200BF15 +:1025D000684605F073FC5849002040F2DE5200BF07 :1025E00021F81020401CC0B21228F9D35449534896 :1025F0000827086088F811703846FFF732FAB0B142 :1026000094F8120158B1012809D002281CD10AE01F :102610008DF80760DCE707208DF80700D8E7484809 -:1026200003F056FF10E0464804F0D5FB0CE094F8A8 +:1026200003F056FF10E0464804F0E3FB0CE094F89A :102630001D0128B194F91E01002801DA84F81E5109 :1026400094F81E0103F01BFD0120FFF70AFA30B1D8 :102650004FF48060FFF705FA08B102F0AFF839498E :102660004FF0100AC1F800A0A1F10409B846C9F85A :1026700000700025A9F10407386880F01000386068 -:10268000386880F008003860192005F037FD012017 -:1026900005F03FFD192005F031FD002005F039FD62 +:10268000386880F008003860192005F045FD012009 +:1026900005F04DFD192005F03FFD002005F047FD38 :1026A0006D1CEDB20A2DE7D3C9F80080C9F800A06F :1026B00001F03CFDFFF7ECF90220FFF7D2F908B179 :1026C00001F000FED4F8200102F0A9F95846FFF706 -:1026D000C8F928B194F82811D4F8240107F006F8B5 +:1026D000C8F928B194F82811D4F8240107F014F8A7 :1026E0004FF40060FFF7BDF908B104F09FF805F062 -:1026F000DCFC154908606079052803D113494FF4C3 +:1026F000EAFC154908606079052803D113494FF4B5 :10270000C870088012494FF47A7008801149C820B7 :102710000880114880F80D6001F046F8FCE7044895 :10272000B0F9D40000F041F9FEE70000E008002015 @@ -646,8 +646,8 @@ :10284000C6E90283C6E9007C401C8842F0DB4FF4F5 :102850008040FFF706F9D8B12778012F18D9002654 :1028600014E000BF05EB06144FF0FF384146A068A6 -:1028700008F022FAA0604146606808F01DFA606026 -:102880004146E06808F018FA761CE060BE42E9DBD9 +:1028700008F030FAA0604146606808F02BFA60600A +:102880004146E06808F026FA761CE060BE42E9DBCB :10289000BDE8F0417CE7F0B5401C0021B04A0B4692 :1028A00002EB0114491C23610C29F9DBAE4B03EB4D :1028B000C0014C68002C11D0002113F830000BE04F @@ -657,22 +657,22 @@ :1028F000E0882189082A27D006DC012A15D0042A7D :1029000029D0052A06D10AE00E2A29D0142A22D07D :10291000152A25D02020FFF7A4F8002832D02188DE -:10292000002005F04DFB618813E091498A48091D9C +:10292000002005F05BFB618813E091498A48091D8E :1029300090F8B300498908B100201FE08D48407825 -:102940000028F9D10021F7E70146002005F038FB07 -:102950002189012012E0002005F032FB6189F8E7AF -:102960000146002005F02CFB2189012005F028FB01 -:102970006189022005F024FBA1890320BDE81040F5 -:1029800005F01EBB10BD70B5764E0024183E784D84 -:1029900007E000BF36F81410204605F006FB641C63 +:102940000028F9D10021F7E70146002005F046FBF9 +:102950002189012012E0002005F040FB6189F8E7A1 +:102960000146002005F03AFB2189012005F036FBE5 +:102970006189022005F032FBA1890320BDE81040E7 +:1029800005F02CBB10BD70B5764E0024183E784D76 +:1029900007E000BF36F81410204605F014FB641C55 :1029A000E4B228788442F5D370BD714A6D4B0021A2 :1029B0001278183B04E000BF23F81100491CC9B28B :1029C0009142F9D3DFE72DE9F047DFF8A891684C91 :1029D000002599F80100684F614E241D48B3B6F8F0 -:1029E000D220B6F8D010B7F9060004F07DF85D49A2 +:1029E000D220B6F8D010B7F9060004F08BF85D4994 :1029F000E0811839B046088096F81B01564E4FF01A :102A0000640A48B30220FFF7A9FEB6F97E20B6F9A2 -:102A10007C1004F069F8B8F81431181A0FFA80FC29 +:102A10007C1004F077F8B8F81431181A0FFA80FC1B :102A20005348B0F90220624506DA98F81B111144A8 :102A300007E0B6F8D400DAE704DD98F81B11A2EB42 :102A40000101418096F98210B0F9020001FB00F10A @@ -686,18 +686,18 @@ :102AC000E8DBBDE8F0872DE9FC5F294C2A4E2B4D51 :102AD0002078032814D9B6F904004142002801DD0A :102AE000024600E00A4602F1640200DC08466FF08C -:102AF0006301A1EB0001B5F9040003F0F5FFA88024 +:102AF0006301A1EB0001B5F9040004F003F8A8801C :102B00001B48DFF86090DFF850A00078A9F11809A1 :102B100001284FD9002480464AE000BF9AF9B2004C -:102B2000B5F904104042484308F0D2F80D49183175 -:102B300001EB0417F96808F049F80190B5F90000B5 -:102B400008F0C6F8796808F041F80090B5F902007D -:102B500008F0BEF8B96813E0EC0700209C0A0020DA -:102B6000700400200C090020A4D00008E008002018 +:102B2000B5F904104042484308F0E0F80D49183167 +:102B300001EB0417F96808F057F80190B5F90000A7 +:102B400008F0D4F8796808F04FF80090B5F9020061 +:102B500008F0CCF8B96813E0EC0700209C0A0020CC +:102B6000700400200C090020C0D00008E0080020FC :102B7000B40000208C0A002044010020360100200F -:102B800008F024F88346B6F9060008F0A1F8396881 -:102B900008F01CF8594607F0C1FF009907F0BEFF86 -:102BA000019907F0BBFF08F0A1F829F81400641C94 +:102B800008F032F88346B6F9060008F0AFF8396865 +:102B900008F02AF8594607F0CFFF009907F0CCFF5C +:102BA000019907F0C9FF08F0AFF829F81400641C78 :102BB0004445B3D3DFF8B483DFF8B4B3ED4C98F8F1 :102BC0000500082868D006DC012837D0042809D081 :102BD000052840D140E00E285BD014287ED015286F @@ -713,7 +713,7 @@ :102C7000FFF774FD3044208093F90800B5F9001087 :102C8000484390FBF2F20120FFF768FD104460809A :102C9000A4E0FFF798FEA1E0B74F787888B3B8F8C2 -:102CA000D220B8F8D010B6F9060003F01DFFE0817D +:102CA000D220B8F8D010B6F9060003F02BFFE0816F :102CB000A9F80000B87A4FF0010100284FF0030096 :102CC00023D0FFF759FDB6F9021000FB01F30221F2 :102CD0000320FFF751FDB6F9001000E042E000FBD1 @@ -742,18 +742,18 @@ :102E400095FBF2F535442580BBF900104B4393FB0D :102E5000F2F10844608000254FEA0A0606EBC5003F :102E60006C30B0F90220B0F9001034F9150003F00D -:102E70003BFE24F815006D1C082DEFD396F8B40026 +:102E700049FE24F815006D1C082DEFD396F8B40018 :102E8000DFF8FCA0400711D500252020FEF7E9FD62 :102E900000B102250024564606EB44000189601962 -:102EA000C0B205F08DF8641C042CF5D3314F01201D +:102EA000C0B205F09BF8641C042CF5D3314F01200F :102EB0003F1F4D46B9F900603A7805E035F910102A :102EC000B14200DD0E46401C9042F7D3002448E09A :102ED000B8F8D200B04205DA35F81410301A081AE2 :102EE00025F814004FF48040FEF7BBFDA0B1BAF9FD :102EF000060040F2DC518842404604DDB0F8D220A2 :102F0000B8F8D81003E0B0F8D620B8F8D41035F9E6 -:102F1000140003F0E9FD15E0B8F8D220B8F8D0109D -:102F200035F9140003F0E0FD25F81400BAF9061095 +:102F1000140003F0F7FD15E0B8F8D220B8F8D0108F +:102F200035F9140003F0EEFD25F81400BAF9061087 :102F3000B8F81601814207DA1020FEF792FD38B189 :102F4000B8F8D40025F814000B48407818B107E011 :102F5000B8F8D000F6E70B4830F8140025F8140054 @@ -762,8 +762,8 @@ :102F80009C0A00200C0900202DE9F04717468946CD :102F900006460025DFF83C841AE0002411E000BF5B :102FA000D8F8001081F00801C8F80010012005F0E1 -:102FB000B0F8484605F0A2F8002005F0AAF8641C15 -:102FC000E4B2B442ECD33C2005F098F86D1CEDB2AD +:102FB000BEF8484605F0B0F8002005F0B8F8641CEB +:102FC000E4B2B442ECD33C2005F0A6F86D1CEDB29F :102FD000BD42E2D3BDE8F0872DE9FC5FFE4C002541 :102FE00040F2DC51B4F90600FC4E4FF4FA7388420B :102FF00001DA64210CE0F949B0F5FA6F91F8251077 @@ -788,22 +788,22 @@ :103120007F7D4F4397FBF3F108F10303A6429954C7 :1031300005DAAC4931F812305B4221F81230521CEA :10314000032AFFF66FAFDFF898A24FF4FA625446F5 -:10315000BAF8161103F0C8FCB4F816114FF47A72DD +:10315000BAF8161103F0D6FCB4F816114FF47A72CF :10316000401A5043C1F5FA61B0FBF1F1642291FBC2 :10317000F2F0994B6FF01806323303EB400433F949 :1031800010307043B4F9024001EB8000E41A44436C :1031900094FBF2F0DFF84C828F4E1844103EA8F8F2 :1031A0000600707AA8F17C04E8B38F48B4F91E10C9 -:1031B000B0F90000401A07F08BFD8C4907F006FDBE -:1031C0008B4907F039FD074608F0CAFB01903846E5 -:1031D00008F0ACFF00904746B8F9000007F078FD12 -:1031E0008346009907F0F2FC8046B7F9020007F029 -:1031F0006FFD8146019907F0E9FC414607F08EFC1E -:1032000007F074FD80464846009907F0DFFC8146D0 -:103210005846019907F0DAFC494607F0D1FC07F05F -:1032200065FD388000E001E0A7F802800220FEF78B +:1031B000B0F90000401A07F099FD8C4907F014FDA2 +:1031C0008B4907F047FD074608F0D8FB01903846C9 +:1031D00008F0BAFF00904746B8F9000007F086FDF6 +:1031E0008346009907F000FD8046B7F9020007F01A +:1031F0007DFD8146019907F0F7FC414607F09CFCF4 +:1032000007F082FD80464846009907F0EDFC8146B4 +:103210005846019907F0E8FC494607F0DFFC07F043 +:1032200073FD388000E001E0A7F802800220FEF77D :1032300018FC002750B3E078401CC0B20621B0FB58 -:10324000F1F2E07001FB1200B8B9002003F09EFE1D +:10324000F1F2E07001FB1200B8B9002003F0ACFE0F :103250002179614A01F00703AC3A491C22F81300B6 :103260002171002032F81010401C29448DB208282A :10327000F8DBE80801F00EF8A072A07AE18C884231 @@ -814,14 +814,14 @@ :1032C000091D0860717811B14249083108604FF456 :1032D0000060FEF7C6FB08B103F0BDFA8020FEF7E0 :1032E000C0FB48B1E16C606B411A05D44CF250311F -:1032F0000844E06405F024FAA16C606B411A03D421 +:1032F0000844E06405F032FAA16C606B411A03D413 :10330000717BF9B10120B07002F027F82020FEF7A0 :1033100093FB68B1216D606B411A09D4E17A0529EC :1033200006D3364908442065286880F010002860DC :103330003348816800290ED002B02A48BDE8F05F0A :103340005C380847B770296881F0080129602D4969 :103350000844A064D8E7BDE8FC9F10B5204C204489 -:1033600090F80A0104F036FEA0F2EE2140F2DD52A0 +:1033600090F80A0104F044FEA0F2EE2140F2DD5292 :10337000914201D3B4F8140110BD2DE9F047194E64 :10338000DFF854807C3EA8F19C087079124F401CF5 :1033900000247071A14608F14005F16B2046884772 @@ -845,17 +845,17 @@ :1034B0001046DFF8949300240090E04EF07808B9AD :1034C0003079E8B3022C3FDADE484FF4FA72443028 :1034D00030F914103BF9140001EB4000514203F0A5 -:1034E00003FBDA49DFF868A331F91410411A0AEB3B +:1034E00011FBDA49DFF868A331F91410411A0AEB2D :1034F0004400B0F9280001EB00089AF80810642095 :1035000001FB08F191FBF0F09AF81C1001EB81022D -:10351000494201EB810103F0E7FA0190C94842F208 +:10351000494201EB810103F0F5FA0190C94842F2FA :103520001072743050F8241001EB0800514203F07F -:10353000DBFAC449743141F824009AF8121000E013 +:10353000E9FAC449743141F824009AF8121000E005 :1035400008E048434FEA203AF07818B1307908B9DA :10355000022C48D13BF91450B84F05EB850001010E :10356000BB48A83F00EB04084FF47A5298F80100DA :1035700091FBF0F039F91410401A57F82410084460 -:10358000514203F0B1FA47F8240039F9140000F56C +:10358000514203F0BFFA47F8240039F9140000F55E :103590002070B0F5A06F02D857F8240002E0002098 :1035A00047F824007D2190FBF1F098F80B10484378 :1035B00087113079A8B1022C13DA0098009AC0F56F @@ -872,13 +872,13 @@ :10366000F05F764E4FF0000BDFF8E4A1DFF8D49165 :103670005C46A83E714DE87808B92879D0B1022C93 :1036800018DA70484FF4FA72443030F914103830B8 -:1036900030F9140001EB4000514203F025FA6B4968 +:1036900030F9140001EB4000514203F033FA6B495A :1036A00031F91410411A0AEB4400B0F9280001EB7B :1036B000000B01E0022C52D0E878E0B39AF8080041 :1036C00000FB0BF0001160490AEB040731F91410FC :1036D000FA7A451A787856F8241068434FEAE018C9 :1036E000B9F80C006843C01200FB02104FF400123E -:1036F00046F82400514203F0F7F946F8240043133A +:1036F00046F82400514203F005FA46F8240043132B :103700004E480C3850F8241040F82450B9F80C00FA :10371000691A02094FF6FF70B0FBF2F048434749BF :103720008011243901F10C0251F824C052F82450C0 @@ -892,7 +892,7 @@ :1037A00000E02D48086470472DE9F84F0027B9461E :1037B000B8460820FEF755F9DFF8A0B068B19BF8CD :1037C000120120B1012802D0022806D102E002F045 -:1037D000A2FE01E003F01EFB8046DFF868A0174C54 +:1037D000A2FE01E003F02CFB8046DFF868A0174C46 :1037E0004FF00005DAF83410DAF854004FF0010613 :1037F000081A02D5B8F1000F7DD044F620621144BA :10380000CAF85410FFF7B9FD4FF48040FEF729F9CC @@ -901,8 +901,8 @@ :103830000021B0F9060013E0800100208C0A00206E :10384000B0010020C80000206800002034000020E3 :10385000EC070020693400085F360008700400207F -:10386000A0F57A7003F040F907F032FAFE4907F04C -:10387000E3F9FE4907F0AAF907F051FAAAF8220085 +:10386000A0F57A7003F04EF907F040FAFE4907F030 +:10387000F1F9FE4907F0B8F907F05FFAAAF822005B :103880004FF40070FEF7EDF8B0B3DFF8E483BAF957 :103890000E2098F8ACC00CEB8C0191421DDA6078D8 :1038A000D8B1BBF91431F349002000BF21F8103022 @@ -996,9 +996,9 @@ :103E2000401CF8654FF48070FDF71BFE10B102F0E6 :103E3000DFF90CE0F86D401CF8651020FDF7FCFD83 :103E400008B100F0C6FC4FF40050FDF70AFE04F084 -:103E50002CF9CAF83400BBF80C20574612B1BB6DE0 +:103E50003AF9CAF83400BBF80C20574612B1BB6DD2 :103E6000C31A71D41044D946B865FEF757F9FFF765 -:103E7000B3F804F01AF97863398F411AB981B8633D +:103E7000B3F804F028F97863398F411AB981B8632F :103E80000820FDF7D9FD48B387491439B1F904205A :103E900002F145008A2822D8607900B3804803885F :103EA00080480088181A00B210F1B40F02DC00F547 @@ -1018,57 +1018,57 @@ :103F80000CFB131115681D441560B9837E7207E0A0 :103F9000797A29B146490A6846490A60BD837D722B :103FA0003E490988084400B2A8F80600B9F8D010C4 -:103FB000B9F8D220963102F097FDA8F806003B4DE3 +:103FB000B9F8D220963102F0A5FDA8F806003B4DD5 :103FC00095F86A0050B1E07808B9207930B13648E8 :103FD000394A1438C18812881144C1802020FDF765 :103FE0002BFDE8B3E07908B9207AC8B3207BB8B3D9 -:103FF0002B4CB4F9000006F06BFE304E314606F053 -:10400000E5FD08F093F80090B4F9000006F060FEBA -:10401000314606F0DBFD07F0A3FC234C064695F87D +:103FF0002B4CB4F9000006F079FE304E314606F045 +:10400000F3FD08F0A1F80090B4F9000006F06EFE90 +:10401000314606F0E9FD07F0B1FC234C064695F861 :10402000B900303CDFF898A0A4F11C0810B3A146F9 :10403000B4F90200241DB4F90210401A01F01EFA6E -:1040400015F8B92F514202F04FFD61880844608095 +:1040400015F8B92F514202F05DFD61880844608087 :10405000B9F90000B4F90010401A01F00FFA00E0BD -:104060004EE02A78514202F03FFD2188084400B218 -:10407000208001E0B4F9000006F02AFE8346009992 -:1040800006F0A4FD0546B4F9020006F021FE8146C3 -:10409000314606F09BFD15E028000020240000209A +:104060004EE02A78514202F04DFD2188084400B20A +:10407000208001E0B4F9000006F038FE8346009984 +:1040800006F0B2FD0546B4F9020006F02FFE8146A7 +:10409000314606F0A9FD15E028000020240000208C :1040A000B0010020B201002058010020EC070020E0 :1040B0005C000020600000200A00002035FA8E3CE1 -:1040C00000002041294606F07BFD5546514606F08A -:1040D000B3FD06F00BFEA8F80000444658463146F2 -:1040E00006F074FD06464846009906F06FFD31461D -:1040F00006F014FD294606F09FFD06F0F7FD6080EE +:1040C00000002041294606F089FD5546514606F07C +:1040D000C1FD06F019FEA8F80000444658463146D6 +:1040E00006F082FD06464846009906F07DFD314601 +:1040F00006F022FD294606F0ADFD06F005FE6080C3 :10410000386C8047FEF7DFFCFEF7E9FBBDE8F84FAF :10411000FEF739BCBDE8F88F03484178002901D08B :1041200000214170704700008C0A00202DE9F843FF :10413000FE4CFF4BFF490026B4F8EE209846A1F153 -:10414000100004F0FEFB08B101260EE0B4F8EE10FA -:10415000F84804F005FE40B9B4F8EE10F54803F055 -:1041600096FD10B9032004F073F8F34D5FF00007DB +:10414000100004F00CFC08B101260EE0B4F8EE10EB +:10415000F84804F013FE40B9B4F8EE10F54803F047 +:10416000A4FD10B9032004F081F8F34D5FF00007BF :1041700094F8ED0006283CD2DFE800F00707192884 :1041800033030220FDF765FC33E08DF800704FF437 -:104190004870E849ADF802001039684602F099FF0E +:104190004870E849ADF802001039684602F0A7FF00 :1041A00008B10120287094F8ED00012821D06EB1EB -:1041B000E049B4F8EE204346A1F1100004F0C1FB41 +:1041B000E049B4F8EE204346A1F1100004F0CFFB33 :1041C0000220287094F8ED0002281DD0D94810383C -:1041D00004F0C0FC28B10320287094F8ED000328F7 -:1041E00012D0D448103805F042FB10B104202870DA +:1041D00004F0CEFC28B10320287094F8ED000328E9 +:1041E00012D0D448103805F050FB10B104202870CC :1041F0000AE0287840B994F8ED0010B184F8ED7029 -:10420000B6E70220FDF725FCCA48103004F0ABFEEB -:1042100038B9C848103003F003F810B90420FDF78E +:10420000B6E70220FDF725FCCA48103004F0B9FEDD +:1042100038B9C848103003F011F810B90420FDF780 :1042200018FC0220FDF708FC28B1C24994F8E3000D :10423000103909688847BF4914F8E20F09688847B0 -:10424000A07803F007F910B90820FDF702FCBB487D +:10424000A07803F015F910B90820FDF702FCBB486F :104250006421B0F9262092FBF1F001FB102406B294 -:104260000820FDF7E9FBB64D90B1204606F030FD81 -:10427000B44906F0ABFC0446304606F029FD214661 -:1042800006F04CFCB04906F0A1FC2860BDE8F883BC +:104260000820FDF7E9FBB64D90B1204606F03EFD73 +:10427000B44906F0B9FC0446304606F037FD214645 +:1042800006F05AFCB04906F0AFFC2860BDE8F883A0 :104290002F60FBE770B50546A44890F8060106F0CC -:1042A00020FD0446284606F01CFDA84906F08EFCB9 -:1042B000A74906F0C1FC214606F088FC06F02FFD58 -:1042C00080B270BD70B500252C46002002F05EFE65 -:1042D00005440A2003F012FF641C202CF5D3C5F31B +:1042A0002EFD0446284606F02AFDA84906F09CFC8F +:1042B000A74906F0CFFC214606F096FC06F03DFD2E +:1042C00080B270BD70B500252C46002002F06CFE57 +:1042D00005440A2003F020FF641C202CF5D3C5F30D :1042E0004F10FFF7D7FF914A022192F8073100BF24 :1042F00003FB01F4844202D8491C0629F8D39548EF :10430000017092F8080148439349088070BD2DE977 @@ -1117,12 +1117,12 @@ :1045B000DFF884820024A3464FF47A79A8F10C0630 :1045C000A888484507D104EB840208EB820146F82D :1045D00024B0C1F810B0994F56F8241037F91400E0 -:1045E000014446F8241006F073FB014604EB8402F4 +:1045E000014446F8241006F081FB014604EB8402E6 :1045F00008EB8200824600F0EFF827F814B0904FE5 :1046000027F814B0A888012837D1DAF8100001285B -:1046100008DD401E06F05CFB0146DAF80C0006F0EF -:104620000BFB00E0002007F047FE8246854890F82B -:10463000F800A8B106F055FB514606F085FB0FD2F5 +:1046100008DD401E06F06AFB0146DAF80C0006F0E1 +:1046200019FB00E0002007F055FE8246854890F80F +:10463000F800A8B106F063FB514606F093FB0FD2D9 :104640007D49A5F80490C8F810B0C1F824B0C1F8AD :1046500038B0C6F808B0C6F804B0C6F800B00CE030 :1046600056F82400012200F5FA7090FBF9F027F8C3 @@ -1130,10 +1130,10 @@ :10468000A888401EA8806D496D4A002031F810307E :1046900032F810401B1B21F81030401C0328F5DBBA :1046A00000E7654810B54C30416864488847BDE86C -:1046B000104077E710B564481024046002F019FF39 +:1046B000104077E710B564481024046002F027FF2B :1046C0006148001F04605B490120487010BD2DE95E :1046D000F0415E48574C0068A169411A02D500209C -:1046E000BDE8F0815A490844A0615A4802F0C9FE69 +:1046E000BDE8F0815A490844A0615A4802F0D7FE5B :1046F000DFF864C14F4B00269CF80E005549514A23 :1047000026339D1D88B1A069E061002002EB4007BF :10471000A7F8006131F8107023F8107025F81070B8 @@ -1147,26 +1147,26 @@ :1047900033F9101035F91040214402EB400401EBCD :1047A000D17141F34F01401CA4F800110328EFD34D :1047B00001210846FCF77BFF012091E710B501209D -:1047C00004F015FA1020FDF73FF925490020086094 -:1047D00010BD234804F05FBA2DE9F041044600699A -:1047E0000E46401C206101281FD006F071FA256892 -:1047F00080462946304606F0E3F90746414606F072 -:104800001BFA294606F08AF90546606029463046BB -:1048100006F0D6F90146384606F0D8F9A16806F048 -:104820007DF92560E060A0605AE7666000202660A0 +:1047C00004F023FA1020FDF73FF925490020086086 +:1047D00010BD234804F06DBA2DE9F041044600698C +:1047E0000E46401C206101281FD006F07FFA256884 +:1047F00080462946304606F0F1F90746414606F064 +:1048000029FA294606F098F905466060294630469F +:1048100006F0E4F90146384606F0E6F9A16806F02C +:104820008BF92560E060A0605AE766600020266092 :10483000F9E700007C010020200C0020740000201B :10484000A800002070040020140C0140FC0000208F :10485000A0860100860000208C0A002080C3C901C8 :10486000B000002070B5F34CF34EC1B20546A17004 -:10487000306805F01DF8E079A1784840E071C5F393 -:104880000721A170306805F013F8E079A17848405D -:10489000E071C5F30741A170306805F009F8E079CF -:1048A000A1784840E071290EA170306805F000F849 +:10487000306805F02BF8E079A1784840E071C5F385 +:104880000721A170306805F021F8E079A17848404F +:10489000E071C5F30741A170306805F017F8E079C1 +:1048A000A1784840E071290EA170306805F00EF83B :1048B000E079A1784840E07170BD70B5DD4CDE4E06 -:1048C000C1B20546E170306804F0F2FFE079E178AA -:1048D0004840E071C5F30721E170306804F0E8FF5B +:1048C000C1B20546E170306805F000F8E079E178A2 +:1048D0004840E071C5F30721E170306804F0F6FF4D :1048E000E079E1784840E07170BD10B50446D248E7 -:1048F0002146006804F0DCFFCE48C1796140C171F7 +:1048F0002146006804F0EAFFCE48C1796140C171E9 :1049000010BDCC4ACD48117A405C491C11727047E9 :1049100000B5FFF7F6FF0346FFF7F3FF03EB0020B8 :1049200080B200BD10B5FFF7F3FF0446FFF7F0FFBC @@ -1181,12 +1181,12 @@ :1049B00010BD2DE9F05FDFF87CB2DFF878920127B7 :1049C0004FF0000A0BF10C0B00251AE09B4814383D :1049D000405D00EB40010BEB8108D8F8040006F0C5 -:1049E0004EF806460FB1B2440AE0002406E000BFCC +:1049E0005CF806460FB1B2440AE0002406E000BFBE :1049F000D8F80400005DFFF778FF641CB442F7DBD1 :104A00006D1C99F800008542E0DB002F05D00AF00C :104A1000FF00FFF7A9FF0027D6E7BDE8F09F70B5BC -:104A2000024603230021864803F0E8FC8249FF2266 -:104A3000086082481421143805F0DBFF7F4D002008 +:104A2000024603230021864803F0F6FC8249FF2258 +:104A3000086082481421143805F0E9FF7F4D0020FA :104A4000143D012428700220FCF7F6FF20B101205C :104A500068700220A87003240420FCF7EDFF50B119 :104A600003202855641C4FF40050FCF7FAFF10B1E6 @@ -1241,7 +1241,7 @@ :104D7000FFF7FAFDE620FFF7B8FD6879FFF7B5FD0C :104D80000020FFF7B2FD95F81B0100B10820EA49A9 :104D900050EA0100FFF766FD05E70B20FFF7E4FD91 -:104DA000E648008800B2FFF788FD02F0ACFE00B2D2 +:104DA000E648008800B2FFF788FD02F0BAFE00B2C4 :104DB000FFF783FD0220FCF73FFE04460420FCF7CA :104DC0003BFE44EA40040820FCF736FE44EA800437 :104DD0002020FCF731FE44EAC0041020FCF72CFE32 @@ -1304,7 +1304,7 @@ :10516000D30000204C0100207601002078010020AF :1051700066010020720100207401002064010020FB :1051800034000020B0010020E60000205C00002078 -:105190002C000020D2000020EA0000205CD1000892 +:105190002C000020D2000020EA00002078D1000876 :1051A00095F83600FFF7A1FB95F83800FFF79DFB57 :1051B00095F83700FFF799FB2DE00820FFF7D4FBA7 :1051C0000024601CC0B2FFF790FB641C082CF8D3CD @@ -1334,17 +1334,17 @@ :1053400018F80400FFF7D1FA19F80400FFF7CDFAB6 :10535000641C28788442EDD325E470B5444C454E56 :105360000025607810B3BDE87040FBF755BE30688B -:1053700004F0B1FAA17951B101291CD002291FD042 +:1053700004F0BFFAA17951B101291CD002291FD034 :10538000032923D0042929D005293FD12CE0242842 :1053900003D00021A17149B901E00121FAE72328D6 :1053A00002D0522832D102E0FBF736FE2EE0012077 -:1053B00002F06FFF2AE04D2804D10220A07125E001 +:1053B00002F07DFF2AE04D2804D10220A07125E0F3 :1053C0003C2801D00020F9E70320F7E740281CD84B :1053D000607125712572E0710420EFE76072E17958 :1053E0004140E1710520E9E721796279914207D2D4 :1053F000E2794240E271204A5054491C217105E093 :10540000E179814201D1FFF772FBA571306804F0A8 -:105410005FFA0028ABD16078002809D14FF4006012 +:105410006DFA0028ABD16078002809D14FF4006004 :10542000FCF71FFB002803D0BDE8704001F02DBA47 :1054300070BD0000540100205C01002060000020CD :10544000C90000207E0100200804002040420F0017 @@ -1353,39 +1353,39 @@ :10547000B4010020E0080020A80C002044F2506194 :10548000884201DDA0EB4100FE49884202DA48F67D :10549000A041084470472DE9F047064650689946F8 -:1054A00014460D46301A05F013FC296805F0C4FBBC -:1054B0002061A768394605F083FB8046F24890F8E2 -:1054C000B80005F00EFCF14905F080FB01464FF0F5 -:1054D0007E5005F0B1FB2D68294605F01FFB014603 -:1054E000284605F0A9FB414605F070FB394605F05A -:1054F00015FB2061C4E901600146D9F8080005F0F8 -:1055000065FBBDE8F04705F0F1BB2DE9F0411D4614 -:1055100014460E4605F0DCFB696805F057FB316860 -:1055200005F054FB216805F0F9FA2060ED680746A4 -:10553000284605F0DBFB064685F0004005F0D6FB6B -:105540000546384605F0D2FB3246294601F0CCFA32 -:1055500005F0BEFB2060BDE8F04105F0C7BB70B5AB +:1054A00014460D46301A05F021FC296805F0D2FBA0 +:1054B0002061A768394605F091FB8046F24890F8D4 +:1054C000B80005F01CFCF14905F08EFB01464FF0D9 +:1054D0007E5005F0BFFB2D68294605F02DFB0146E7 +:1054E000284605F0B7FB414605F07EFB394605F03E +:1054F00023FB2061C4E901600146D9F8080005F0EA +:1055000073FBBDE8F04705F0FFBB2DE9F0411D46F8 +:1055100014460E4605F0EAFB696805F065FB316844 +:1055200005F062FB216805F007FB2060ED68074687 +:10553000284605F0E9FB064685F0004005F0E4FB4F +:105540000546384605F0E0FB3246294601F0DAFA16 +:1055500005F0CCFB2060BDE8F04105F0D5BB70B58F :10556000CB4CD4E90D01401AFFF788FF0028D4E99D :105570000D01A0EB010002DDFFF780FF02E0FFF765 :105580007DFF404241F29411884228DAD4E90D01AE -:10559000401A05F09DFBBF4905F018FB0646E06B7D -:1055A00005F09FFB0546304606F0C0FD294605F094 -:1055B0000DFB05F09BFB00B240F6B8322082514251 -:1055C00001F092FA616B084448F6A0416064884299 +:10559000401A05F0ABFBBF4905F026FB0646E06B61 +:1055A00005F0ADFB0546304606F0CEFD294605F078 +:1055B0001BFB05F0A9FB00B240F6B8322082514235 +:1055C00001F0A0FA616B084448F6A041606488428B :1055D00000DD401A002800DA0844606470BD606B8A :1055E000FBE72DE9FE4F0546FFF7B9FFA84842F259 -:1055F0002831406C081A05F06BFBA64905F0E6FA65 -:10560000044606F0ADF90190204606F08FFD0090AB -:105610000024284605F05CFBDFF874A2DFF87892DE +:1055F0002831406C081A05F079FBA64905F0F4FA49 +:10560000044606F0BBF90190204606F09DFD00908F +:105610000024284605F06AFBDFF874A2DFF87892D0 :10562000DFF878B20AF1300A029099481A3030F95E -:10563000140005F04DFB05465DF82410029805F0B6 -:10564000C5FA294605F0BCFA05F050FB00B24FF44C -:105650007A7255462AF81400514201F045FA8E49F3 +:10563000140005F05BFB05465DF82410029805F0A8 +:10564000D3FA294605F0CAFA05F05EFB00B24FF422 +:105650007A7255462AF81400514201F053FA8E49E5 :1056600000B225F81400603900F080FE04EB8406D7 :10567000894B8749074609EB8602904635F91400A5 :10568000603B2831FFF741FF834B81490744424685 :1056900035F91400603B2831FFF7FDFE384400B2B5 -:1056A00040F6B8325D462BF81400514201F01CFA66 +:1056A00040F6B8325D462BF81400514201F02AFA58 :1056B00025F81400784859F826102838641C40F85A :1056C0002610022CB1DBBDE8FE8F2DE9F05F704E95 :1056D0000024DFF8C4915036DFF8C0B1A6F1360AD5 @@ -1395,36 +1395,36 @@ :10571000241004EB840708445F4B5D4909EB8702C2 :105720009046703B2831FFF7F0FE28445A4B584909 :105730002BF814005D46424656F82400703B283191 -:10574000FFF7A9FE4FF4FA62514201F0CDF93AF9A0 +:10574000FFF7A9FE4FF4FA62514201F0DBF93AF992 :1057500014103131622900D8002035F8141040F6B9 -:10576000B832084400B225F81400514201F0BCF9E7 +:10576000B832084400B225F81400514201F0CAF9D9 :1057700025F81400484859F82710641C40F82710F1 :10578000022CAFDBBDE8F09F70B5054608681968CC -:105790001446401A05F09CFA3D49C96A05F016FA0C -:1057A00005F0A4FA01463A48503041602968226861 +:105790001446401A05F0AAFA3D49C96A05F024FAF0 +:1057A00005F0B2FA01463A48503041602968226853 :1057B000891A016070BD2DE9F0410F46DDE90685CB -:1057C000116800681E46081A05F082FA044630681F -:1057D0003968401A05F07CFA2D49C96A05F0F6F9D6 -:1057E0000646014605F0F2F907462146084605F04F -:1057F000EDF9394605F092F906F05EFD284905F00D -:10580000E5F905F08CFAC8F8000084F00040314654 -:1058100005F07CFF234905F0D9F9234905F07EF90D -:1058200005F064FA2860002803DA48F6A04108442D +:1057C000116800681E46081A05F090FA0446306811 +:1057D0003968401A05F08AFA2D49C96A05F004FAB9 +:1057E0000646014605F000FA07462146084605F040 +:1057F000FBF9394605F0A0F906F06CFD284905F0E3 +:10580000F3F905F09AFAC8F8000084F00040314638 +:1058100005F08AFF234905F0E7F9234905F08CF9E3 +:1058200005F072FA2860002803DA48F6A04108441F :105830002860BDE8F0812DE9F0471C48144CD0E900 :105840000056617804F1480991B34FF07E50A16A87 -:1058500005F0F2F98246D9F80400301A05F038FA5A -:10586000E16A05F0B3F9514605F0B0F905F03EFAEA -:1058700007B2D9F8000004F11A08281A05F028FA2E +:1058500005F000FA8246D9F80400301A05F046FA3D +:10586000E16A05F0C1F9514605F0BEF905F04CFAC0 +:1058700007B2D9F8000004F11A08281A05F036FA20 :10588000514616E0B0B9FFFFEC070020DB0FC9401E :10589000BC020020D30237398C0D002028010020E3 :1058A0002C7D8E3FA00CB34500A00C464C0100207F -:1058B0001AE005F08BF905F019FA01B204F12400A1 +:1058B0001AE005F099F905F027FA01B204F1240085 :1058C000B0F902203A4402EBD27242F34F02A8F838 :1058D0000220B0F90030194401EBD17141F34F01BE :1058E000A8F800104280018001206070C9E90056CC -:1058F000BDE8F08710B5044605F0EAF9002C01DC9C -:1059000080F00040F74905F097F9F74905F05EF996 -:1059100006F026F8F549C86210BD10B5F44CE07ADF +:1058F000BDE8F08710B5044605F0F8F9002C01DC8E +:1059000080F00040F74905F0A5F9F74905F06CF97A +:1059100006F034F8F549C86210BD10B5F44CE07AD1 :10592000002811D0F348007805280DD3F249F34A36 :105930000868106049685160FFF7DCFFF048EB49E8 :10594000008888820120207310BD2DE9F043E749CB @@ -1461,7 +1461,7 @@ :105B300054181D559C5C00EB80004000A4F1300619 :105B4000092E01D830382044521C9C5C002CEAD12C :105B500070BD2DE9F04100268046354637460446A3 -:105B600004F008FF016800E0641C2078085C20282D +:105B600004F016FF016800E0641C2078085C20281F :105B7000FAD0404609E01EB106EB86025206160E28 :105B800010F8012B303E3244D6B2221A022AF2DC3F :105B900009E01DB105EB85025206150E10F8012B28 @@ -1502,7 +1502,7 @@ :105DC00088426771EBD1A0790128E8D190E52DE9EF :105DD000FF5FD949C0B291F81D1119B1012904D052 :105DE00002297CD1FFF703FF01E0FFF730FE002816 -:105DF00075D0CC4C1034A068E06002F070F9A0605F +:105DF00075D0CC4C1034A068E06002F07EF9A06051 :105E00002020FBF721FECD484FF0000B017801293F :105E100010D001210170C248C17A00295FD0C24967 :105E2000097805295BD38246407830B19AF80C1086 @@ -1518,8 +1518,8 @@ :105EC000FEF3A34D6D42694303EBC1119C4B70334C :105ED000B9F1010F43F8201007D1B61E00E080E0B1 :105EE000B6F5797F01D844F82010401C0228B9DBB0 -:105EF00002F0F5F8924D296A401A04F0F2FE954935 -:105F000004F09AFEA86202F0EAF82862A86A4FF04C +:105EF00002F003F9924D296A401A04F000FF954917 +:105F000004F0A8FEA86202F0F8F82862A86A4FF030 :105F10007E51884200DB0846A86203A902A88E4B86 :105F2000CDE900011A1F211D8748FFF744FC0298A4 :105F30006426B0FBF6F08949894A574608800398E1 @@ -1534,43 +1534,43 @@ :105FC0000BD2D5E90D01401AFFF758FA002800DC82 :105FD000404242F21071884203DD01202070A88AFD :105FE0001080BDE8FF9FFFF770FBFAE72DE9F0474F -:105FF0005C4C607904F075FEDFF87091494604F05E -:106000001BFE484D24352860E07B04F06AFE4946BB -:1060100004F012FE564EEE606860A07904F061FE56 -:10602000544F394604F008FE10352860207C04F0F7 -:1060300058FE494604F000FE6860A07E04F051FE60 -:10604000DFF81081414604F0F7FDC5E90206E0796A -:1060500004F047FE394604F0EFFD10352860607CFF -:1060600004F03FFE494604F0E7FD6860E07E04F07E -:1060700038FE414604F0E0FDC5E9020638E470B59B +:105FF0005C4C607904F083FEDFF87091494604F050 +:1060000029FE484D24352860E07B04F078FE49469F +:1060100004F020FE564EEE606860A07904F06FFE3A +:10602000544F394604F016FE10352860207C04F0E9 +:1060300066FE494604F00EFE6860A07E04F05FFE36 +:10604000DFF81081414604F005FEC5E90206E0795B +:1060500004F055FE394604F0FDFD10352860607CE3 +:1060600004F04DFE494604F0F5FD6860E07E04F062 +:1060700046FE414604F0EEFDC5E9020638E470B57F :1060800006460325002000F06CF94FF48070FBF702 -:10609000E8FC00281FD0234C1034667002F01FF873 +:10609000E8FC00281FD0234C1034667002F02DF865 :1060A000A06000206060244890F81D0100B901251F :1060B000FFF79CFF304906EB46002B4651F82020A5 -:1060C0002E492F4802F09AF92E494860BDE87040E9 +:1060C0002E492F4802F0A8F92E494860BDE87040DB :1060D000012000F046B970BD2DE9F041164F294D61 :1060E000104C97F81D11244E6868103411B1012925 :1060F0007BD10BE0617801EB410156F8211003F0F0 -:10610000EDFBBDE8F041032000F02BB903F0E9FB03 +:10610000FBFBBDE8F041032000F02BB903F0F7FBE7 :1061100028B120780128206937D0A8B356E064E080 :106120008C0A0020E80C0020D3000020760100201B :106130007801002066010020700400206401002026 :10614000BC020020C90000204C010020809698006D :10615000D3CEFEFF00007A445801002072010020D7 :1061600074010020EC070020B20100200000C842AA -:106170000000FA44000020418CD10008CF5D0008E7 +:106170000000FA4400002041A8D10008CF5D0008CB :1061800000440040E008002018E0052811D200EB90 -:10619000400056F82010686803F0A0FB97F91E0134 -:1061A00000EB400006EB80004168686803F083FB69 +:10619000400056F82010686803F0AEFB97F91E0126 +:1061A00000EB400006EB80004168686803F091FB5B :1061B00014E097F81E016070022014E0607800EB94 -:1061C000400056F82010686803F088FB20698C288E -:1061D00008D28449095C686803F06AFB2069401CA6 +:1061C000400056F82010686803F096FB20698C2880 +:1061D00008D28449095C686803F078FB2069401C98 :1061E000206102E0032000F0BCF80020606093E42E :1061F00010B57D4C207805282DD2DFE800F02C0367 :10620000031C0600BDE8104066E760680521401CDD :1062100060606078401CC0B2B0FBF1F201FB12007C -:10622000607001F05CFF7149A06000200870704947 -:10623000C87201200BE001F052FFA168401A40F63D +:10622000607001F06AFF7149A06000200870704939 +:10623000C87201200BE001F060FFA168401A40F62F :10624000C411884207D92020FBF703FC0420BDE8D5 :10625000104000F086B810BD2DE9F05FDFF888A18E :106260000024644FDFF89081DFF890910AF1440A2E @@ -1580,24 +1580,24 @@ :1062A00000F09BF8641C022CE6DBBDE8F09F2DE9B2 :1062B000F0414D480078032802D04FF0FF302BE426 :1062C0004F4C504D002061684FF00808C862C5F877 -:1062D000008010262E602F1D606803F0F9FA50B17F -:1062E000C7F80080606803F0F6FA0146206803F002 -:1062F000DFFAC5F80080206803F0EAFA0028EBD046 -:106300003E60206803F0E7FA0146606803F0D0FAC7 +:1062D000008010262E602F1D606803F007FB50B170 +:1062E000C7F80080606803F004FB0146206803F0F3 +:1062F000EDFAC5F80080206803F0F8FA0028EBD02A +:106300003E60206803F0F5FA0146606803F0DEFAAB :106310002E60E1E77CB53C4C026822600968616050 :106320000068FFF7E7FAA4F1240101F10800374EF5 :10633000CDE90001231D2246311D3046FFF73BFA0F :10634000A4F15805331D686B68643246211D204650 :10635000FFF71AFA686BA8632D48B0F8BC00688292 :106360007CBD2149087000200861704710B50C46BB -:1063700004F0AEFC216804F029FCBDE8104004F0F4 -:10638000B5BC70B5204C583CE26B21B1B0EB520F5C +:1063700004F0BCFC216804F037FCBDE8104004F0D8 +:10638000C3BC70B5204C583CE26B21B1B0EB520F4E :106390000BD3500809E0904200D310461C4900B2CC :1063A000B1F8BC10814200DB0846B4F9125000B2CB -:1063B000A84208DD1749A06A04F008FC04F096FC26 +:1063B000A84208DD1749A06A04F016FC04F0A4FC0A :1063C000284400B2608270BD3038C0B2092801D9BB :1063D000C01FC0B200F00F00704700210160416093 -:1063E00081607047C8D10008F80C0020D30000205D +:1063E00081607047E4D10008F80C0020D300002041 :1063F0008C0A00200C0100202C0100202801002024 :10640000E0080020100C0140140300204C01002083 :10641000EC0700200000C842F0B5404A404C11781B @@ -1609,29 +1609,29 @@ :106470000A0149B154F820004FF4777101EB500044 :1064800006E0B1F81401F0BD34F8200000F5777093 :1064900080B2F0BD70B5214C01260546A67001F012 -:1064A00004FEA168421AC4E9020241F288300021C8 +:1064A00012FEA168421AC4E9020241F288300021BA :1064B000824200D9E1701A4AE0781C3215540F2844 :1064C00002D0401CE07070BD17482670018070BD7E :1064D00070B504461348114990F81221032007258E :1064E0002AB1012A08D108714D71012003E002226E :1064F0000A7148710020487001234FF4E1320B49C2 -:106500000B4801F07BFF01460A48C1600CB10A4903 +:106500000B4801F089FF01460A48C1600CB10A49F5 :106510002160457470BD0148007870473C0300203D :10652000A40E002070040020D6000020956400080E :1065300000440040E00800201964000870B57C4C5D -:1065400006460125207880B901F0C9FDA1683231E5 -:10655000884207D32570012001F0DBFD01F0BFFD6B -:10656000A06070BD20780028FBD001F0B8FDA168C4 -:1065700031448842F5D30020207001F0CAFD01F0BB -:10658000AEFD6C49A060087808B1401E08706570C7 +:1065400006460125207880B901F0D7FDA1683231D7 +:10655000884207D32570012001F0E9FD01F0CDFD4F +:10656000A06070BD20780028FBD001F0C6FDA168B6 +:1065700031448842F5D30020207001F0D8FD01F0AD +:10658000BCFD6C49A060087808B1401E08706570B9 :1065900070BDF8B5664D8DF800008DF801108DF8CE :1065A00002208DF80330A8791DF8001044292DD061 :1065B0004C2929D04D2925D04E292AD03224002615 :1065C000032806D274B12046FFF7B8FFA879032844 -:1065D00008D301F084FDA968001B884202D9554800 +:1065D00008D301F092FDA968001B884202D95548F2 :1065E000AE7106706878012801D0002C09D1A87915 :1065F000032801D2401CA8716E702E70002001F09B -:1066000088FDF8BD6424DAE7C824D8E74FF4FA64BB +:1066000096FDF8BD6424DAE7C824D8E74FF4FA64AD :10661000D5E70024D3E72DE9F047DFF81CA10546B4 :10662000434C9AF80D004FF00109002610B184F890 :10663000029000E0A6704FF40070FBF712FA3F4F93 @@ -1649,1942 +1649,1944 @@ :1066F00002E044234D224D215320BDE8F04748E7F6 :10670000442305E044234E22F5E7787810B14E2368 :106710004D22ECE70748007818B1BDE8F047322079 -:106720000CE72670BDE8F047002001F0F2BC000045 +:106720000CE72670BDE8F047002001F000BD000036 :106730004C030020C8000020E60A00208C0A00203C -:10674000EC070020D600002010B5D84C5E28A268C7 +:10674000EC070020D600002010B5DE4C5E28A268C1 :1067500007D05D280CD001461046BDE8104003F07C -:10676000A7B85D21104603F0A3F83E21A068F4E726 -:106770005D21104603F09CF83D21A068EDE72DE96E -:10678000F041132000F04AF9C94C2068002800DCD1 -:106790004042C84D90FBF5F000B200F051F91B20CB -:1067A00000F03CF92068002800DC40420A2690FBFB +:10676000B5B85D21104603F0B1F83E21A068F4E70A +:106770005D21104603F0AAF83D21A068EDE72DE960 +:10678000F041132000F055F9CF4C2068002800DCC0 +:106790004042CE4D90FBF5F000B200F05CF91B20BA +:1067A00000F047F92068002800DC40420A2690FBF0 :1067B000F6F042F2107790FBF7F107FB110000B200 -:1067C00000F03EF9232000F029F92068002801DAC2 -:1067D000532000E04E2000F033F9122000F01EF9A3 +:1067C00000F049F9232000F034F92068002801DAAC +:1067D000532000E04E2000F03EF9122000F029F98D :1067E0006068002800DC404290FBF5F000B200F049 -:1067F00027F91A2000F012F96068002800DC4042F6 +:1067F00032F91A2000F01DF96068002800DC4042E0 :1068000090FBF6F090FBF7F107FB110000B200F0EF -:1068100017F9222000F002F96068002801DA5720F9 -:1068200000E04520BDE8F04100F00AB910B54FF492 -:106830000040FBF716F9A04A9C4920B192F82901C3 +:1068100022F9222000F00DF96068002801DA5720E3 +:1068200000E04520BDE8F04100F015B910B54FF487 +:106830000040FBF716F9A64AA24920B192F82901B7 :10684000012806D002E0002082F82901086888604B -:1068500010BD9A48FBE770B5974890F8291111B917 -:10686000974A52780AB1012400E00024954D2A7815 +:1068500010BDA048FBE770B59D4890F8291111B90B +:106860009D4A52780AB1012400E000249B4D2A7809 :10687000944209D039B914B14FF4165001E0D0F860 -:106880002001FEF7CCF82C7070BD2DE9F0478A4846 -:1068900090F8290118B98A48407800287ED08348AA -:1068A000806803F015F8002878D101F018FC854DB8 -:1068B0006968401A7D2871D301F011FC686068781E -:1068C000814F401CDFF80482DFF8049268700024D6 -:1068D00004F12400C0B200F0A1F8388804F001FAF5 -:1068E000064638F9140004F0F3F9314604F0A4F92F -:1068F000494604F06BF904F0F9F900B200F0A0F891 -:10690000641C032CE4DB00F096F868784FF0640414 -:10691000800724D1102000F081F86E4E306890FB83 -:10692000F4F000B200F08CF8212000F077F8306825 -:1069300090FBF4F104FB110000B200F081F8142088 -:1069400000F06CF86448B0F9000000F079F81C2001 -:1069500000F064F8002000F073F800F06CF868783C -:10696000400735D1022000F059F85C484FF00A0882 -:10697000B0F9001091FBF8F000B200F061F80220CD -:10698000FBF76FF8E0B100F065F855486E2100782C -:1069900048431521B0FBF1F63A2000E03CE000F05E -:1069A0003DF8B6FBF4F738B200F04AF83B2000F0AF -:1069B00035F804FB1760401DB0FBF8F000F040F81C -:1069C0002020FBF739F808B1FFF7D9FE00F033F8C3 -:1069D0006878282820D10020687001F080FB4FF4EF -:1069E0007A71B0FBF1F43C25B4FBF5F6B6FBF5F09B -:1069F00005FB1067172000F011F8380200B200F014 -:106A00001FF8182000F00AF805FB164000F018F8EF -:106A1000BDE8F04700F00FB8BDE8F08770B5234C33 -:106A200005465E21A06802F043FF2946A068BDE844 -:106A3000704002F03DBF1D485E21806802F038BF03 -:106A400010B50446C0B2FFF77FFEC4F30720BDE8CF -:106A5000104079E670B52248224E40F634020078A4 -:106A60003178184DB0FBF1F050432A22B0FBF2F020 -:106A70006A88B2FBF1F301FB13214FF6FF7202EAC1 -:106A8000011141EA0024C0F3032004430620FFF76C -:106A9000C5FF20B2FFF7D4FF68883178401C80B270 -:106AA000B0FBF1F201FB1200688070BDE00800202D -:106AB0004C010020A086010070040020FC1400207E -:106AC0008C0A002058030020820100208000002052 -:106AD00000007A4420000020B0010020E8000020DF -:106AE000D200002068010020884201DA0846704781 -:106AF0009042FCDD104670472DE9FE4F97499748BC -:106B0000E831B0F9E600B1F90050B1F9024010B92E -:106B10000DB9002C7ED0924A0021117004F0D8F8F3 -:106B2000904F394604F052F8DFF83C82414604F0B9 -:106B300083F80646284604F0CBF8394604F046F8B8 -:106B4000414604F079F80546204604F0C1F839467C -:106B500004F03CF8414604F06FF80746304604F074 -:106B6000FFFE0290304605F0E1FA0190284604F05D -:106B7000F7FE0646284605F0D9FA0546384604F0E1 -:106B8000EFFE0446384605F0D1FA009020460299FF -:106B900004F01CF881463146204604F017F8804680 -:106BA0000299009804F012F883462146019804F0F7 -:106BB0000DF88246DDE9001004F008F86B4C07463A -:106BC00086F00040C4F80080009903F0FFFFC4E99C -:106BD00001052946504603F0F9FF594603F09EFF90 -:106BE000E0602946384603F0F1FF494603F0EBFF29 -:106BF00020610198314680F0004003F0E7FF6061BA -:106C00002946484603F0E2FF394603F0DCFF2946F7 -:106C1000A06100E00BE0584603F0D8FF514603F0B6 -:106C20007DFFE0613046029903F0D0FF2062BDE8AD -:106C3000FE8F2DE9F0470546B0F90080B0F90260FB -:106C4000B0F9040004F044F8484C8246A16903F00E -:106C5000BDFF0746304604F03BF88146E16803F08B -:106C6000B5FF0646404604F033F88046216803F03D -:106C7000ADFF314603F052FF394603F04FFF04F0F9 -:106C80002FFF28805046E16903F0A0FF07464846E1 -:106C9000216903F09BFF06464046616803F096FFBA -:106CA000314603F03BFF394603F038FF04F018FF8C -:106CB00068805046216A03F089FF074648466169AB -:106CC00003F084FF06464046A16803F07FFF31468B -:106CD00003F024FF394603F021FF04F001FFA880F0 -:106CE000BDE8F087092A11D2DFE802F01005091685 -:106CF0001C21262A2E0002880A80428803E042884E -:106D00000A8002880CE04A808088888014480078D5 -:106D1000002822D108468CE7028852420A80428825 -:106D20005242F0E7428852420A800288EBE702882A -:106D300052420A8042880CE042880A80028808E0B9 -:106D400002880A80428803E0428852420A80028810 -:106D500052424A8080884042D7E770477004002042 -:106D600060030020DB0F494000003443D00E0020B8 -:106D700044490844444990F80A0151F820004FF46E -:106D8000777101EB500080B2704710B5044601F0F6 -:106D90008CF93E4902464868131A0020B3F57A6F11 -:106DA00000D948704A604A780AB90F2C0AD1087095 -:106DB00032B1354B20331344182A03F8014C02D06A -:106DC000521C4A7010BD304A2032D27D0AB90122CD -:106DD0000A70487010BD10B504462A4800212A4B9D -:106DE000B0F814014200A2F5F76200BF43F8212079 -:106DF000491C0829FADB0123254A2649264801F0C7 -:106E0000FDFA01462548C1600CB1254921600821E1 -:106E1000417410BD1D4B10B5187840B11A484FF0A1 -:106E200000022030817DC908C90702D01A700020F5 -:106E300010BD1C49401C0A8030F8011CC1F30A0433 -:106E400011490C600488C4F3CA044C600468C4F39C -:106E50008A348C60B0F80340C4F34A04CC60848860 -:106E6000C4F30A140C614468C4F3CA344C61B0F82A -:106E70000740C4F38A048C6100894009C8611A7014 -:106E8000012010BD70040020F40E002064030020D7 -:106E9000A08601008B6D000800440040E00800203F -:106EA000716D0008D60000202DE9F04106460078FB -:106EB00090B008B1012500E00025DFF8D8804046F9 -:106EC00002F0D0FE3448009000243448CDE901049B -:106ED000012725B10220CDE90304802002E0CDE99D -:106EE0000374002005904FF4807006908000079096 -:106EF000202008900002CDE909046946404602F0CE -:106F00001EFF0121404602F044FF8DF830500B94E3 -:106F10008DF831704FF46020CDE90D040DB10220E1 -:106F200000E001201C4C8DF83C004C3C0BA9204695 -:106F300002F004FE032301220421204602F053FE46 -:106F40002DB1317803230222204602F04CFE0121AC -:106F5000204602F01CFE0121204602F00EFE2046D3 -:106F600002F01FFE204602F021FE0028FAD1204642 -:106F700002F023FE204602F025FE0028FAD101216E -:106F8000204602F026FE10B0BDE8F081034931F83A -:106F900010007047080002404C2401406C030020A0 -:106FA0002DE9FF47DFF86C81814698F80000D0B3E7 -:106FB00000273E463D463C46641CE4B202AB082234 -:106FC0003221532000F063FD9DF808009DF8091060 -:106FD000202C00EB012000B207449DF80A009DF828 -:106FE0000B1000EB012000B206449DF80C009DF848 -:106FF0000D1000EB012000B205449DF80F0000F0D9 -:107000007F0001D20028D7D197FBF4F0ADF8000043 -:1070100096FBF4F0ADF8020095FBF4F0ADF8040037 -:1070200088F802401EE0FFE702AB0622322153201F -:1070300000F02DFD9DF808009DF8091000EB0120DF -:10704000ADF800009DF80A009DF80B1000EB012040 -:10705000ADF802009DF80C009DF80D1000EB01202A -:10706000ADF8040098F8012049466846FFF73AFE5B -:10707000BDE8FF8770B5274D04464FF00802287819 -:107080004FF02D0100284FF053000ED000F0F9FC16 -:107090000A223121532000F0F4FC0C222C21532031 -:1070A00000F0EFFC9022382108E000F0EAFC0A2210 -:1070B0003121532000F0E5FC0A222C21532000F05E -:1070C000E0FC154940F20910002C088000D06C70DB -:1070D00070BD38B5054600208DF800000F480C46FD -:1070E0000F49006888420AD06B46012200215320D4 -:1070F00000F0CDFC18B19DF80000E52801D000207B -:1071000038BD044928780870064820600648606049 -:10711000012038BD70030020820100200C040020F3 -:10712000001BB70075700008A16F000810B54FF480 -:107130008044204602F08AFE012805D1204602F054 -:1071400093FEB9490120087010BD70B50D46B649CF -:10715000B64A064688885389B2F91440C01A138982 -:107160005843B2F91230C013DB02044493FBF4F32A -:107170001844D06100EB8000082202EB40000411AB -:10718000886800F0D0F806B13060002D00D02C6087 -:1071900070BD38B5A44C207810B96088401C608060 -:1071A0006B460322F621772000F071FC9DF8000069 -:1071B0009DF80110000440EA01209DF802100843E8 -:1071C0009A49B1F92010C1F10801C840A06038BD4A -:1071D0009648342190F8200001EB80109249C2B209 -:1071E00000200870F421772000F04BBC38B58E4C9D -:1071F000207810B96088401C60806B460222F6211E -:10720000772000F044FCBDF8000040BAA08038BDF3 -:10721000854900202E220870F421772000F031BC2F -:107220002DE9F04304468248824985B000688842CF -:1072300003D1002005B0BDE8F083DFF8EC9199F8A8 -:10724000010008B10120F5E74FF40055ADF80C50EE -:1072500002208DF80F001020774E8DF80E0003A944 -:10726000304601F039FF6F00ADF80C7004208DF846 -:107270000E0003A9304601F02FFF35610E210220D8 -:1072800001F060FF00208DF8080008208DF809004B -:107290004FF00108019747468DF80A8001A802F0D7 -:1072A0009FFD28208DF810000F208DF811008DF81B -:1072B00012008DF8137004A802F00DFC142000F0E9 -:1072C0001DFF6B460122D021772000F0E0FB574FD5 -:1072D0009DF800000321F8753984552801D07561A7 -:1072E000A7E76B460122D121772000F0D0FB9DF863 -:1072F000000000F00F0139760009787600F05CF8A4 -:1073000089F8018041F27070208046F67810608024 -:107310004A4860604A48A0604A48E0604A482061A4 -:107320004A4860618EE770B54049CA69B1F90E40BC -:10733000A2F57A6202FB02F31D136C43E512B1F968 -:107340000240B1F90460544305EBE424B1F9005064 -:1073500004EB850591F82040A54056437213B1F91E -:107360000C601B135E4302EB2642921C9210C988EC -:1073700002F50042AD1C5143C90B4CF25032A0EB58 -:10738000A500E2405043B0F1004F03D24000B0FBF3 -:10739000F1F002E0B0FBF1F040000112494340F689 -:1073A000DE3251432A4A0914424301EB224101F6DD -:1073B000CF6100EB211070BD00B587B06B4616227F -:1073C000AA21772000F063FBBDF8000041BA1748FE -:1073D0000180BDF8021049BA4180BDF8041049BAD5 -:1073E0008180BDF8061049BAC180BDF8081049BABD -:1073F0000181BDF80A1049BA4181BDF80C1049BAA3 -:107400008181BDF80E1049BAC181BDF8101049BA8A -:107410000182BDF8121049BA4182BDF8141049BA70 -:10742000818207B000BD000074030020300F0020EF -:107430000C040020001BB70000100140117200086E -:10744000ED710008D1710008937100084B710008BC -:1074500043E3FFFF38B5044600208DF800006B467B -:1074600001220A211E2000F012FB18B19DF8000035 -:10747000482801D0002038BD0CB18D48047001208F -:1074800038BD7FB5054602AB062203211E2000F061 -:10749000FEFABDF8080040BA00B203F019FC844CB3 -:1074A000241D216803F092FB03F020FCADF80000DE -:1074B000BDF80A0040BA00B203F00AFCA16803F06C -:1074C00085FB03F013FCADF80400BDF80C0040BAD6 -:1074D00000B203F0FDFB616803F078FB03F006FCEB -:1074E000ADF80200201F294602786846FFF7FAFB34 -:1074F0007FBD2DE9F0476F4800246F49006825469D -:107500008EB02E464FF0010888420CD14FF48050C7 -:10751000ADF8280002208DF82B0004208DF82A00F9 -:107520000AA9664808E06649884207D14FF48040BE -:10753000ADF828000AA9634801F0CEFD322000F022 -:10754000DDFD112200211E2000F09BFA60220121A6 -:107550001E2000F096FA642000F0D0FD6846FFF788 -:1075600090FFDFF858A1DFF8609100270AF10C0ABC -:10757000012202211E2000F084FA322000F0BEFD1C -:107580006846FFF77EFFBDF90210BDF90400BDF9A2 -:1075900000200D4414440644814201DA0B4600E009 -:1075A0000346934201DD104602E0814200DA0846BC -:1075B000484502DC4FF0000808E0DAF8001081F0DE -:1075C0001001CAF800107F1C0A2FD1DB1222002103 -:1075D0001E2000F056FA0027012202211E2000F092 -:1075E00050FA322000F08AFD6846FFF74AFFBDF9E5 -:1075F0000020BDF90210BDF90400A41A6D1A361A54 -:10760000814201DA0B4600E00346934201DD104659 -:1076100002E0814200DA0846484502DC4FF00008EB -:1076200008E0DAF8001081F01001CAF800107F1CA1 -:107630000A2FD1DB204603F04BFB244F014638468E -:1076400003F0FAFA1A4C20F00040241D206028466E -:1076500003F03EFB0146384603F0EEFA20F000400E -:107660006060304603F034FB0146194803F0E4FA49 -:1076700020F00040A060702200211E2000F001FADE -:10768000202201211E2000F0FCF9002202211E20F0 -:1076900000F0F7F9642000F031FDB8F1000F04D1DB -:1076A0004FF07E5020606060A0600EB0BDE8F087B3 -:1076B000800300200C04002000127A00000C01401E -:1076C000001BB7000010014000F0FFFF00406F46B4 -:1076D00001C05E4630B587B005464FF44060ADF856 -:1076E000140002208DF817001C208DF8160005A943 -:1076F000FB4801F0F1FCFB4CE56000F007FAE068A4 -:1077000002F0B8FB684602F020FC00224FF4407102 -:10771000E06802F050FC0025ADF804504BF6FF7015 -:10772000ADF806004FF48040ADF80C00EE48009034 -:107730000121E06802F017FC6946E06802F0ADFB49 -:107740004FF4A06002F0C2F922208DF810008DF8ED -:1077500011508DF8125001208DF8130004A802F08A -:10776000BAF921208DF810008DF8115004A802F00C -:10777000B2F907B030BD38B5DA4CE068818A0091C3 -:1077800011F4706F01D001212170009911F4E06FA4 -:1077900025D0018B00224FF4806102F00CFC009890 -:1077A00080051CD4E0680188890518D40188C905C2 -:1077B0000CD50188C905FCD4012102F0E8FBE06882 -:1077C00001888905FCD4FFF785FF08E0012102F05C -:1077D000DEFB00224FF44071E06802F0ECFBE06851 -:1077E000818A21F4706181820020207138BDC2E756 -:1077F0002DE9F041BB4CE068818A4FF00105C9B228 -:10780000CA074FF0000627D0018821F400610180EB -:10781000012102F0C6FBE670607A20B1607860B9A1 -:10782000A079FF2809D061790022E06802F0D0FB3E -:10783000A079FF2848D0FF20C9E06570E0790228D0 -:1078400004D1E068018841F400610180617901227E -:10785000E06802F0BDFB37E08A074FF4806745D54A -:10786000BFF3508FE079012810D1607A70B1607851 -:1078700060B10021E06802F094FBBFF3508FE06834 -:10788000018B012102F083FBA57018E0E068008BFA -:10789000BFF3508FE079022808D1607A30B1607868 -:1078A00020B10021E06802F07CFB06E0E0790328CB -:1078B00005D1607A18B1607808B1002200E0012299 -:1078C0003946E06802F077FB94F90310E079401C38 -:1078D000814209D16670A07828B100224FF440712E -:1078E000E06802F068FB2671BDE8F0814A0753D5D5 -:1078F000A570627A7B494978CAB3C9B3E179022994 -:107900001FD9002102F04DFBE06802F05EFB94F904 -:10791000031062695054491CE1700121E06802F0D3 -:1079200036FBA570E06802F050FB94F90310626921 -:107930005054491CE17001223946E06802F03BFBDB -:1079400025E0012102F023FBE06802F03EFB94F900 -:10795000031062695054491CE170E06802F035FB85 -:1079600094F9031062695054891CE1700FE000E043 -:1079700000E009B9217A31B1012102F008FBE07879 -:10798000401CE07003E0012102F0F7FA6570E06846 -:107990000188C905FCD497E74A061AD502F015FB01 -:1079A00094F9031062695054491C48B2E070E179BF -:1079B000C01C814204D100223946E06802F0FBFA83 -:1079C000E17994F903008142E5D100F10100E07012 -:1079D0007AE70906DFD594F903104B1C5AB20BD095 -:1079E0002369595CE27002F0EEFAE07994F9031031 -:1079F00088423FF45AAF67E7E270A17902F0E3FAF8 -:107A0000607A00287FF451AFE0790028F1D05BE77D -:107A1000EEE6B0E6ECE670B5324C4FEA400047F2D5 -:107A200030556071A17101202072002161722361C3 -:107A30006361E27120712170E068818889050ED44C -:107A40000188C90505D401888905FCD4012102F00B -:107A500094FA01224FF44071E06802F0ACFA207908 -:107A600010B16D1EFBD104E01DB1207880F0010043 -:107A700070BD6089401C6081E068FFF72BFE00202C -:107A800070BD07B502AB0122FFF7C5FF0EBD70B593 -:107A9000144C4FEA400047F230556071A17100204C -:107AA00020720121617263612361E2712171207092 -:107AB000E068818889050ED40188C90505D401884C -:107AC0008905FCD4012102F058FA01224FF44071DB -:107AD000E06802F070FA207940B16D1EFBD10AE037 -:107AE000000C014090030020801A06001DB1207890 -:107AF00080F0010070BD6089401C6081E068FFF784 -:107B0000E9FD002070BD2A48408970472DE9F84FF3 -:107B10004FF44067ADF800704FF0020A8DF803A0F3 -:107B20001420DFF890B08DF802006946584601F045 -:107B3000D3FA204D10352F60DFF8789000262C15F1 -:107B400005F1040809F1080902E00A2000F0CAFA68 -:107B5000D9F800004005F8D5C8F800400A2000F028 -:107B6000C1FA2C600A2000F0BDFA761CF6B2082E8D -:107B7000EED34FF400694646C8F800900A2000F0A2 -:107B8000B1FA34600A2000F0ADFA2C600A2000F04F -:107B9000A9FAC5F80090ADF800708DF803A01C207C -:107BA0008DF802006946584601F096FABDE8F88F54 -:107BB00090030020000C014038B504466B460222B9 -:107BC0001B216820FFF763FFBDF8000043F29031EE -:107BD00040BA08444FF48C71B0FBF1F023302080A0 -:107BE00038BD1FB5044602AB06221D216820FFF7F1 -:107BF0004EFFBDF80800214640BA02B2D01702EB92 -:107C000090708010ADF80000BDF80A0040BA02B2D2 -:107C1000D01702EB90708010ADF80200BDF80C0098 -:107C200040BA02B2D01702EB90708010ADF8040099 -:107C30002F4842786846FFF755F81FBD70B50446D7 -:107C4000192000F05BFA002215216820FFF719FFC8 -:107C500010B9032000F0FCFA254D1621287840F0D9 -:107C600018026820FFF70DFF002217216820FFF798 -:107C700008FF01223D216820FFF703FF01223E217A -:107C80006820FFF7FEFE002C00D06C7070BD70B550 -:107C900004460D46192000F031FA00221521682013 -:107CA000FFF7EFFE00281CD01248206012486060E9 -:107CB0001248A0601248E0600D48622D12D004DC2A -:107CC0000A2D13D0142D05D10EE0BC2D06D0B5F52C -:107CD000807F01D0032102E0002100E0012101703A -:107CE000012070BD0221FAE70421F8E70521F6E73B -:107CF000A80300203D7C0008E37B0008B97B000856 -:107D000018449231FEB5064614460D46684602F008 -:107D100039FC0120ADF804000021ADF80050ADF8A9 -:107D20000610ADF80810ADF802406946304602F082 -:107D300079FBFEBD70B51646D04A02EB0015D04A5D -:107D400002EB00140122206801F003FBD4E90101D9 -:107D5000182200F087F9217B3246206800F03FF9B5 -:107D6000A07B18B10121206802F01EFC01212068CF -:107D700002F010FC207B30B1042807D008280AD07C -:107D80000C2806D10AE02068343001E02068383041 -:107D90002860284670BD20683C30F9E720684030F4 -:107DA000F6E72DE9F0410546B4480F4600EB05160D -:107DB000B348B27100EB05142822D4E9010100F0A8 -:107DC00051F9217B00222068FFF79CFF01224FF62A -:107DD000FF71204601F0DAFA3A462946204601F0C2 -:107DE0009BFA3046BDE8F08170B5A64800240289B0 -:107DF00042810181891A8BB240F68C218B4201D9D4 -:107E0000C47070BD9F49A3F2EF2540F2DB569E4A35 -:107E1000C978B5421BD2082919D2984DE0350429FA -:107E200025F8113007D2C588AB4204D90123057962 -:107E30008B402B43037103790F2B08D10471B2F9E6 -:107E40000030142B02DD143B138000E01480491C29 -:107E5000C170148070BD70B5884A894B02EB001266 -:107E600003EB0013D47918681B7B8CB15181148902 -:107E7000824D091B91819479E03525F81410002476 -:107E8000D47122461946FFF73DFF7F48048070BD3C -:107E900011810121D171BDE870400222194631E7FC -:107EA0002DE9F0470446774DE1890020E980A1796A -:107EB00001B10220617801B1401C7449DFF8D08122 -:107EC000002651F820704FF47A79BA5D02F00F0065 -:107ED00002F0F001FF2A65D0A2781AB102285ED024 -:107EE00003285CD0E2783AB1042858D0052856D04F -:107EF000062854D0072852D0E2790AB182424ED0E7 -:107F000011F0300F02D0227802B90021227932B16B -:107F1000A27922B9082801D0092800D180216279EC -:107F20002AB1A2791AB9021F032A00D88021CA06F1 -:107F300005D500225749FFF734FF082008E08A06DC -:107F400008D5AA785449FFF72CFFA87800F1010062 -:107F5000A87024E04A0612D52289B8FBF2F1A28962 -:107F600089B202B94A46FFF7E5FE0146434A28783E -:107F7000F03242F8201000F1010028700FE00906ED -:107F80000DD56289B8FBF2F189B24A46FFF7D2FEFD -:107F90000146424A687842F82010401C6870761CFE -:107FA0000E2E92DB0020BDE8F087364A1278904210 -:107FB00005D23A4A303A52F82000006801807047F2 -:107FC000304A5278904204D2344A52F82000006875 -:107FD000018070473149403931F8100070477FB552 -:107FE000064615460C46684602F0C2FA7020ADF807 -:107FF00000000120ADF802000020ADF804000220CE -:10800000ADF80800C001ADF80650ADF80C0074B131 -:10801000042C15D0082C1CD00C2C07D169463046F6 -:1080200002F04CF90821304602F0E7FA7FBD6946BC -:10803000304602F098F80821304602F0C8FA7FBDB9 -:108040006946304602F0C4F80821304602F0C5FA0D -:108050007FBD6946304602F0F7F80821304602F04D -:10806000C6FA7FBD08B5ADF800108DF802200221D8 -:108070008DF80310694601F02FF808BD540F002059 -:10808000C8D20008AA030020D60000208CD2000825 -:1080900040420F00E97D0008577E00087410002060 -:1080A00080484168491C4160704710B57D484FF0D9 -:1080B000E02341689A694468A142FAD103680068E4 -:1080C00003EB4304C4EBC313C2EBC302B2FBF0F0F7 -:1080D00001EB4102C2EBC11100EBC10010BD7148C0 -:1080E0004068704730B50546FFF7DFFF4FEA0004F0 -:1080F000FFF7DBFF001BA842FAD330BD30B50446C2 -:108100004FF47A7502E02846FFF7ECFF641EFAD2BE -:1081100030BD6449896808474FF4805108B162480E -:1081200001E06148001F016070474FF4805110B1B9 -:108130005D48001F00E05C48016070472DE9F04F8A -:108140008DB018225949684602F041FC032701F01E -:1081500016FC0121564801F0A1FF012144F61D2023 -:1081600001F093FF0121084601F086FF01F0B1FF05 -:108170004FF6FF70ADF818004B484FF0000A8DF82D -:108180001AA006A9143800F0A7FF06A9494800F074 -:10819000A3FF06A9484800F09FFF4848416841F006 -:1081A00000714160464DDFF81C813E4E2968414513 -:1081B00001D1454800E04548B0600020FFF7A9FF25 -:1081C0003C4908201031086010200860A9460024AE -:1081D00083466D46D9F80010414506D105EBC40031 -:1081E0008179142901D180F806B005EBC401091D7D -:1081F00055F8340000F070FF641CBC42EAD307A8B5 -:1082000001F0F4FE32490798B0FBF1F030603148DC -:108210004FF47A710068B0FBF1F0B0F1807F0CD2BE -:1082200020F07F414FF0E020491E41612A4AF021B1 -:108230001170C0F818A0072101612848FFF74AFA19 -:1082400000F0C9FF6420FFF759FF0DB0BDE8F08FC3 -:10825000184A1021143211600821121F11600446BF -:10826000151F40F2DB104443286880F0100028609E -:10827000286880F008002860A01EFFF73FFF01205B -:10828000FFF747FF1920FFF739FF0020FFF741FFF5 -:10829000EAE710B11349124808600F49124817392C -:1082A00008607047B8030020140801409CD2000801 -:1082B00007004000000C0140001001400000014098 -:1082C0000C040020001BB7002B8100081981000856 -:1082D00040420F000804002023ED00E00058004059 -:1082E000EFBEADDEF04F00200400FA057CB5FA4C7D -:1082F0000D46FA492160A060A4F53070606100F578 -:108300008070A0614FF48070E0602061F4482063C9 -:10831000F348012114386063880301F0B6FE02209F -:108320008DF803000002ADF8000018208DF802005F -:10833000EC4EA80703D56946304600F0CDFE4FF459 -:108340008060ADF8000048208DF80200E80703D0F7 -:108350006946304600F0C0FE0E208DF80400012072 -:108360008DF805008DF806008DF8070001A801F0D2 -:10837000B2FB20467CBD2DE9FC41D74C0D464C3468 -:10838000D6492160A0608020E06040202061A4F5F3 -:10839000867060618030A061D3480121A0644804E8 -:1083A00001F07CFE02268DF803600420ADF8000089 -:1083B00018208DF80200CB4FA80703D56946384630 -:1083C00000F08AFE0820ADF8000048208DF8020079 -:1083D000E80703D06946384600F07EFE26208DF877 -:1083E000040001208DF805008DF806608DF8070067 -:1083F00001A801F070FB2046BDE8FC812DE9F043A7 -:1084000089460646B9490024B7488FB01D4617462D -:108410008E4204D119461046FFF768FF05E08642F8 -:1084200004D119461046FFF7A6FF04464FF0000896 -:10843000C4F82080C4F81C80C4F82880C4F82C90AC -:10844000C4F82480A6642571A760ADF83080ADF82B -:1084500034800B97ADF83280ADF83880ADF83680B7 -:10846000E80702D00420ADF83600A80705D5BDF80E -:10847000360040F00800ADF836000BA9304602F097 -:10848000E3F80121304602F037F9684601F074FC48 -:10849000301D00904FF48050CDE909088020CDF8C0 -:1084A0001080CDE905084746CDF81C80E80723D0A9 -:1084B000206BD8B1E068CDE9027020200890606997 -:1084C0000190206B01F0CEFB6946206B01F037FC78 -:1084D0000121206B01F05DFC01224021304602F0B9 -:1084E0002DF9206B01F06AFC206405E0012240F2C6 -:1084F0002551304602F00AF9A80724D5606BE0B197 -:1085000020690390102008970290606B01F0AAFB8D -:108510006946606B01F013FC01220221606B01F0DF -:1085200043FC0021606B01F047FC606B4760012257 -:108530008021304602F002F905E0012240F2277165 -:10854000304602F0E3F80FB02046BDE8F0837FB577 -:1085500004460020ADF80400ADF808000091ADF825 -:108560000600ADF80C00ADF80A0020790D46C007F2 -:1085700002D00420ADF80A002079800705D5BDF8A7 -:108580000A0040F00800ADF80A006946A06C02F04D -:108590005BF8A5607FBD826A81691144426BD1603E -:1085A000D0E9092100238A4205D9511A426B516052 -:1085B000416A816204E00269511A426B5160836230 -:1085C00080F84430406B012101F0E3BB016B11B135 -:1085D0004968006C01E01C3003C8814201D00120D1 -:1085E000704700207047416B11B190F8440070470C -:1085F000243003C8814201D1012070470020704718 -:1086000010B50146036BC268406943B10B6CD21AC6 -:10861000805C5B1E0B6401D1CA680A6410BD0B6AE2 -:10862000C05C5B1CB3FBF2F402FB14320A6210BDA7 -:10863000436A8269D154416A0269491CB1FBF2F371 -:1086400002FB13114162416B19B10968C90706D1D8 -:10865000A1E7806C012240F2277102F057B8704701 -:1086600010B51D4C4FF4005001F0ABFB0021606BC6 -:1086700001F08FFBD4E90901884203D02046BDE810 -:10868000104088E7012084F8440010BD1249886C2E -:10869000028812060ED5D1E909329A420BD08B69B5 -:1086A0009A5C8280886A0A69401CB0FBF2F302FB84 -:1086B000130088627047002240F2277102F026B84A -:1086C00070B5054C4C34A06C0588A9061CD5808873 -:1086D000E16A69B1884717E054130020B4D200085A -:1086E00058000240000801400044004000380140AA -:1086F000E26961698854E069E16800F10100B0FB5A -:10870000F1F201FB1200E06128060FD5D4E909104F -:1087100088420CD0A169085CA16C8880A06A21699C -:10872000401CB0FBF1F201FB1200A06270BDA06C16 -:10873000BDE87040002240F2277101F0E7BF000061 -:10874000FEB52C4C0125207878B1012823D00228D1 -:1087500020D164208DF8000027488DF801500026B4 -:108760004078E0B38DF802503CE07A208DF80000AC -:1087700022486B460222B0F90000FF21C0F1B4008C -:1087800000EBD070C0F347008DF801006D20FFF7BB -:1087900042F92570FEBD1A4E79208DF80000B6F919 -:1087A00000000A2590FBF5F05A30B4220021FEF7B4 -:1087B0009BF98DF80100B6F90200B42290FBF5F0A8 -:1087C0005A300021FEF790F98DF802006B46032223 -:1087D000FF216D20FFF71FF902202070FEBDFFE78B -:1087E0008DF802606B460322FF216D20FFF713F91D -:1087F0002670F3E7C40300208C0A0020B00100209B -:10880000340000201FB5044602AB06224321682035 -:10881000FFF73DF9BDF80800214640BA02B2D01773 -:1088200002EB90708010ADF80000BDF80A0040BA6D -:1088300002B2D01702EB90708010ADF80200BDF8C4 -:108840000C0040BA02B2D01702EB90708010ADF865 -:1088500004007C4842786846FEF744FA1FBD38B5EC -:1088600004464FF40050ADF8000002208DF80300DC -:1088700004208DF80200744874490068884202D1CF -:108880006946734804E07349884203D169467248D7 -:1088900000F022FC80226B216820FFF7F2F805200F -:1088A000FFF72CFC002219216820FFF7EAF80322C9 -:1088B0006B216820FFF7E5F8022237216820FFF7D7 -:1088C000E0F8604D1A2168202A78FFF7DAF81822BC -:1088D0001B216820FFF7D5F810221C216820FFF724 -:1088E000D0F8002C00D06C7038BD1FB5044602AB28 -:1088F00006223B216820FFF7CAF8BDF80800214690 -:1089000040BAADF80000BDF80A0040BAADF8020068 -:10891000BDF80C0040BAADF804004A4882786846B9 -:10892000FEF7E0F91FBD47494C4ACB7813B14FF42D -:10893000FF6301E04FF480531380002800D088705B -:1089400070472DE9FE4F8146984692460D462320FA -:10895000FFF7D4FB6B46012275216820FFF797F8DB -:10896000002804D09DF80000682802D00020BDE84F -:10897000FE8F062201AB11466820FFF788F89DF8AC -:1089800009009DF80710C007400F01F0010140EAFF -:1089900041009DF805102B4C01F0010108434FF0F8 -:1089A00001064FF0000704D0012833D002280DD073 -:1089B0002CE06B4601220C216820FFF768F89DF837 -:1089C000000010F00F0021D0042823D0E7702449C4 -:1089D000C9F8001023492448C9F804102860234826 -:1089E00068602348E860B8F1000F02D0E17888F8A9 -:1089F00000105046BAF1620F19D00DDC05281ED0C8 -:108A00000A281AD0BAF1140F0BD114E00520FFF791 -:108A10001FFCDCE7E670DAE7BC2806D0BAF5807FF9 -:108A200001D0032004E0277003E0267001E002205B -:108A3000207001209BE70420FAE70520F8E70620D4 -:108A4000F6E70000C50300200C04002000127A00A5 -:108A5000000C0140001BB700001001408201002003 -:108A600027890008EB8800085F880008058800084F -:108A7000194492311FB5044602AB062201211C2085 -:108A8000FFF705F8BDF80800214640BA40F38D0213 -:108A9000D01702EB90708010ADF80000BDF80A000E -:108AA00040BA40F38D02D01702EB90708010ADF801 -:108AB0000200BDF80C0040BA40F38D02D01702EB63 -:108AC00090708010ADF80400334802786846FEF7D5 -:108AD00009F91FBD38B504462020ADF8000002207A -:108AE0008DF8030004208DF8020069462B4800F041 -:108AF000F3FA00222A211C20FEF7C3FF02220E21D6 -:108B00001C20FEF7BEFF03220F211C20FEF7B9FF39 -:108B100012222B211C20FEF7B4FF02222C211C2044 -:108B2000FEF7AFFF01222D211C20FEF7AAFF002235 -:108B30002E211C20FEF7A5FF05222A211C20FEF76E -:108B4000A0FF17494FF48070002C088001D0124814 -:108B5000047038BD38B5044600208DF80000114877 -:108B60001149006888420CD06B4601220D211C205F -:108B7000FEF78DFF28B19DF800002A2803D01A289F -:108B800001D0002038BD09492160094961600249CE -:108B90004870012038BD0000C903002000080140D2 -:108BA000820100200C040020001BB700D58A0008B9 -:108BB000758A0008434810B50068434CA1880842F4 -:108BC00003D0FFF772FAA0600AE0FFF76EFAA1681F -:108BD000884205D9401A3B2190FBF1F06169086099 -:108BE000E068BDE8104001F03FB9E3E7E2E7FEB519 -:108BF0000125354C022110B1012810D109E04FF4B4 -:108C0000807060804000A080E06009202070172004 -:108C100004E06580A180E1602570072060706088B5 -:108C2000ADF800001026274F8DF802608DF8031074 -:108C3000083F6946384600F04FFAA088ADF80000BA -:108C400004208DF802006946384600F045FA217884 -:108C5000012000F077FAE06801F006F9E068019081 -:108C600000208DF808008DF809608DF80A5001A8E1 -:108C700001F0B6F894F9010000F01F018D404009A1 -:108C80004FF0E02101EB8000C0F80051FFF727FA18 -:108C90003C382061FEBD70B50546FFF720FA0A4C4E -:108CA00021693C3188420CD3C4E904050549608838 -:108CB000083108600B20FFF715FA024960880C3173 -:108CC000086070BD080C0140CC0300201FB50446AD -:108CD00002AB0622A8216820FEF7D9FEBDF80800E5 -:108CE000214640BA02B2D01702EB90708010ADF866 -:108CF0000000BDF80A0040BA02B2D01702EB907033 -:108D00008010ADF80200BDF80C0040BA02B2D017D6 -:108D100002EB90708010ADF8040026484278684657 -:108D2000FDF7E0FF1FBD70B504466420FFF7E6F9CC -:108D3000F02223216820FEF7A4FE10B90320FFF7DC -:108D400087FA0520FFF7DAF91A4D2021287840F03C -:108D50000F026820FEF795FE002C00D06C7070BDED -:108D600038B504460D461920FFF7C8F96B460122B5 -:108D70000F216820FEF78BFE9DF80000D32801D05C -:108D8000002038BD0C4820600C4860600C48E06052 -:108D90000848362D05D04E2D07D05D2D07D0002177 -:108DA00000E040210170012038BD8021FAE7C02198 -:108DB000F8E70000E4030020278D0008CD8C0008B0 -:108DC000DDE9A7312DE9F04FB74C83468E46608927 -:108DD00026890102B5484FF0000A4068421AA6FBF6 -:108DE000027CA0884FEAE2754FEA10414FEA004347 -:108DF0000AFB02C006FB05064FEAD71040EA4660B0 -:108E000013EB000941EBE611E6886388A6FB02C874 -:108E10004FEA53404FEAC3370AFB028306FB05368D -:108E20004FEA1C2343EA0663FB1840EB2620A68981 -:108E3000A6FB027C0AFB02C206FB05244FEAD752BE -:108E400042EA44224FF4FA654FEAE454521944F1DD -:108E50000004A246551B74F1000448DA944D5519DC -:108E6000A5FB05674AF1FF3404FB057705FB047C8D -:108E70000525A6FB05480CFB0585002706FB0755C5 -:108E80006F104FEA340CB9EB0C0961EB0701A40831 -:108E900044EA85741B1B60EBA500864D551B7AF1D7 -:108EA000FF3424DA40F2DC555619A6FB06474AF196 -:108EB000000505FB067706FB05750726A4FB06C81B -:108EC00005FB0686002704FB0767B9EB0C0961EB7D -:108ED00007010B27A4FB07C805FB0785002604FB39 -:108EE000065464104FEA3C055B1B60EB04006F4CBA -:108EF000A5680024A5FB036704FB037305FB003092 -:108F0000740D44EAC0244015B4EB090360EB010082 -:108F1000410441EAD330BBF1000F01D0CBF800008F -:108F2000BEF1000F01D0CEF80020BDE8F08F10B5E3 -:108F300000F072F85D49886010BD5C48012200783D -:108F40004030C1B27720FEF79CBD10B500F064F848 -:108F50005649486010BD5548012200785030C1B2D2 -:108F60007720FEF78EBD2DE9FE4305465248534952 -:108F7000006888420FD04FF40054ADF80040022042 -:108F80008DF8030010204E4E8DF8020069463046E1 -:108F900000F0A2F874610A20FFF7B0F801AB0122DB -:108FA000A0217720FEF773FD002823D001221E2187 -:108FB0007720FEF766FD4FF42F60FFF793F800244B -:108FC000DFF8E4802646A02707EB4400C1B202ABDD -:108FD000022277200296FEF75AFDBDF8080040BA3B -:108FE00028F81400641C082CEEDB2F4800F026F84B -:108FF00010B10020BDE8FE8342F210702880688026 -:10900000304868603048A8603048E86030482861DF -:10901000304868610120EDE708B56B460322002166 -:109020007720FEF734FD9DF800009DF80110000444 -:1090300040EA01209DF80210084308BDF0B5C2893E -:10904000002102F47F4502F00F040123C5810A4686 -:1090500030F8126006B10023521C082AF8DB4FF0EA -:10906000FF36F3B90022D30722F0010302D0C35C1C -:10907000594002E0C35A81EA132108230F0401D5A5 -:1090800081F4C05149005B1E002BF7DC521C102AF2 -:10909000E9DB2543C581C1F30330844201D10020BF -:1090A000F0BD3046F0BD0000EC130020E8030020C6 -:1090B00030F8FFFF24FAFFFF0C040020001BB7006C -:1090C00000100140578F00084B8F00083B8F0008AD -:1090D0002F8F0008C58D0008F0B500234FF0010C5C -:1090E0000A880CFA03F52A4228D04FEAD30200EB93 -:1090F00082064FEA437491F802E04FEAD46734687D -:109100000EF00F025FEACE6E03D591F803E04EEA4F -:1091100002024FF00F0E0EFA07FE24EA0E04BA40C8 -:10912000224332608A78282A02D0482A03D005E0F8 -:10913000C268AA4301E0C2682A43C2605B1C102BCC -:10914000CED3F0BD10B58A0721F003040649130FF2 -:1091500021440F228C689A4094438C608A6898401E -:1091600002438A6010BD0000000001404FF48051AE -:1091700008B14E4801E04D48001F016070472DE9DD -:10918000F04104464A4817460D460088484E0C3EBA -:109190001CE015B115F8010B00E0FF20804602210C -:1091A000304601F0D9FB0028F9D04146304601F0A5 -:1091B000CFFB0121304601F0CFFB0028F9D030462B -:1091C00001F0C8FBC0B20CB104F8010B7F1EE0D265 -:1091D0000120BDE8F081F0B501218C0389B0204663 -:1091E00000F05CFF0121204600F06AFF18208DF896 -:1091F00016004FF42040ADF814002C4E03208DF8DB -:109200001700143E05A93046FFF766FFADF814407D -:1092100004208DF8160005A93046FFF75DFFA01069 -:10922000ADF8140010258DF8165005A93046FFF74B -:1092300053FF1F4E0C3E304601F040FB4FF482704E -:10924000ADF8020068010024ADF80A000720ADF86F -:109250001000ADF804400220ADF80E40ADF8060055 -:109260000127ADF80040ADF80870ADF80C50694624 -:10927000304601F047FB0121304601F05FFB0DA0B5 -:10928000006806900120FFF771FF042206A907A8D5 -:10929000FFF775FF0020FFF769FF9DF81D00EF281D -:1092A00002D0204609B0F0BD3846FBE7140C01405F -:1092B0000C3800409F0000002DE9F04180461D461B -:1092C00016460C46084600F0E7F80746404600F010 -:1092D000D8F807EB8000C0B2102805D2734901EB23 -:1092E0000010856004710673BDE8F08151B1042956 -:1092F0000BD008290CD00C290DD101225FF01001F0 -:1093000001F05DB901220221FAE701220421F7E709 -:1093100001220821F4E7704770B50D460446017B31 -:10932000134600682A46FFF7C7FF217B2068BDE887 -:109330007040DBE708B58DF8000000208DF80100D3 -:1093400001208DF802008DF80300684600F0C3FB91 -:1093500008BDFEB5064614460D46684601F0FFF806 -:1093600053486D1E44435348ADF8045069460068A5 -:10937000B0FBF4F0401EADF800000020ADF8060090 -:10938000ADF80200304600F0B5FEFEBD10B5044653 -:109390000068FFF7DEFF0121206801F0FBF8607B29 -:1093A000BDE81040C6E770B50546084600F074F801 -:1093B0000446284600F065F804EB80003B49C0B243 -:1093C00001EB001070BD70B50546022101F028F9CF -:1093D000012825D00421284601F022F901282CD0AB -:1093E0000821284601F01CF9012833D01021284615 -:1093F00001F016F901283AD11021284601F01CF994 -:109400000C212846FFF7CFFF0446284601F005F956 -:10941000A2680146002A2AD0207BBDE87040104790 -:109420000221284601F008F900212846FFF7BBFF7A -:109430000446284601F0EBF8EAE70421284601F04B -:10944000FBF804212846FFF7AEFF0446284601F04A -:10945000E0F8DDE70821284601F0EEF8082128466B -:10946000FFF7A1FF0446284601F0D5F8D0E770BD0C -:109470001148A8E74FF08040A5E71048A3E710483F -:10948000A1E7014600200F4A01E0401CC0B252F89B -:1094900020308B42F9D17047014600200A4A01E092 -:1094A000401CC0B2135C8B42FAD17047FC13002001 -:1094B00040420F0008040020002C0140000400403E -:1094C00000080040F4030020A8D30008016B4A689C -:1094D000926889680A4290F8441204D0002000295A -:1094E00000D10120704701200029FBD100207047E6 -:1094F000D0F8343101299A685B6801D021B107E0C6 -:1095000090F8440230B103E090F84402012801D001 -:109510005A6170471A6170470189406889B24822D0 -:1095200000F052B970B5044601EB4100AC49164653 -:10953000B1FBF0F081B21D4603222046FFF726FF63 -:109540002A4631462046BDE87040FFF7E5BE018956 -:10955000406889B2102200F037B900B503460320F5 -:1095600083F83C021846FFF7B1FF30B1B3F8400270 -:1095700093F839120843A3F8400293F839024000E7 -:1095800083F8390293F83E02401E10F0FF0083F882 -:109590003E0205D1012083F83802022083F83C0204 -:1095A00000BDC268016A521E914201D3002100E051 -:1095B000491C0162704710B50124034680F83C4203 -:1095C000FFF784FF01280FD1002083F8380283F8C9 -:1095D0003A4293F84002A3F840021A6A5969885443 -:1095E000BDE810401846DCE710BD00B50346FFF7A4 -:1095F0006DFF012101280BD003F23A2300201870DF -:10960000D880042098700820187103F8011C00BD50 -:1096100083F83C1200BD90F83C12491E11F0FF0186 -:1096200080F83C1208D190F83A1201B1DDE790F8C9 -:10963000381201B1BFE790E77047D0E909108142C5 -:1096400001D1012070470020704730B5044690F8E2 -:109650003B020025F8B194F83D02401E10F0FF00D7 -:1096600084F83D0216D1B4F8420200F0010140082E -:10967000A4F842022046FFF73BFF032084F83D0296 -:1096800094F83F02401E10F0FF0084F83F0201D121 -:1096900084F83B5230BD2046FFF7CFFF0028F9D1B8 -:1096A000A16AA269481CA062515C2269904200D361 -:1096B000A5624FF4007004F23B2440EA4100A4F894 -:1096C00007000A2020710120A070207030BD00EB3F -:1096D000C00101EB801010B5424901EBC0042046E7 -:1096E000FFF7B3FF2046BDE8104094E770B53D4C4E -:1096F00006463D48206003202071A66084F844128D -:109700003A4820631030C4F83401002504F13401D4 -:10971000256261614FF48070E060206104F59C7106 -:10972000C4E90615A562656284F83B52012084F8FD -:109730003A0284F8385284F83C02206BFFF7ECFEC2 -:10974000D4F83401FFF703FF01212046FFF7D0FED4 -:109750003220FEF7D3FCAFF289032A463146206B54 -:10976000BDE87040DEE6D0E90721914202D14FF01A -:109770000000704702D9A1EB020003E0C068084472 -:10978000A0EB0200C0B2704700B50346FFF7EBFF45 -:1097900000280BD05969D869095CDA68521E9042DA -:1097A00001D2401C00E00020D861084600BD436A99 -:1097B0008269D154416A0269491CB1FBF2F302FB90 -:1097C000131141627047704708B5ADF800108DF86D -:1097D000022002218DF803106946FFF77DFC08BDC9 -:1097E000C0C62D00FC140020ACD3000808D300082C -:1097F0001FB5044602AB062202211820FEF747F9E6 -:109800009DF808009DF80910800800EB0120ADF8D4 -:1098100000009DF80A009DF80B10800800EB012065 -:10982000ADF802009DF80C009DF80D10800800EBCB -:109830000120ADF804001A48214602786846FDF779 -:1098400051FA1FBD10B5044608220F211820FEF75B -:1098500018F90E2210211820FEF713F911494FF4C0 -:109860008050002C088001D00D48047010BD38B520 -:10987000044600208DF8000001466B4601221820A6 -:10988000FEF705F918B19DF80000FB2801D0002073 -:1098900038BD0548206005486060012038BD0000E3 -:1098A000040400208201002045980008F197000878 -:1098B00002681268104770B50C46054603E02A6836 -:1098C00028461268904714F8011B0029F7D170BD93 -:1098D0000168496808470168896808470268D268D2 -:1098E00010470168096908476E48016841F00101A5 -:1098F000016041686C4A1140416001686B4A114047 -:109900000160016821F480210160416821F4FE01B9 -:1099100041604FF41F0181606549C00308607047D2 -:10992000604A10B55068634B10F00C01624803D0D8 -:10993000042903D0082903D0036016E0416813E02E -:109940005168536801F470114FF0020413F4803F22 -:1099500004EB914106D053689B03436800D55B0834 -:109960004B43E9E7554B594301605168524AC1F3F3 -:1099700003110832515C0268CA40026010BD3EB457 -:10998000002100914FF4E01301914648CDE90131E7 -:109990004B4A046844F480340460846944F0100441 -:1099A00084614FF4A064056805F400350195009DBD -:1099B0006D1C0095019D15B9009DA542F3D1056868 -:1099C000AD0301D5022114E0056845F001050560ED -:1099D0000091016801F0020101910099491C009178 -:1099E000019911B90099A142F3D10168890739D5CC -:1099F0000121029133490C6844F010040C600C689A -:109A000024F003040C600C6844F002040C6041680C -:109A1000416041684160416841F480614160116882 -:109A200021F070411160244C22496160416821F4A9 -:109A30007C114160116841F0004111602049091F0B -:109A4000CA6822F40042CA608968090403D51E4925 -:109A50004FF48013616002990193012908D0022913 -:109A60000AD100E0FEE7416843F48032114302E08E -:109A7000416841F460114160016841F0807101600A -:109A800001688901FCD5416821F00301416041680A -:109A900041F0020141604168C1F381010229FAD11C -:109AA0003EBC3DE7001002400000FFF8FFFFF6FE5D -:109AB00008ED00E000127A000804002000093D00D3 -:109AC0000410014000200240001BB7001849084361 -:109AD000184908607047F0B50F21C4780278012357 -:109AE0004FF0E026DCB1134C2468457804F4E064C0 -:109AF000C4F5E064240AC4F10407E1408478BD4061 -:109B00000C402C4321010C4C1155007800F01F0132 -:109B10008B40400906EB8000C0F80031F0BD02F038 -:109B20001F008340500906EB8000C0F88031F0BD73 -:109B30000000FA050CED00E000E400E010B542681A -:109B4000464B0C791A400B6842EA042213434360E7 -:109B50008368434A1340D1E9024222434C7943EAE5 -:109B600044031A438260C26A097C22F47002491ECF -:109B7000C9B242EA0151C16210BD0029816802D018 -:109B800041F0010101E021F00101816070470029ED -:109B9000816802D041F4807101E021F4807181601C -:109BA0007047816841F008018160704701460020DC -:109BB0008968090700D501207047816841F00401D8 -:109BC00081607047014600208968490700D501205F -:109BD00070470029816802D041F4A00101E021F41E -:109BE000A0018160704770B5072409290AD9C568AA -:109BF000A1F10A0606EB4606B440A543B3401D4357 -:109C0000C56007E0056901EB4106B440A543B340D8 -:109C10001D4305611F23072A09D2446B521E02EB24 -:109C2000820293409C4391400C43446370BD0D2AD3 -:109C300009D2046BD21F02EB820293409C439140F5 -:109C40000C43046370BDC46A0D3A02EB8202934078 -:109C50009C4391400C43C46270BD0000FFFEF0FFC6 -:109C6000FDF7F1FF01684FF6FE721140016000211F -:109C7000016041608160C1605749574A083990428C -:109C800003D1486840F00F0006E0534A1432904276 -:109C900004D1486840F0F000486070474E4A2832CE -:109CA000904203D1486840F47060F5E74A4A3C327C -:109CB000904203D1486840F47040EDE7464A503284 -:109CC000904203D1486840F47020E5E7424A64328C -:109CD000904203D1486840F47000DDE73E4A783294 -:109CE000904203D1486840F07060D5E73B4A111FAD -:109CF000904203D1086840F00F0006E0374A143262 -:109D0000904204D1086840F0F00008607047334A80 -:109D10002832904203D1086840F47060F5E72F4A7A -:109D20003C32904203D1086840F47040EDE72B4A82 -:109D300050329042EAD1086840F47020E5E730B52F -:109D4000036847F6F07293430C6A8A682243D1E9AC -:109D500004452C4322438C692243CC6922434C6A3C -:109D600022438C6A22431A430260CA6842600A682E -:109D700082604968C16030BD00210160416081603E -:109D8000C160016141618161C161016241628162C1 -:109D900070470029016802D041F0010102E04FF64E -:109DA000FE72114001607047002A026801D00A4328 -:109DB00000E08A430260704741607047406880B2AB -:109DC0007047C10003D50549091F08607047024963 -:109DD000083948607047000008000240080402404B -:109DE00030B523498379026853B30B6893430B6002 -:109DF0000A1D13680468A343136002790A441368B8 -:109E00000468234313601A4A083213680468A343A2 -:109E10001360131D1C680568AC431C604479102C4A -:109E200005D021440A68006802430A6030BD116809 -:109E3000046821431160196800680143196030BD4E -:109E40000079084401689143016030BD084A014629 -:109E500000201268064B0A4014331B680B4202D0E4 -:109E6000002A00D001207047014914310860704772 -:109E7000000401405A4910B588424FF0010101D158 -:109E80004C0501E04FF48004204600F019F920460B -:109E9000BDE81040002100F013B970B50446808879 -:109EA00086B00D4620F03F06684600F09FF84D4909 -:109EB0000298B0FBF1F189B20E43A680228822F00D -:109EC00001022280484B2A689A421CD85200B0FBFB -:109ED000F2F080B2042800D20420491C2184A0831F -:109EE000208840F00100208021884FF6F5300140A5 -:109EF000A8886A89104308432080A88929890843D3 -:109F0000208106B070BDEB88A3F53F46FF3E05D12A -:109F100002EB4202B0FBF2F080B208E002EBC203B7 -:109F200003EB0212B0FBF2F080B240F48040020575 -:109F300001D140F001004FF4967251434FF47A7210 -:109F4000B1FBF2F140F40040C7E741F28831016013 -:109F5000002181804BF6FF72C280018141814FF464 -:109F60008041818170470029018802D041F00101C0 -:109F700001E021F00101018070470029018802D031 -:109F800041F4807101E021F4807101807047002963 -:109F9000018802D041F4007101E021F400710180D8 -:109FA00070470029018802D041F4806101E021F46A -:109FB000806101807047002A828801D00A4300E056 -:109FC0008A438280704701827047008AC0B270471E -:109FD00012B141F0010101E001F0FE010182704780 -:109FE0000054004040420F00A086010030B53C49BB -:109FF0004A683C4B12F00C0405D03B4A042C126812 -:10A0000003D0082C24D0036000E002604A680F23CC -:10A0100003EA1212354B9C5C0268E24042604C68D5 -:10A02000072505EA14241C5D22FA04F484604C68B8 -:10A0300005EAD4241B5DDA40C2604968032303EAC1 -:10A0400091312A4B1B1F595CB2FBF1F1016130BD0C -:10A050004B684C6803F470134FF0020514F4803F12 -:10A0600005EB934305D04C68A40300D552085A432E -:10A07000CBE71F4A5343C6E7194A0029516901D06B -:10A08000014300E0814351617047154A00299169FD -:10A0900001D0014300E0814391617047104A0029DB -:10A0A000D16901D0014300E08143D16170470C4A7E -:10A0B0000029D16801D0014300E08143D16070479D -:10A0C000074A0029116901D0014300E08143116171 -:10A0D00070470348416A41F0807141627047000057 -:10A0E0000010024000127A000C040020240400201A -:10A0F00000093D0030B50288FD4BFE4C98420DD062 -:10A10000A0420BD0B0F1804F08D0FB4DA84205D043 -:10A11000FA4DA84202D0FA4DA84203D122F07005B0 -:10A120004A882A43F74DA84206D0F74DA84203D0EB -:10A1300022F44075CA882A4302808A8882850A8868 -:10A14000028598420AD0A04208D0F04A904205D039 -:10A15000EF4A904202D0EF4A904201D1097A01863B -:10A160000121818230BD30B5028C22F001020284CF -:10A17000028C8388048B22F0020224F073050C8881 -:10A180002C430D8915434A882A43D94DA8420BD048 -:10A19000D84DA84208D0DD4DA84205D0DC4DA842DC -:10A1A00002D0DC4DA8420DD122F008054A8923F4E3 -:10A1B00040732A4322F004058A882A438D891D436F -:10A1C000CB892B4383800483C9888186028430BD78 -:10A1D00070B5028C22F010020284028C8488038BFA -:10A1E0000D8823F4E6464FF6FF7303EA0525354351 -:10A1F0000E8922F0200203EA061616434A8803EA73 -:10A2000002123243BA4EB04202D0BA4EB04215D119 -:10A2100022F080064A8924F4406403EA02123243A1 -:10A2200022F040068A8803EA021232438E8903EA4A -:10A2300086062643CC8903EA84043443848005835C -:10A24000C9880187028470BD70B5028C22F48072C7 -:10A250000284028C8488838B0D8823F073031D4352 -:10A2600022F400730E894FF6FF7202EA06261E439F -:10A270004B8802EA032333439D4EB04202D09D4EE9 -:10A28000B04215D123F400664B8924F4405402EA0D -:10A290000323334323F480668B8802EA032333438A -:10A2A0008E8902EA06162643CC8902EA0414344356 -:10A2B00084808583C9888187038470BD70B5028CD2 -:10A2C00022F480520284048C8288838B0D8823F4CC -:10A2D000E6464FF6FF7303EA0525354324F400569E -:10A2E0000C8903EA043434434E8803EA06362643D5 -:10A2F0007F4CA04202D07F4CA04205D122F4804482 -:10A300008A8903EA8212224382808583C988A0F861 -:10A310004010068470BD828B22F440628283828B5F -:10A320004FF6FF7303EA01210A4382837047828B51 -:10A3300022F00C028283828B0A4382837047028B55 -:10A3400022F440620283028B4FF6FF7303EA01217D -:10A350000A4302837047F0B5048C24F0100404848F -:10A36000078B048C4FF6FF7527F4734705EA033318 -:10A370003B4305EA02221A435D4B05EA0116984267 -:10A380000ED05C4B98420BD0B0F1804F08D05A4BA6 -:10A39000984205D0594B984202D0594B984205D16A -:10A3A00024F02001314341F0100104E024F0A00327 -:10A3B0000B4343F0100102830184F0BD028B22F0B5 -:10A3C0000C020283028B0A430283704770B5048C2F -:10A3D00024F001040484058B048C4FF6FF7606EA12 -:10A3E0000313134325F0F305414A2B4390420ED04B -:10A3F000404A90420BD0B0F1804F08D03E4A904284 -:10A4000005D03E4A904202D03D4A904202D124F00B -:10A41000020201E024F00A020A4342F00101038330 -:10A42000018470BD2DE9F05F0D4604460888304F69 -:10A43000DFF8C0C0DFF8C0804988AA882B894FF0B8 -:10A44000804960B3042832D04FF6FF7E082836D00A -:10A45000208C9B4620F480502084A38B268C704651 -:10A4600000EA022223F473431A4300EA0B3010433C -:10A470000EEA013EBC420BD0644509D04C4507D0E2 -:10A48000444505D01D4A944202D01D4B9C425AD1EE -:10A4900026F4005141EA0E0141F4805158E0204673 -:10A4A000FFF794FFE9882046BDE8F05F86E7204685 -:10A4B000FFF751FFE9882046BDE8F05F3FE7208CB9 -:10A4C00020F480702084B4F81CA0208C0EEA0313C2 -:10A4D00013432AF0F30A0EEA012B43EA0A03BC42B3 -:10A4E00020D064451ED04C451CD044451AD013E002 -:10A4F000002C0140003401400004004000080040EE -:10A50000000C0040001000400014004000400140DA -:10A510000044014000480140494A944202D0494A5F -:10A52000944204D120F4007040EA0B0002E020F4D1 -:10A530002060084340F48070A3832084E98820468B -:10A54000BDE8F05FF3E626F402420A4342F480518C -:10A55000A08320462184E988BDE8F05FDBE64FF662 -:10A56000FF71818000210180C180418001727047AC -:10A570000021018041808180C180018141818181F0 -:10A58000C181704700210180418001228280C18009 -:10A59000018170470029018802D041F0010101E0EA -:10A5A00021F0010101807047002930F8441F02D0DA -:10A5B00041F4004101E0C1F30E0101807047002A1F -:10A5C000828901D00A4300E08A4382817047028B6E -:10A5D00022F008020A4302837047028B4FF6FF7392 -:10A5E00022F4006203EA0121114301837047828B48 -:10A5F00022F008020A4382837047828B4FF6FF7372 -:10A6000022F4006203EA0121114381837047808EA6 -:10A610007047008F7047808F7047B0F840007047D8 -:10A6200002460020138A92890B4202EA010202D0FC -:10A63000002A00D001207047C94301827047000002 -:10A6400000080040000C004030B50446008A85B088 -:10A650000D464CF6FF710840E98801432182A1892B -:10A660004EF6F3100140A8882A8910436A890A43EC -:10A670001043A081A08A4FF6FF410840A9890143F9 -:10A68000A1826846FFF7B2FC3048844201D10398AA -:10A6900000E00298A1890904002900EBC00101EB48 -:10A6A0000010296802DA4FEA410101E04FEA810116 -:10A6B000B0FBF1F06422B0FBF2F14FEA01114FEA76 -:10A6C00011136FF018056B4300EB8300A3891D0481 -:10A6D0004FF0320306D503EBC000B0FBF2F000F000 -:10A6E000070005E003EB0010B0FBF2F000F00F00F4 -:10A6F0000843208105B030BD0029818902D041F492 -:10A70000005101E021F400518181704710B5C1F37F -:10A71000421301F01F040121A140012B07D0022B9D -:10A7200007D01430002A026805D00A4304E00C3038 -:10A73000F8E71030F6E78A43026010BD002A828AEB -:10A7400001D00A4300E08A4382827047003801400A -:10A750003948384941603949416070473648016994 -:10A7600041F080010161704733490420CA68D20773 -:10A7700001D001207047CA68520701D502207047F6 -:10A78000C968C906FBD50320704700B50346FFF72B -:10A79000EBFF02E0FFF7E8FF5B1E012803D0002B70 -:10A7A00000D1052000BD002BF4D1FAE770B50546B5 -:10A7B0004FF430263046FFF7E8FF042811D11E4C35 -:10A7C000206940F0020020616561206940F040008E -:10A7D00020613046FFF7D9FF216941F6FD72114033 -:10A7E000216170BDF8B5064600204FF4005C009072 -:10A7F0000D466046FFF7C9FF042816D10E4C2069AC -:10A8000040F00100206135806046FFF7BEFF41F651 -:10A81000FE77042806D1B61C280C009630806046CE -:10A82000FFF7B3FF216939402161F8BD0249C860D3 -:10A83000704700002301674500200240AB89EFCD3F -:10A8400014481549026800608A4203D013488047C3 -:10A8500013480047134E4FF009003060124801685A -:10A8600021F07061016041020160104C18202060ED -:10A870000F49104808601048D0F800D040680047E1 -:10A88000FEE7FEE7FEE7FEE7FEE7FEE7FEE7FEE7A0 -:10A89000FEE7FEE7F04F0020EFBEADDEE9980008CE -:10A8A000ED0000081810024004000140140C0140A3 -:10A8B000000C01404434434400F0FF1F2A4910B506 -:10A8C00088420AD1841401212046FFF7F0FB20467C -:10A8D000BDE810400021FFF7EABB2449884202D1BD -:10A8E0000121041404E0224988420AD10121C41341 -:10A8F0002046FFF7E5FB2046BDE810400021FFF7AA -:10A90000DFBB10BD30B502884C8802F441530A8881 -:10A91000CD8822438C882C4322430C8922434C89C6 -:10A9200022438C892243CC8922431A430280828BA2 -:10A9300022F400628283098A018230BD00290188E5 -:10A9400002D041F0400101E021F040010180704758 -:10A9500081817047808970470246002012890A422F -:10A9600000D0012070470000003001400038004056 -:10A97000003C00400048704784D50008A0F1610108 -:10A98000192900D8203870472DE9F05F99461546FF -:10A990000F4683464FF0FF36DDF828A011E0A819D6 -:10A9A000441009FB047080460146584652469047C1 -:10A9B000002802D004DA254603E04046BDE8F09FB7 -:10A9C0002646A5EB06000128E9DC0020F6E740EA70 -:10A9D00001039B0703D009E008C9121F08C0042A1D -:10A9E000FAD203E011F8013B00F8013B521EF9D204 -:10A9F0007047D2B201E000F8012B491EFBD270472C -:10AA00000022F6E710B513460A4604461946FFF73A -:10AA1000F0FF204610BD421E12F8013F002BFBD173 -:10AA200011F8013B02F8013B002BF9D1704730B51A -:10AA300005462A460B4612F8010B13F8014B08B1E4 -:10AA4000A042F8D01CB1002802D06D1CF1E72846C6 -:10AA500030BD10B5044604E00B7800F8013B03B1AB -:10AA6000491C521EF8D2204610BDCAB2401E10F832 -:10AA7000011F8A4202D00029F9D100207047421CF0 -:10AA800010F8011B0029FBD1801A704770B50F4DDB -:10AA900000B92868002412E00A4602E09E4203D072 -:10AAA000521C1378002BF9D1DAB2224305D02BB116 -:10AAB00024B1002100F8011B04E00446401C067884 -:10AAC000002EE9D12860204670BD0000340400202B -:10AAD0002DE9F0410546002090460E46044600E070 -:10AAE000641C44450BD2285D00F058F90746305DE0 -:10AAF00000F054F9381A02D1295D0029F0D1BDE8DF -:10AB0000F08170B5064600F059FC046805460A223B -:10AB10000021304600F048F92C6070BDF0B480EAA6 -:10AB20000102D40F4200B2EB410F02D202460846A6 -:10AB300011464A0042D0C30DDDB2C1F3C752AD1A6F -:10AB4000202D35DAC1F3160141F4000204B152425E -:10AB5000C5F1200602FA06F12A411044B3EBD05F9A -:10AB600023D0C4B1012DA0EBC35009DCF0BC4FF0E1 -:10AB7000004202EAC35200F50000DBB200F055B912 -:10AB8000400000F1807000EBC350A0F1807040EAFB -:10AB9000D170490009E0490841EAC071A0EBC350F7 -:10ABA00000F50000400800EBC350F0BC00F034B9E1 -:10ABB0006142012202EB4101001BF6E7F0BC704745 -:10ABC00081F00041AAE780F00040A7E780EA010297 -:10ABD00010B502F00043400026D04A0023D04FEACF -:10ABE000106101EB1261C0F35600C2F3560240F44B -:10ABF000000042F40002A0FB0220A1F17F014FEA15 -:10AC00000040140401D000F1010050EA124001D4C8 -:10AC10004000491EC2B20C0604EBD010401C400894 -:10AC2000802A02D003E0002010BD20F0010000299E -:10AC300000DA0020184310BD30B480EA010202F0AF -:10AC4000004530F0004221F0004015D0A0B1C0F323 -:10AC5000C753C2F3C754C2F31601C0F31600E41A77 -:10AC600041F4000140F400027D34914201D3641CA0 -:10AC700000E04900002C02DA30BC002070474FF49D -:10AC800000000023914201D3891A034340084FEA90 -:10AC90004101F7D151B1914202D14FF0004105E09D -:10ACA00002D24FF0010101E06FF0010103EBC4504B -:10ACB000284430BC00F0B0B8420005D0C0F3C75201 -:10ACC0005242914201DC0020704700EBC1507047B6 -:10ACD000C10F80EAE0700844CA079623002100F003 -:10ACE000A4B896230022114600F09FB800F000425D -:10ACF00020F00040C10DC0F3160040F400007F2991 -:10AD000001DA00207047962903DCC1F19601C840A2 -:10AD100001E096398840002AF4D04042704720F084 -:10AD20000040C10DC0F3160040F400007F2901DA95 -:10AD300000207047962903DCC1F19601C840704796 -:10AD40009639884070470000002801DBC0F10040C0 -:10AD5000002901DBC1F1004181427047002801DB7D -:10AD6000C0F10040002901DBC1F100418842704779 -:10AD700030B50B46014600202022012409E021FACB -:10AD800002F59D4205D303FA02F5491B04FA02F5C8 -:10AD90002844151EA2F10102F1DC30BDA0F14101F1 -:10ADA000192900D8203070472DE9F04791460F4609 -:10ADB00080460446002614F8015B2DB1FFF7DAFD4A -:10ADC0000068405DC007F6D12B2D02D02D2D18D084 -:10ADD000641E4A463946204600F0E1F927B1396839 -:10ADE000A14201D1C7F8008071054FF002040BD5D4 -:10ADF0004042002803DD00F0E1FA0460A007BDE84E -:10AE0000F08746F48066E4E70028F8DA00F0D6FA26 -:10AE100004606FF00040F2E70029A8BF7047401CB3 -:10AE2000490008BF20F00100704710B4B0FA80FC60 -:10AE300000FA0CF050EA010404BF10BC704749B19D -:10AE4000CCF1200421FA04F411FA0CF118BF01210D -:10AE500021430843A3EB0C01CB1D0106000A002B84 -:10AE6000BEBF002010BC704700EBC3501044002947 -:10AE7000A4BF10BC7047401C490008BF20F001006F -:10AE800010BC7047F0B4002802DCF0BC0020704712 -:10AE9000C0F3C751C0F3160040F40000CA0701D147 -:10AEA0004000491E3F2202EB6105002211464FF48B -:10AEB000000626FA01F31344D418844201D8001B7B -:10AEC0001A464000491C1729F3DD5100814202D285 -:10AED0004FF0FF3100E0002102EBC550F0BCFFF75E -:10AEE0009BBF10B541000CD0C0F3C751962908DCB8 -:10AEF0007E2909DC06DB410204D000F0004040F06E -:10AF00007E5010BD002010BDC1F19604C4F1200197 -:10AF100000FA01F1E040FFF77FFFA04010BD2DE9EE -:10AF2000FE4F804681EA0300C00F0C46009021F0DE -:10AF3000004123F00045B8EB0200A94105D240468C -:10AF4000214690461C460B46024623F00040104323 -:10AF500004D14046214603B0BDE8F08F270DC7F36A -:10AF60000A00C3F30A510290401A0190402866DAA1 -:10AF7000C3F3130040F4801B0098924620B10023D5 -:10AF8000D2EB030A63EB0B0B01985946C0F1400268 -:10AF9000504600F0D3F806460D4650465946019AF1 -:10AFA00000F0EBF810EB08006141002487EA115231 -:10AFB00084EAE7731A433BD0009A3AB3019A012A14 -:10AFC0004FEA075210DC001B61EB02014FF0004218 -:10AFD00002EA0752CDE90042001C41F580113246D9 -:10AFE0002B4600F038F9B6E7001B61EB0201001CAC -:10AFF00041F5801300185B412018A2F5001747EBBC -:10B00000030140EAD570B6196D4111E06D084FEAB1 -:10B01000360645EAC0754FEA0752001B61EB020194 -:10B02000001C41F5801149084FEA300000195141D8 -:10B0300032462B4603B0BDE8F04F00F0FFB8009851 -:10B04000012240000023D0EB020263EBE073009882 -:10B0500021464FEAE074B8EB000061EB0401E9E738 -:10B0600083F000435BE781F0004158E710B500F042 -:10B07000004420F00040C20DC0F3160040F4000070 -:10B080007F2A07DA7D2A00DA7D22763A00FA02F179 -:10B09000002008E0962A09DCA2F1760100FA01F10D -:10B0A000C2F19602D040FFF7B7FE01E0963A904019 -:10B0B000002C00D0404210BD00F0004230F00040B3 -:10B0C0000AD0C10D01F56071C0F3160042EA0151CA -:10B0D000C20840071143704700200146704701F045 -:10B0E000004330B421F0004150EA010206D00A0DBD -:10B0F000A2F56072C1F31301002A02DC30BC00200B -:10B100007047440F44EAC104C100E01830BC00EBB2 -:10B11000C250FFF781BE0000064C074D06E0E06814 -:10B1200040F0010394E8070098471034AC42F6D38E -:10B13000F4F7E0FF1CDF00083CDF0008202A04DBF6 -:10B14000203A00FA02F1002070479140C2F120033A -:10B1500020FA03F3194390407047202A04DB203A79 -:10B1600021FA02F00021704721FA02F3D040C2F127 -:10B1700020029140084319467047202A06DBCB176E -:10B18000203A41FA02F043EAE07306E041FA02F3A2 -:10B19000D040C2F1200291400843194670472DE982 -:10B1A000F05F82460078002715468B460AF10104BD -:10B1B000B946302801D09DB113E014F8010B0127E6 -:10B1C000782803D0582801D045B10AE00DB1102DE0 -:10B1D00007D10027102514F8010B02E0082500E034 -:10B1E0000A250026B0460EE005FB080005FB06F127 -:10B1F000012701EB10461FFA80F8B6F5803F00D317 -:10B20000B94614F8010B294600F077F80028EBDA6C -:10B21000BBF1000F05D00FB1641E00E05446CBF81F -:10B220000040B9F1000F06D000F0C8F8022101601B -:10B23000C81EBDE8F09F48EA0640FAE710B5002BAB -:10B2400008DA401C41F1000192185B411A4301D118 -:10B2500020F0010010BD2DE9F04D92469B4611B142 -:10B26000B1FA81F202E0B0FA80F220329046FFF7A4 -:10B2700065FF04460F4640EA0A0041EA0B015346C7 -:10B280005A46084303D120463946BDE8F08D1146A1 -:10B2900053EA010015D0C8F140025046FFF75DFFA8 -:10B2A00005460E46504659464246FFF747FF0843BB -:10B2B00001D0012000E00020054346EAE0762C435F -:10B2C00037430A984FEA4453A0EB08004FEAD424CE -:10B2D0000A304FF0000244EA47544FEAD72502D51E -:10B2E00000200146D1E7010510196941DDE9084553 -:10B2F00000196941BDE8F04DA0E73A2800D2303886 -:10B3000020F02002412A01D3A2F13700884201D364 -:10B310004FF0FF30704770B501EB020410F8015B8D -:10B3200015F0070301D110F8013B2A1106D110F8DE -:10B33000012B03E010F8016B01F8016B5B1EF9D1E2 -:10B340002B0705D40023521E0FD401F8013BFAE766 -:10B3500010F8013B02F10202A1EB030303E013F832 -:10B36000015B01F8015B521EF9D5A142D6D3002042 -:10B3700070BD00000FB4054B10B503A9044A029834 -:10B3800000F0E8F810BC5DF814FB0000C5240008CC -:10B39000380400204100080218BF04200A0E18BF1C -:10B3A00040F001004FF07F4232EA010108BF40F057 -:10B3B0000200012808BF05207047000000487047C0 -:10B3C0003C0400206FF05E010807FFF775BC000029 -:10B3D0002DE9F04D0E4614464FF07F41B1EB440F7E -:10B3E0009EBF4FF0FF313160BDE8F08D4FF000405F -:10B3F00040EA0421C4F3C7507838431100F01F001D -:10B40000DFF814C1C0F12002FC445CF823500CEBBF -:10B4100083038540D3F804C02CFA02F72F439D68BC -:10B420000CFA00FC25FA02F8DB6805FA00F023FAB2 -:10B4300002F240EA02054CEA080CA7FB0132ACFB21 -:10B4400001C0A5FB015101EB0C058D4234BF4FF04B -:10B45000010C4FF0000CC1186144BCF1000F02D088 -:10B46000814202D903E0814201D2012000E00020A4 -:10B47000104400F120024FEA92188006CA0C40EAFC -:10B4800042304F03C6F80080FFF722FC8246384660 -:10B49000FFF727FC6FF01201FFF70EFC0746284666 -:10B4A000FFF71FFC6FF02501FFF706FC83463946C6 -:10B4B0005046FFF733FB5946FFF730FB00F50065B8 -:10B4C0006FF30B0551462846FFF77AFB3946FFF725 -:10B4D00077FB5946FFF777FB1049FFF777FB0746E5 -:10B4E0000F492846FFF772FB3946FFF717FB07465F -:10B4F0000C492846FFF76AFB3946FFF70FFB14F0AB -:10B50000004F08BFBDE8F08DC8F1805180F00040C9 -:10B510003160BDE8F08D00007C210000DB0FC92FF9 -:10B5200022AAFD290000C92F02E008C8121F08C185 -:10B53000002AFAD170477047002001E001C1121FB4 -:10B54000002AFBD1704700000149086070470000E5 -:10B550003C0400202DE9FF4F8BB09A460F4605466C -:10B560000026C9E0252837D100246D1C6649A04675 -:10B5700001222B78203B02FA03F0084202D0044358 -:10B580006D1CF6E728782E2817D115F8010F44F026 -:10B5900004042A280ED06FF02F022878A0F1300181 -:10B5A00009290AD808EB880102EB410100EB0108E8 -:10B5B0006D1CF2E757F8048B6D1C287869283FD082 -:10B5C00006DC002871D063280CD0642804D137E051 -:10B5D000732811D075284ED052460D99904706F128 -:10B5E000010688E017F8040B8DF8000000208DF8A4 -:10B5F0000100E946012003E057F8049B4FF0FF30BB -:10B6000061074FF0000401D40AE0641C44450DDAE0 -:10B610008442FADB19F804100029F6D106E0641C14 -:10B620008442FCDB19F804100029F8D1264404E018 -:10B6300019F8010B52460D999047641EF8D25AE052 -:10B6400001CF4FF00A0B002804DAC0F100004FF0E0 -:10B650002D0102E0210504D52B218DF824100121B4 -:10B6600003E0E10705D02021F7E70DF1200908915B -:10B670000CE00021F9E701CF4FF00A0BF9E759463A -:10B68000FFF776FB01F1300209F8012D0028F6D111 -:10B69000ADEB090000F1200B600701D44FF0010869 -:10B6A000D84503DDA8EB0B0001E029E0002080462F -:10B6B000002406E009A85246005D0D999047761CCB -:10B6C000641C08988442F5DB04E0302052460D9952 -:10B6D0009047761CB8F10001A8F10108F5DC05E0FF -:10B6E00019F8010B52460D999047761CBBF10001E9 -:10B6F000ABF1010BF4DC6D1C287800287FF432AF2D -:10B700000FB03046BDE8F08F092801002DE9F04761 -:10B710004FF0684202EB40030C460546B3F1654F1B -:10B720003CBF02EB4102B2F1654F3FD34FF07F4285 -:10B73000B2EB400F28BFB2EB410F03D2BDE8F04798 -:10B74000FFF7ECB940EA01035B0008BF44F0FF419A -:10B750000AD0B2EB400F08BFB2EB410F06D125F083 -:10B76000804024F0804105460C461FE0B2EB400FBC -:10B7700012BF5FEA410245F0FF4004F0004115D0DE -:10B780004FEA410292EA400310D4002AB4BF4FF0BE -:10B790003E564FF09F463146FFF718FA05463146B0 -:10B7A0002046FFF713FA044628462146C0F3C75344 -:10B7B000C1F3C7529A1A1B2A06DD10F0004F14BFBE -:10B7C00054485548BDE8F08712F11A0F17DA11F006 -:10B7D000004F06D010F0004F0CBF50485048BDE855 -:10B7E000F08721462846FFF727FA0446FFF7D2FDE7 -:10B7F000042808BFFFF7E6FD2046BDE8F0874200B9 -:10B80000B2EB410F25D910F0004F19BF454F464EFE -:10B81000464F474E224685F0004415460A4680F0C2 -:10B82000004110460A1A5200B2F1807F3ED24840D1 -:10B830004049DFF804A110F0004F18D04FF03F4806 -:10B840003846FFF7BDF9074651463046FFF7B8F9CD -:10B8500017E011F0004F04BF00263746E2D010F089 -:10B86000004F19BF354F364E364F374EDAE74FF09F -:10B870007C583846FFF752F9074651463046FFF7E5 -:10B880004DF9064641462846FFF7A0F92146FFF745 -:10B8900045F9824621464046FFF798F92946FFF7C9 -:10B8A00092F95146FFF7C8F9044604E021462846BC -:10B8B000FFF7C2F904460146FFF788F9804623499D -:10B8C000FFF784F92249FFF729F94146FFF77EF98E -:10B8D0002049FFF723F94146FFF778F91E49FFF7A2 -:10B8E0001DF94146FFF772F91C49FFF717F90546A4 -:10B8F00041462046FFF76AF92946FFF767F93146C6 -:10B90000FFF70CF92146FFF709F93946BDE8F04782 -:10B91000FFF704B9DB0FC9BFDB0FC93FDB0F49409D -:10B92000DB0F49C00000C9BF22AAFDB90000C93F12 -:10B9300022AAFD390060ED3EC30ACE37000049C09F -:10B9400022AA7DBA0000494022AA7D3A2DAD65BDEC -:10B950008FB8D53D0FB511BE61C84C3EA8AAAABE8E -:10B960002DE9F8430446024650486946B0EB420FC1 -:10B9700009D94FF0E640B0EB420F94BF00204FF0E2 -:10B98000FF30009034E04A4B22F0004083422BD934 -:10B9900048492046FFF71AF9FFF7A3FA8046FFF758 -:10B9A000A5F900F00300009043494046FFF70EF967 -:10B9B000054642494046FFF709F9064640494046D8 -:10B9C000FFF704F907463F494046FFF7FFF82146D5 -:10B9D000FFF7F9F83946FFF7F3F83146FFF7F0F8CB -:10B9E0002946FFF7EDF802E01046FFF7F1FC0446A8 -:10B9F0002546009C002C18DA6800B0F17F4F3CBF50 -:10BA00004FF07E50BDE8F88309D14FF00100FFF7F9 -:10BA10009BFDBDE8F84300210846FFF70DB9284615 -:10BA2000BDE8F8430121FFF747B9294614F0010F9B -:10BA300008461CD0FFF7CAF806462349FFF7C6F8A8 -:10BA40002249FFF7C0F83146FFF7C0F82049FFF759 -:10BA500065F83146FFF7BAF82946FFF7B7F82946E7 -:10BA6000FFF75CF814F0020F1CD0BDE8F883FFF775 -:10BA7000ADF805461749FFF7A9F81749FFF74EF843 -:10BA80002946FFF7A3F81549FFF748F82946FFF7BD -:10BA90009DF84FF07E51FFF741F814F0020F08BFF8 -:10BAA000BDE8F88380F00040BDE8F883B61F927EC1 -:10BAB000490E494683F9223F1A61342C0020A233F3 -:10BAC00000A0FD390000C93F336D4C39DA82083CD3 -:10BAD000A0AA2ABEB93AB2BACA9F2A3DDDFFFFBE6C -:10BAE00070B50546FFF7C2FA04464000801C0DD130 -:10BAF0002846FFF7F6F905462046FFF7E9F82946FC -:10BB0000FFF722F91CBF0120FFF71EFD204670BD84 -:10BB10002DE9F04D0F460E46A0F500018046044683 -:10BB20004FF0007084B04FF07E554FF0000B00EBEB -:10BB300047004FF07F4AB1F1FE4F04D2B0F1804F81 -:10BB400080F0018141E0B0F1804F3ED304F1FF402D -:10BB5000B0F1FE4F1FD200BF28F00048C6F3C75017 -:10BB600044467F2809DB97287DDAC0F19600012141 -:10BB700001FA00F0411E314209D00120FFF7E4FC38 -:10BB800004B00021BDE8F04D0846FFF755B830423B -:10BB900018BFFE4DD7E0600000281CBF4FF080703A -:10BBA000B0EB440F0BD91B214046FFF785F88046C8 -:10BBB00004466FF01A0B10F0004FCDD1C3E0A4F58E -:10BBC0000000B0F1FE4F1BD2BDE0B0F1007F11D3F9 -:10BBD00000213846FFF7B8F806D16000002818BFEA -:10BBE000BAEB440F71D8B1E706F0004040F0FC56C4 -:10BBF0003746ABE7B0F1807F38BFA6F50007A5D385 -:10BC000024F000406FF0FF42E14B8118994210D3BD -:10BC100026F000410A449A420BD3B4F17E5F18BF6C -:10BC20005FEA460251D0B0F1FF4F98BFB1F1FF4F2C -:10BC300006D904B039464046BDE8F04DFEF76EBF68 -:10BC4000B4F1FF4F10D0C6F3C7507F2809DB972807 -:10BC500012DAC0F19600012101FA00F0411E3142D2 -:10BC600006D0002009E06EE016F0004F5DD127E01D -:10BC7000304218BF012000D1022014F5000F13D06C -:10BC800024B3B4F1004F27D014F1814F56D04FF0B8 -:10BC9000FE40B0EB440F94BF01200020012101EBD6 -:10BCA000E671884241D10BE016F0004F02D0012826 -:10BCB0003FD03AE0012802BFB64804B0BDE8F08D9D -:10BCC0004FF0FF4004B0BDE8F08D37E016F00040C3 -:10BCD0000ED104B0BDE8F08DB6F1FF4F25D016F5BA -:10BCE000000F05D016F0004F18D008B101280AD077 -:10BCF0000220FFF729FC04B00021BDE8F04D4FF011 -:10BD00007E50FEF799BF0220FFF71EFC04B04146AB -:10BD1000BDE8F04D4FF07E50FEF78EBF002804BF07 -:10BD200004B0BDE8F08D012803D004B00020BDE8C8 -:10BD3000F08D04B04FF00040BDE8F08D04B04FF03E -:10BD40007E50BDE8F08D94482044B0F5005F44D8A3 -:10BD50004046FFF7B1F90022904BFFF781F9FFF75A -:10BD6000BEF904466FF00101FEF7A6FF8C49FEF70D -:10BD70002AFF2146FEF72AFF4FF07C51FEF723FFF2 -:10BD8000064621460846FEF721FF80F00040314676 -:10BD9000FEF71CFF804683492046FEF717FF064644 -:10BDA00081494046FEF712FF804680492046FEF753 -:10BDB0000DFF4146FEF7B2FE044601463046FEF74F -:10BDC000ADFE00F5006B6FF30B0B59463046FEF7E6 -:10BDD000F7FE2146FEF7A2FED4E004F58020C00C59 -:10BDE00000F00F06C0F307107F38A4EBC054834463 -:10BDF0003046FEF76DFF6FF00301FEF75DFF4FF079 -:10BE00007E51FEF78BFE014602902046FEF7D8FEDB -:10BE1000019020460299FEF781FE00F500686FF35D -:10BE20000B08009041460298FEF7CAFE2146FEF735 -:10BE300075FE02904FF07E500099FEF7FDFE014620 -:10BE400000900198FEF7C2FE00F500646FF30B044A -:10BE500020460299FEF7BAFE029041462046FEF7C0 -:10BE6000B5FE0199FEF7AFFE0299FEF7A9FE009913 -:10BE7000FEF7ACFE014600902046FEF74FFE01465D -:10BE8000FEF7A4FE80464A49FEF7A0FE4449FEF7AD -:10BE900045FE4146FEF79AFE804600212046FEF709 -:10BEA0000BFF019020460099FEF738FE4146FEF751 -:10BEB0008DFE044600210098FEF7FEFE2146FEF7A7 -:10BEC0002DFE804601460198FEF728FE00F500642D -:10BED0006FF30B0421460198FEF772FE4146FEF710 -:10BEE0001DFE804633492046FEF770FE0090324921 -:10BEF0004046FEF76BFE804630492046FEF766FE60 -:10BF00004146FEF70BFE804601460098FEF706FE0E -:10BF100000F500646FF30B0421460098FEF750FE15 -:10BF20004146FEF7FBFD80462548784450F8361020 -:10BF300000EBC600019146684FEA0B10FEF7C8FE01 -:10BF4000009031464046FEF7E9FD2146FEF7E6FD4A -:10BF50000199FEF7E3FD0099FEF7E0FD00F5006BA7 -:10BF60006FF30B0B58460099FEF72AFE0199FEF776 -:10BF700027FE2146FEF724FE3146FEF721FE41460C -:10BF8000FEF721FE804607F500641BE0000080BF3D -:10BF9000FFFF3F00000080FF001080C00000F03F66 -:10BFA000ABAAAA3E00B0B8413BAAB841D49A38BB6C -:10BFB0007EE24C3E00B038423BAA3842D49AB8BB2D -:10BFC000921400006FF30B0421463846FEF7F8FD8B -:10BFD000074621465846FEF7F9FD064639462046F3 -:10BFE000FEF79CFD4146FEF7F1FD044639465846F2 -:10BFF000FEF7ECFD2146FEF791FD0746014630466F -:10C00000FEF78CFD00F500646FF30B04214630460B -:10C01000FEF7D6FD3946FEF781FD804601462046F3 -:10C02000FEF77CFDFFF722F807460611FEF750FEEB -:10C030002146FEF7C8FD4146FEF770FD044635492E -:10C04000FEF7C4FD3449FEF769FD2146FEF7BEFD4B -:10C050003249FEF763FD2146FEF7B8FD0146304840 -:10C0600007F00F04784450F82400FEF7AFFD2D4987 -:10C07000794451F82410FEF751FD2B49794451F8C9 -:10C080002410FEF74BFD06F17D01FC2908D2314654 -:10C09000FEF712FE04B02946BDE8F04DFEF796BD4E -:10C0A00006F1BF01B1F5BF7F16D83146FEF704FE99 -:10C0B0002946FEF78BFD0446BAEB440F1AD0600008 -:10C0C0000CD02046FFF766F9042808BFFFF77AF97D -:10C0D000204604B0BDE8F08D002E0BDA0220FFF7F9 -:10C0E00033FAFFF76FF90146284604B061F31E00EA -:10C0F000BDE8F08D0220FFF727FA61214FF0E04004 -:10C10000FEF7DAFD0146284604B061F31E00BDE8E3 -:10C11000F08D0000FC596337C9FF753A1872313D44 -:10C12000581400000C140000C01300002DE9F8435F -:10C130000446024653486946B0EB420F09D94FF016 -:10C14000E640B0EB420F94BF00204FF0FF3000906C -:10C1500034E04D4B22F0004083422BD94B4920461E -:10C16000FEF734FDFEF7BDFE8046FEF7BFFD00F092 -:10C170000300009046494046FEF728FD0546454924 -:10C180004046FEF723FD064643494046FEF71EFDA6 -:10C19000074642494046FEF719FD2146FEF713FDCA -:10C1A0003946FEF70DFD3146FEF70AFD2946FEF73A -:10C1B00007FD02E01046FFF70BF904462546009CF8 -:10C1C000002C1DDA6800B0F17F4F09D22846FFF736 -:10C1D000E1F8042808BFFFF7F5F82846BDE8F88322 -:10C1E00008D10120FFF7B0F9BDE8F8430021084667 -:10C1F000FEF722BD2846BDE8F8430121FEF75CBDED -:10C20000294614F0010F08461ED0FEF7DFFC054654 -:10C210002349FEF7DBFC2349FEF780FC2946FEF7A5 -:10C22000D5FC2149FEF77AFC2946FEF7CFFC4FF0FA -:10C230007E51FEF773FC14F0020F08BFBDE8F883CF -:10C2400080F00040BDE8F883FEF7C0FC06461749C1 -:10C25000FEF7BCFC1649FEF7B6FC3146FEF7B6FC0D -:10C260001449FEF75BFC3146FEF7B0FC2946FEF7A9 -:10C27000ADFC2946FEF752FC14F0020FE0D1BDE8F8 -:10C28000F8830000B61F927E490E494683F9223F8B -:10C290001A61342C0020A23300A0FD390000C93FF0 -:10C2A000B93AB2BACA9F2A3DDDFFFFBE336D4C39A1 -:10C2B000DA82083CA0AA2ABE70B50546FEF7E2FD68 -:10C2C000044620F00040C0F1FF40C00F08D025F028 -:10C2D0000040C0F1FF40C00F04BF0120FFF734F958 -:10C2E000204670BD41D600089ED60008FCD6000846 -:10C2F0003ED6000845D60008DDD50008D8D5000890 -:10C300002CD60008CDD50008F6D60008E0D50008E8 -:10C31000AFD600080BD70008F7D500086FD6000885 -:10C3200008D60008C6D5000838D6000891D60008FF -:10C33000D7D60008CAD6000868D60008000000005A -:10C340007DD60008E6D600084CD6000802D70008C3 -:10C35000A4D60008EBD6000814D6000823D600089F -:10C36000E2D60008EED50008B9D6000815D70008B7 -:10C37000BFD6000881D60008EBD500085DD60008BE -:10C38000000000008CD60008E7D5000887D600081A -:10C3900004D60008B9D60008E2D6000800D6000886 -:10C3A000000000009ADD0008D0D50008B7D50008CD -:10C3B0005ADD0008BFD5000872D800080000000050 -:10C3C00075DD000808DD00083303000870DD000893 -:10C3D000FCDB00088703000855DC0008B6DC000819 -:10C3E000A9060008CCDB0008E3DA00085B070008B8 -:10C3F00083DC00089ADD0008D10800089BD80008FB -:10C400004EDA0008F5080008B6D9000805DA000879 -:10C41000C1090008C7DB00089ADD0008D909000837 -:10C42000C3DB0008D1DB0008050A00080ADC0008AD -:10C43000D3DC0008D50C000842DC000810D9000845 -:10C440005B0D000823D80008A8D50008EB0D0008F4 -:10C450002BD90008A6DC0008AB0800087FDC000828 -:10C46000E6DC0008250E000878DC00086CDC00081B -:10C47000690F000820DB00089ADD0008131000088F -:10C4800069D80008020000007C04002000000000C1 -:10C490002823000029D7000802000000840500209E -:10C4A000B0040000A406000051D8000802000000FB -:10C4B0004005002000000000D00700005DD8000803 -:10C4C000020000004205002000000000D00700002C -:10C4D000D3D700080200000044050020000000003F -:10C4E000D0070000E4D90008020000008605002003 -:10C4F00000000000D0070000EDD900080200000095 -:10C500008805002000000000D00700004BDD000877 -:10C51000020000004605002000000000D0070000D7 -:10C52000A6D9000802000000480500200000000015 -:10C53000D00700002FD70008020000004A050020A5 -:10C5400000000000D00700002BD800080200000007 -:10C550004C05002000000000D0070000CAD80008E9 -:10C56000020000004E05002032000000F201000031 -:10C57000BBD8000802000000500500203200000077 -:10C58000F2010000D6DA0008000000008A05002051 -:10C59000000000000100000058D700080000000063 -:10C5A0008B0500200000000064000000EBD80008AC -:10C5B0000400000090050020B004000000C201004B -:10C5C000E7D8000804000000940500208025000042 -:10C5D000004B000064D70008000000009805002010 -:10C5E000000000000100000077D8000800000000F3 -:10C5F0008D0500200000000003000000FBD80008AB -:10C60000010000008E050020FFFFFFFF0400000076 -:10C6100080D8000800000000820500200000000013 -:10C62000020000001FDA0008000000009905002049 -:10C63000000000000100000019D800080000000000 -:10C64000760500200A000000C8000000F1D70008AD -:10C6500000000000770500200A0000003200000002 -:10C66000DED7000800000000780500200A00000066 -:10C670003200000062DA00080000000079050020A6 -:10C68000000000000900000087DB00080000000037 -:10C690005205002000000000080000001FD700081D -:10C6A000000000005305002000000000080000000A -:10C6B00056D90008000000005405002000000000CA -:10C6C00008000000A9DA0008030000005605002059 -:10C6D0004CFFFFFF6801000075D90008030000004F -:10C6E000580500204CFFFFFF680100002FDD000807 -:10C6F000030000005A0500204CFFFFFF6801000006 -:10C7000038DB0008010000005C050020FFFFFFFF90 -:10C71000010000008ED80008000000005D05002028 -:10C72000000000000500000080D7000800000000A5 -:10C730006805002000000000800000004DD90008BE -:10C74000020000005E050020000000000001000063 -:10C750001FDC0008020000006005002064000000EB -:10C76000E803000030DC0008020000006205002041 -:10C7700064000000E8030000EDDB0008000000009A -:10C78000EC0700200000000001000000CAD70008EC -:10C7900000000000520800200000000020000000FF -:10C7A000C7D7000800000000530800200000000068 -:10C7B0006400000034DA0008000000005408002083 -:10C7C00001000000FA00000004D80008000000008A -:10C7D0005508002000000000010000005CDB00089C -:10C7E0000000000056080020000000006400000067 -:10C7F000A3D80008000000000B0800200000000083 -:10C80000FA00000076DB0008000000000C080020A1 -:10C81000000000006400000078D70008000000005D -:10C820000D08002000000000640000007EDB00080E -:10C83000000000000E08002000000000640000005E -:10C84000ABD80008000000000F0800200000000026 -:10C850006400000008D90008000000001008002053 -:10C86000000000006400000079DD00080000000006 -:10C870009808002000000000C800000088DD0008C3 -:10C88000000000009908002000000000C80000001F -:10C890003FD80008020000009A080020E8030000CA -:10C8A000D007000090D70008020000009C0800207C -:10C8B00064000000D007000074DA000801000000E6 -:10C8C0008C05002000000000040000004EDB000882 -:10C8D000010000009E080020FFFFFFFF0100000094 -:10C8E00092DB0008010000009F080020000000000B -:10C8F0000100000048DC000800000000A008002043 -:10C9000000000000FF00000010DC00080000000034 -:10C910001808002000000000FA000000AAD7000854 -:10C92000000000001A080020000000006400000061 -:10C93000B9D700080000000019080020000000001E -:10C9400064000000F6D9000800000000280800205C -:10C9500000000000010000008FD900080300000063 -:10C9600016080020D4FEFFFF2C010000C1DA0008E9 -:10C970000300000014080020D4FEFFFF2C0100007B -:10C9800030D90008000000001B0800200000000053 -:10C99000300000003ED90008050000001C080020FF -:10C9A000000000000100000085DA0008050000001A -:10C9B0002008002000000000010000008EDC0008BC -:10C9C0000500000024080020000000000100000015 -:10C9D00028DB00080300000012080020B0B9FFFFA8 -:10C9E00050460000AFDB000800000000F107002007 -:10C9F00000000000C8000000D0D9000800000000BE -:10CA0000FB07002000000000C800000044D7000819 -:10CA1000000000000508002000000000C800000021 -:10CA2000A4DB000800000000F20700200000000066 -:10CA3000C8000000C5D9000800000000FC07002065 -:10CA400000000000C800000039D700080000000006 -:10CA50000608002000000000C8000000B9DB000844 -:10CA600000000000F307002000000000C8000000E4 -:10CA7000DAD9000800000000FD07002000000000D7 -:10CA8000C80000004ED70008000000000708002082 -:10CA900000000000C80000005EDC0008020000008A -:10CAA000A208002000000000D007000060D90008A4 -:10CAB00000000000A60800200000000001000000A7 -:10CAC00012DB000802000000A80800200A00000095 -:10CAD000D007000062DD000802000000AA08002064 -:10CAE0000A000000D0070000D9D8000800000000AC -:10CAF000A508002000000000640000009ED9000886 -:10CB000000000000EE07002000000000C800000048 -:10CB100087D9000800000000F8070020000000008E -:10CB2000C80000007FD900080000000002080020B3 -:10CB300000000000C8000000CFDA0008000000007C -:10CB4000ED07002000000000C8000000BADA00086D -:10CB500000000000F707002000000000C8000000EF -:10CB6000B3DA000800000000010800200000000007 -:10CB7000C800000045DD000800000000EF070020AD -:10CB800000000000C80000003FDD000800000000B9 -:10CB9000F907002000000000C800000039DD00088F -:10CBA000000000000308002000000000C800000092 -:10CBB000A0DC000800000000F007002000000000DA -:10CBC000C80000009ADC000800000000FA070020FE -:10CBD00000000000C800000088DC00080000000021 -:10CBE0000408002000000000C8000000A1DA0008CE -:10CBF00000000000F407002000000000C800000052 -:10CC000099DA000800000000FE0700200000000084 -:10CC1000C800000091DA00080000000008080020A9 -:10CC200000000000C8000000414552543132333446 -:10CC3000000000000000803F00000000A8AAAA3FFA -:10CC4000000000000000803F000080BFB0AA2ABFA3 -:10CC5000000000000000803F0000803FB0AA2ABF13 -:10CC6000000000000000803F000000000000803F46 -:10CC7000000080BF0000803F000080BF0000000077 -:10CC80000000803F0000803F0000803F0000000067 -:10CC90000000803F0000803F00000000000080BFD7 -:10CCA000000080BF0000803F000080BF0000803F88 -:10CCB000000080BF0000803F000080BF000080BFF8 -:10CCC0000000803F0000803F0000803F0000803F68 -:10CCD0000000803F0000803F0000803F000080BFD8 -:10CCE000000080BF0000803F0000803F0000000087 -:10CCF000000000000000803F000080BF0000000036 -:10CD0000000000000000803F00000000A8AAAA3F29 -:10CD10000000803F0000803F000080BFB0AA2ABF13 -:10CD2000000080BF0000803F0000803FB0AA2ABF03 -:10CD3000000080BF0000803F00000000A8AAAA3FBA -:10CD4000000080BF0000803F000080BFB0AA2ABF63 -:10CD50000000803F0000803F0000803FB0AA2ABF53 -:10CD60000000803F0000803F000080BFD0B35D3FE7 -:10CD70000000803F0000803F000080BFD0B35DBF57 -:10CD8000000080BF0000803F0000803FD0B35D3FC7 -:10CD90000000803F0000803F0000803FD0B35DBFB7 -:10CDA000000080BF0000803F00000000D0B35DBFE6 -:10CDB0000000803F0000803F00000000D0B35D3FD6 -:10CDC000000080BF0000803F000000000000803FA6 -:10CDD000000080BF0000803F000080BF000080BFD7 -:10CDE000000000000000803F000000000000803FC5 -:10CDF0000000803F0000803F0000803F000080BFB7 -:10CE0000000000000000803FD0B35DBF0000803F05 -:10CE10000000803F0000803FD0B35DBF000080BFB6 -:10CE20000000803F0000803FD0B35D3F0000803FA6 -:10CE3000000080BF0000803FD0B35D3F000080BF96 -:10CE4000000080BF0000803FD0B35DBF0000000045 -:10CE5000000080BF0000803FD0B35D3F00000000B5 -:10CE60000000803F0000803F000080BF0000803F46 -:10CE7000000080BF0000803F000080BF000080BF36 -:10CE80000000803F0000803F0000803F0000803FA6 -:10CE90000000803F0000803F0000803F000080BF16 -:10CEA000000080BF0000803F000080BF0000803F86 +:106880002001FEF7CCF82C7070BD2DE9F047904840 +:1068900090F8290118B99048407800287ED089489E +:1068A000806803F023F8002878D101F026FC8B4D96 +:1068B0006968401A7D2871D301F01FFC6860687810 +:1068C000874F401CDFF81C82DFF81C9268700024A0 +:1068D00004F12400C0B200F0ACF8388804F00FFADC +:1068E000064638F9140004F001FA314604F0B2F912 +:1068F000494604F079F904F007FA00B200F0ABF869 +:10690000641C032CE4DB302000F093F87748008807 +:1069100000B200F0A0F800F099F868784FF0640435 +:10692000800727D1102000F084F8714E306890FB6A +:10693000F4F000B200F08FF8212000F07AF830680F +:1069400090FBF4F104FB1100002800DC404200B28F +:1069500000F081F8142000F06CF86648B0F90000EF +:1069600000F079F81C2000F064F8002000F073F8C3 +:1069700000F06CF86878400735D1022000F059F833 +:106980005D484FF00A08B0F9001091FBF8F000B232 +:1069900000F061F80220FBF764F800E047E0D0B1B6 +:1069A00000F063F855486E21007848431521B0FB8C +:1069B000F1F63A2000F03DF8B6FBF4F738B200F0FB +:1069C0004AF83B2000F035F804FB1760401DB0FB8F +:1069D000F8F000F040F82020FBF72EF808B1FFF7A0 +:1069E000CEFE00F033F86878282820D100206870A7 +:1069F00001F083FB4FF47A71B0FBF1F43C25B4FB5A +:106A0000F5F6B6FBF5F005FB1067172000F011F85E +:106A1000380200B200F01FF8182000F00AF805FB59 +:106A2000164000F018F8BDE8F04700F00FB8BDE8D8 +:106A3000F08770B5234C05465E21A06802F046FF42 +:106A40002946A068BDE8704002F040BF1D485E21A5 +:106A5000806802F03BBF10B50446C0B2FFF774FE79 +:106A6000C4F30720BDE810406EE670B52348244EFD +:106A700040F6340200783178184DB0FBF1F0504305 +:106A80002A22B0FBF2F06A88B2FBF1F301FB13217A +:106A90004FF6FF7202EA011141EA0024C0F303201D +:106AA00004430620FFF7C5FF20B2FFF7D4FF688834 +:106AB0003178401C80B2B0FBF1F201FB120068801B +:106AC00070BD0000E00800204C010020A0860100FD +:106AD00070040020FC1400208C0A002058030020C1 +:106AE000820100208000002000007A442C00002059 +:106AF00020000020B0010020E8000020D20000208B +:106B000068010020884201DA084670479042FCDDA7 +:106B1000104670472DE9FE4F97499748E831B0F984 +:106B2000E600B1F90050B1F9024010B90DB9002CDE +:106B30007ED0924A0021117004F0D8F8904F394667 +:106B400004F052F8DFF83C82414604F083F8064630 +:106B5000284604F0CBF8394604F046F8414604F0E4 +:106B600079F80546204604F0C1F8394604F03CF8AF +:106B7000414604F06FF80746304604F0FFFE0290ED +:106B8000304605F0E1FA0190284604F0F7FE06468B +:106B9000284605F0D9FA0546384604F0EFFE0446CB +:106BA000384605F0D1FA00902046029904F01CF80E +:106BB00081463146204604F017F880460299009835 +:106BC00004F012F883462146019804F00DF882463D +:106BD000DDE9001004F008F86B4C074686F0004031 +:106BE000C4F80080009903F0FFFFC4E901052946BD +:106BF000504603F0F9FF594603F09EFFE060294636 +:106C0000384603F0F1FF494603F0EBFF206101989D +:106C1000314680F0004003F0E7FF606129464846B6 +:106C200003F0E2FF394603F0DCFF2946A06100E0F3 +:106C30000BE0584603F0D8FF514603F07DFFE061BA +:106C40003046029903F0D0FF2062BDE8FE8F2DE9A7 +:106C5000F0470546B0F90080B0F90260B0F90400D1 +:106C600004F044F8484C8246A16903F0BDFF074692 +:106C7000304604F03BF88146E16803F0B5FF064674 +:106C8000404604F033F88046216803F0ADFF3146FA +:106C900003F052FF394603F04FFF04F02FFF288026 +:106CA0005046E16903F0A0FF07464846216903F01A +:106CB0009BFF06464046616803F096FF314603F0AD +:106CC0003BFF394603F038FF04F018FF6880504658 +:106CD000216A03F089FF07464846616903F084FF93 +:106CE00006464046A16803F07FFF314603F024FFCB +:106CF000394603F021FF04F001FFA880BDE8F087CA +:106D0000092A11D2DFE802F0100509161C21262AF3 +:106D10002E0002880A80428803E042880A800288A6 +:106D20000CE04A808088888014480078002822D1AE +:106D300008468CE7028852420A8042885242F0E7B5 +:106D4000428852420A800288EBE7028852420A8057 +:106D500042880CE042880A80028808E002880A80A3 +:106D6000428803E0428852420A80028852424A80A6 +:106D700080884042D7E770477004002060030020FD +:106D8000DB0F494000003443D00E00204449084442 +:106D9000444990F80A0151F820004FF4777101EB53 +:106DA000500080B2704710B5044601F08CF93E499E +:106DB00002464868131A0020B3F57A6F00D948706C +:106DC0004A604A780AB90F2C0AD1087032B1354BA3 +:106DD00020331344182A03F8014C02D0521C4A7085 +:106DE00010BD304A2032D27D0AB901220A704870A3 +:106DF00010BD10B504462A4800212A4BB0F81401F2 +:106E00004200A2F5F76200BF43F82120491C08297F +:106E1000FADB0123254A2649264801F0FDFA0146FE +:106E20002548C1600CB1254921600821417410BD7D +:106E30001D4B10B5187840B11A484FF000022030B1 +:106E4000817DC908C90702D01A70002010BD1C49F5 +:106E5000401C0A8030F8011CC1F30A0411490C607F +:106E60000488C4F3CA044C600468C4F38A348C6098 +:106E7000B0F80340C4F34A04CC608488C4F30A1415 +:106E80000C614468C4F3CA344C61B0F80740C4F3E1 +:106E90008A048C6100894009C8611A70012010BD04 +:106EA00070040020F40E002064030020A08601007E +:106EB000A76D000800440040E00800208D6D000828 +:106EC000D60000202DE9F0410646007890B008B1C8 +:106ED000012500E00025DFF8D880404602F0D0FE12 +:106EE0003448009000243448CDE90104012725B13D +:106EF0000220CDE90304802002E0CDE903740020E4 +:106F000005904FF480700690800007902020089034 +:106F10000002CDE909046946404602F01EFF012146 +:106F2000404602F044FF8DF830500B948DF83170DC +:106F30004FF46020CDE90D040DB1022000E00120E6 +:106F40001C4C8DF83C004C3C0BA9204602F004FE82 +:106F5000032301220421204602F053FE2DB1317893 +:106F600003230222204602F04CFE0121204602F0BB +:106F70001CFE0121204602F00EFE204602F01FFEFC +:106F8000204602F021FE0028FAD1204602F023FE1E +:106F9000204602F025FE0028FAD10121204602F009 +:106FA00026FE10B0BDE8F081034931F810007047AB +:106FB000080002404C2401406C0300202DE9FF47EB +:106FC000DFF86C81814698F80000D0B300273E4678 +:106FD0003D463C46641CE4B202AB082232215320F9 +:106FE00000F063FD9DF808009DF80910202C00EBCF +:106FF000012000B207449DF80A009DF80B1000EB39 +:10700000012000B206449DF80C009DF80D1000EB25 +:10701000012000B205449DF80F0000F07F0001D26E +:107020000028D7D197FBF4F0ADF8000096FBF4F000 +:10703000ADF8020095FBF4F0ADF8040088F80240CA +:107040001EE0FFE702AB06223221532000F02DFDA7 +:107050009DF808009DF8091000EB0120ADF8000034 +:107060009DF80A009DF80B1000EB0120ADF802001E +:107070009DF80C009DF80D1000EB0120ADF8040008 +:1070800098F8012049466846FFF73AFEBDE8FF87B9 +:1070900070B5274D04464FF0080228784FF02D01B7 +:1070A00000284FF053000ED000F0F9FC0A223121E5 +:1070B000532000F0F4FC0C222C21532000F0EFFCB4 +:1070C0009022382108E000F0EAFC0A223121532006 +:1070D00000F0E5FC0A222C21532000F0E0FC1549C9 +:1070E00040F20910002C088000D06C7070BD38B5DB +:1070F000054600208DF800000F480C460F49006837 +:1071000088420AD06B4601220021532000F0CDFCBA +:1071100018B19DF80000E52801D0002038BD0449D1 +:10712000287808700648206006486060012038BD55 +:1071300070030020820100200C040020001BB70017 +:1071400091700008BD6F000810B54FF480442046D0 +:1071500002F08AFE012805D1204602F093FEB949CB +:107160000120087010BD70B50D46B649B64A0646F6 +:1071700088885389B2F91440C01A13895843B2F968 +:107180001230C013DB02044493FBF4F31844D061C3 +:1071900000EB8000082202EB40000411886800F038 +:1071A000D0F806B13060002D00D02C6070BD38B52D +:1071B000A44C207810B96088401C60806B46032284 +:1071C000F621772000F071FC9DF800009DF8011079 +:1071D000000440EA01209DF8021008439A49B1F9E1 +:1071E0002010C1F10801C840A06038BD9648342184 +:1071F00090F8200001EB80109249C2B20020087084 +:10720000F421772000F04BBC38B58E4C207810B9B3 +:107210006088401C60806B460222F621772000F0D7 +:1072200044FCBDF8000040BAA08038BD854900206C +:107230002E220870F421772000F031BC2DE9F043B4 +:1072400004468248824985B00068884203D1002004 +:1072500005B0BDE8F083DFF8EC9199F8010008B1C2 +:107260000120F5E74FF40055ADF80C5002208DF8E1 +:107270000F001020774E8DF80E0003A9304601F064 +:1072800039FF6F00ADF80C7004208DF80E0003A9D3 +:10729000304601F02FFF35610E21022001F060FF22 +:1072A00000208DF8080008208DF809004FF0010833 +:1072B000019747468DF80A8001A802F09FFD28201B +:1072C0008DF810000F208DF811008DF812008DF848 +:1072D000137004A802F00DFC142000F01DFF6B4693 +:1072E0000122D021772000F0E0FB574F9DF80000ED +:1072F0000321F8753984552801D07561A7E76B46DD +:107300000122D121772000F0D0FB9DF8000000F091 +:107310000F0139760009787600F05CF889F8018071 +:1073200041F27070208046F6781060804A486060B4 +:107330004A48A0604A48E0604A4820614A48606183 +:107340008EE770B54049CA69B1F90E40A2F57A627C +:1073500002FB02F31D136C43E512B1F90240B1F9CF +:107360000460544305EBE424B1F9005004EB8505B7 +:1073700091F82040A54056437213B1F90C601B13DD +:107380005E4302EB2642921C9210C98802F500422D +:10739000AD1C5143C90B4CF25032A0EBA500E240AA +:1073A0005043B0F1004F03D24000B0FBF1F002E0D7 +:1073B000B0FBF1F040000112494340F6DE32514388 +:1073C0002A4A0914424301EB224101F6CF6100EB46 +:1073D000211070BD00B587B06B461622AA21772018 +:1073E00000F063FBBDF8000041BA17480180BDF80A +:1073F000021049BA4180BDF8041049BA8180BDF835 +:10740000061049BAC180BDF8081049BA0181BDF81B +:107410000A1049BA4181BDF80C1049BA8181BDF802 +:107420000E1049BAC181BDF8101049BA0182BDF8E9 +:10743000121049BA4182BDF8141049BA818207B0CE +:1074400000BD000074030020300F00200C04002059 +:10745000001BB700001001402D72000809720008DF +:10746000ED710008AF7100086771000843E3FFFF8A +:1074700038B5044600208DF800006B4601220A2131 +:107480001E2000F012FB18B19DF80000482801D022 +:10749000002038BD0CB18D480470012038BD7FB587 +:1074A000054602AB062203211E2000F0FEFABDF8BD +:1074B000080040BA00B203F019FC844C241D216876 +:1074C00003F092FB03F020FCADF80000BDF80A00C9 +:1074D00040BA00B203F00AFCA16803F085FB03F098 +:1074E00013FCADF80400BDF80C0040BA00B203F084 +:1074F000FDFB616803F078FB03F006FCADF80200C9 +:10750000201F294602786846FFF7FAFB7FBD2DE968 +:10751000F0476F4800246F49006825468EB02E461C +:107520004FF0010888420CD14FF48050ADF828008C +:1075300002208DF82B0004208DF82A000AA9664845 +:1075400008E06649884207D14FF48040ADF8280032 +:107550000AA9634801F0CEFD322000F0DDFD1122C2 +:1075600000211E2000F09BFA602201211E2000F065 +:1075700096FA642000F0D0FD6846FFF790FFDFF830 +:1075800058A1DFF8609100270AF10C0A01220221BC +:107590001E2000F084FA322000F0BEFD6846FFF79E +:1075A0007EFFBDF90210BDF90400BDF900200D44B5 +:1075B00014440644814201DA0B4600E0034693423C +:1075C00001DD104602E0814200DA0846484502DC4F +:1075D0004FF0000808E0DAF8001081F01001CAF856 +:1075E00000107F1C0A2FD1DB122200211E2000F088 +:1075F00056FA0027012202211E2000F050FA322004 +:1076000000F08AFD6846FFF74AFFBDF90020BDF98A +:107610000210BDF90400A41A6D1A361A814201DA6B +:107620000B4600E00346934201DD104602E0814232 +:1076300000DA0846484502DC4FF0000808E0DAF8B6 +:10764000001081F01001CAF800107F1C0A2FD1DB56 +:10765000204603F04BFB244F0146384603F0FAFA6C +:107660001A4C20F00040241D2060284603F03EFB09 +:107670000146384603F0EEFA20F0004060603046E4 +:1076800003F034FB0146194803F0E4FA20F000400F +:10769000A060702200211E2000F001FA20220121AA +:1076A0001E2000F0FCF9002202211E2000F0F7F954 +:1076B000642000F031FDB8F1000F04D14FF07E508E +:1076C00020606060A0600EB0BDE8F08780030020FD +:1076D0000C04002000127A00000C0140001BB700CF +:1076E0000010014000F0FFFF00406F4601C05E4601 +:1076F00030B587B005464FF44060ADF81400022065 +:107700008DF817001C208DF8160005A9FB4801F024 +:10771000F1FCFB4CE56000F007FAE06802F0B8FB12 +:10772000684602F020FC00224FF44071E06802F04D +:1077300050FC0025ADF804504BF6FF70ADF8060084 +:107740004FF48040ADF80C00EE4800900121E06855 +:1077500002F017FC6946E06802F0ADFB4FF4A06050 +:1077600002F0C2F922208DF810008DF811508DF82A +:10777000125001208DF8130004A802F0BAF921205C +:107780008DF810008DF8115004A802F0B2F907B07E +:1077900030BD38B5DA4CE068818A009111F4706F21 +:1077A00001D001212170009911F4E06F25D0018BE7 +:1077B00000224FF4806102F00CFC009880051CD47C +:1077C000E0680188890518D40188C9050CD50188AD +:1077D000C905FCD4012102F0E8FBE06801888905B5 +:1077E000FCD4FFF785FF08E0012102F0DEFB002258 +:1077F0004FF44071E06802F0ECFBE068818A21F40C +:10780000706181820020207138BDC2E72DE9F0410E +:10781000BB4CE068818A4FF00105C9B2CA074FF03E +:10782000000627D0018821F400610180012102F0C7 +:10783000C6FBE670607A20B1607860B9A079FF2855 +:1078400009D061790022E06802F0D0FBA079FF281E +:1078500048D0FF20C9E06570E079022804D1E068D3 +:10786000018841F40061018061790122E06802F041 +:10787000BDFB37E08A074FF4806745D5BFF3508FD3 +:10788000E079012810D1607A70B1607860B1002190 +:10789000E06802F094FBBFF3508FE068018B012198 +:1078A00002F083FBA57018E0E068008BBFF3508FF7 +:1078B000E079022808D1607A30B1607820B10021E7 +:1078C000E06802F07CFB06E0E079032805D1607AED +:1078D00018B1607808B1002200E001223946E06862 +:1078E00002F077FB94F90310E079401C814209D142 +:1078F0006670A07828B100224FF44071E06802F071 +:1079000068FB2671BDE8F0814A0753D5A570627AFD +:107910007B494978CAB3C9B3E17902291FD900214B +:1079200002F04DFBE06802F05EFB94F9031062691F +:107930005054491CE1700121E06802F036FBA5704B +:10794000E06802F050FB94F9031062695054491C3E +:10795000E17001223946E06802F03BFB25E001219D +:1079600002F023FBE06802F03EFB94F90310626929 +:107970005054491CE170E06802F035FB94F90310A3 +:1079800062695054891CE1700FE000E000E009B921 +:10799000217A31B1012102F008FBE078401CE0704F +:1079A00003E0012102F0F7FA6570E0680188C9057B +:1079B000FCD497E74A061AD502F015FB94F9031098 +:1079C00062695054491C48B2E070E179C01C8142A0 +:1079D00004D100223946E06802F0FBFAE17994F91B +:1079E00003008142E5D100F10100E0707AE7090669 +:1079F000DFD594F903104B1C5AB20BD02369595CA4 +:107A0000E27002F0EEFAE07994F9031088423FF454 +:107A10005AAF67E7E270A17902F0E3FA607A0028D2 +:107A20007FF451AFE0790028F1D05BE7EEE6B0E6F5 +:107A3000ECE670B5324C4FEA400047F230556071C9 +:107A4000A171012020720021617223616361E271E2 +:107A500020712170E068818889050ED40188C905EC +:107A600005D401888905FCD4012102F094FA012291 +:107A70004FF44071E06802F0ACFA207910B16D1E4D +:107A8000FBD104E01DB1207880F0010070BD608959 +:107A9000401C6081E068FFF72BFE002070BD07B539 +:107AA00002AB0122FFF7C5FF0EBD70B5144C4FEAC3 +:107AB000400047F230556071A17100202072012111 +:107AC000617263612361E27121712070E0688188D5 +:107AD00089050ED40188C90505D401888905FCD41F +:107AE000012102F058FA01224FF44071E06802F0DF +:107AF00070FA207940B16D1EFBD10AE0000C014004 +:107B000090030020801A06001DB1207880F001004B +:107B100070BD6089401C6081E068FFF7E9FD0020CE +:107B200070BD2A48408970472DE9F84F4FF44067EF +:107B3000ADF800704FF0020A8DF803A01420DFF8B2 +:107B400090B08DF802006946584601F0D3FA204DF6 +:107B500010352F60DFF8789000262C1505F1040809 +:107B600009F1080902E00A2000F0CAFAD9F8000079 +:107B70004005F8D5C8F800400A2000F0C1FA2C6092 +:107B80000A2000F0BDFA761CF6B2082EEED34FF4B0 +:107B900000694646C8F800900A2000F0B1FA346047 +:107BA0000A2000F0ADFA2C600A2000F0A9FAC5F80E +:107BB0000090ADF800708DF803A01C208DF8020035 +:107BC0006946584601F096FABDE8F88F9003002008 +:107BD000000C014038B504466B4602221B21682088 +:107BE000FFF763FFBDF8000043F2903140BA08444C +:107BF0004FF48C71B0FBF1F02330208038BD1FB5FD +:107C0000044602AB06221D216820FFF74EFFBDF897 +:107C10000800214640BA02B2D01702EB90708010E3 +:107C2000ADF80000BDF80A0040BA02B2D01702EB6E +:107C300090708010ADF80200BDF80C0040BA02B29E +:107C4000D01702EB90708010ADF804002F484278F6 +:107C50006846FFF755F81FBD70B50446192000F0BF +:107C60005BFA002215216820FFF719FF10B90320E5 +:107C700000F0FCFA254D1621287840F01802682003 +:107C8000FFF70DFF002217216820FFF708FF0122F0 +:107C90003D216820FFF703FF01223E216820FFF706 +:107CA000FEFE002C00D06C7070BD70B504460D4611 +:107CB000192000F031FA002215216820FFF7EFFEAD +:107CC00000281CD012482060124860601248A06052 +:107CD0001248E0600D48622D12D004DC0A2D13D04A +:107CE000142D05D10EE0BC2D06D0B5F5807F01D056 +:107CF000032102E0002100E001210170012070BD9C +:107D00000221FAE70421F8E70521F6E7A80300209D +:107D1000597C0008FF7B0008D57B0008184492318D +:107D2000FEB5064614460D46684602F039FC0120B1 +:107D3000ADF804000021ADF80050ADF80610ADF824 +:107D40000810ADF802406946304602F079FBFEBDEE +:107D500070B51646D04A02EB0015D04A02EB00146B +:107D60000122206801F003FBD4E90101182200F090 +:107D700087F9217B3246206800F03FF9A07B18B1DB +:107D80000121206802F01EFC0121206802F010FC95 +:107D9000207B30B1042807D008280AD00C2806D14F +:107DA0000AE02068343001E0206838302860284636 +:107DB00070BD20683C30F9E720684030F6E72DE9D7 +:107DC000F0410546B4480F4600EB0516B348B271C2 +:107DD00000EB05142822D4E9010100F051F9217BC0 +:107DE00000222068FFF79CFF01224FF6FF7120461A +:107DF00001F0DAFA3A462946204601F09BFA30466D +:107E0000BDE8F08170B5A648002402894281018155 +:107E1000891A8BB240F68C218B4201D9C47070BD97 +:107E20009F49A3F2EF2540F2DB569E4AC978B5423E +:107E30001BD2082919D2984DE035042925F81130B4 +:107E400007D2C588AB4204D9012305798B402B4367 +:107E5000037103790F2B08D10471B2F90030142B90 +:107E600002DD143B138000E01480491CC1701480B3 +:107E700070BD70B5884A894B02EB001203EB00130A +:107E8000D47918681B7B8CB151811489824D091BF0 +:107E900091819479E03525F814100024D47122469C +:107EA0001946FFF73DFF7F48048070BD1181012115 +:107EB000D171BDE870400222194631E72DE9F04743 +:107EC0000446774DE1890020E980A17901B10220C3 +:107ED000617801B1401C7449DFF8D081002651F867 +:107EE00020704FF47A79BA5D02F00F0002F0F001D1 +:107EF000FF2A65D0A2781AB102285ED003285CD090 +:107F0000E2783AB1042858D0052856D0062854D033 +:107F1000072852D0E2790AB182424ED011F0300FD8 +:107F200002D0227802B90021227932B1A27922B995 +:107F3000082801D0092800D1802162792AB1A279CC +:107F40001AB9021F032A00D88021CA0605D50022CB +:107F50005749FFF734FF082008E08A0608D5AA78B9 +:107F60005449FFF72CFFA87800F10100A87024E025 +:107F70004A0612D52289B8FBF2F1A28989B202B968 +:107F80004A46FFF7E5FE0146434A2878F03242F8B8 +:107F9000201000F1010028700FE009060DD562895C +:107FA000B8FBF2F189B24A46FFF7D2FE0146424AD7 +:107FB000687842F82010401C6870761C0E2E92DB08 +:107FC0000020BDE8F087364A1278904205D23A4A3E +:107FD000303A52F82000006801807047304A5278E9 +:107FE000904204D2344A52F8200000680180704761 +:107FF0003149403931F8100070477FB506461546C3 +:108000000C46684602F0C2FA7020ADF8000001206C +:10801000ADF802000020ADF804000220ADF8080021 +:10802000C001ADF80650ADF80C0074B1042C15D0A9 +:10803000082C1CD00C2C07D16946304602F04CF9B4 +:108040000821304602F0E7FA7FBD6946304602F06B +:1080500098F80821304602F0C8FA7FBD69463046DC +:1080600002F0C4F80821304602F0C5FA7FBD694627 +:10807000304602F0F7F80821304602F0C6FA7FBD1C +:1080800008B5ADF800108DF8022002218DF803101C +:10809000694601F02FF808BD540F0020E4D2000813 +:1080A000AA030020D6000020A8D2000840420F00FA +:1080B000057E0008737E0008741000208048416827 +:1080C000491C4160704710B57D484FF0E02341687E +:1080D0009A694468A142FAD10368006803EB43043B +:1080E000C4EBC313C2EBC302B2FBF0F001EB4102DD +:1080F000C2EBC11100EBC10010BD71484068704770 +:1081000030B50546FFF7DFFF4FEA0004FFF7DBFF5E +:10811000001BA842FAD330BD30B504464FF47A753F +:1081200002E02846FFF7ECFF641EFAD230BD644936 +:10813000896808474FF4805108B1624801E06148FE +:10814000001F016070474FF4805110B15D48001F5F +:1081500000E05C48016070472DE9F04F8DB01822B7 +:108160005949684602F041FC032701F016FC012141 +:10817000564801F0A1FF012144F61D2001F093FFB4 +:108180000121084601F086FF01F0B1FF4FF6FF70B4 +:10819000ADF818004B484FF0000A8DF81AA006A958 +:1081A000143800F0A7FF06A9494800F0A3FF06A96C +:1081B000484800F09FFF4848416841F00071416025 +:1081C000464DDFF81C813E4E2968414501D14548A6 +:1081D00000E04548B0600020FFF7A9FF3C490820B7 +:1081E0001031086010200860A946002483466D46BF +:1081F000D9F80010414506D105EBC4008179142956 +:1082000001D180F806B005EBC401091D55F8340012 +:1082100000F070FF641CBC42EAD307A801F0F4FE32 +:1082200032490798B0FBF1F0306031484FF47A7171 +:108230000068B0FBF1F0B0F1807F0CD220F07F41FC +:108240004FF0E020491E41612A4AF0211170C0F828 +:1082500018A0072101612848FFF74AFA00F0C9FF7A +:108260006420FFF759FF0DB0BDE8F08F184A1021C8 +:10827000143211600821121F11600446151F40F2CC +:10828000DB104443286880F010002860286880F0E4 +:1082900008002860A01EFFF73FFF0120FFF747FFFF +:1082A0001920FFF739FF0020FFF741FFEAE710B17F +:1082B0001349124808600F4912481739086070477F +:1082C000B803002014080140B8D20008070040009D +:1082D000000C014000100140000001400C0400208F +:1082E000001BB700478100083581000840420F009D +:1082F0000804002023ED00E000580040EFBEADDE92 +:10830000F04F00200400FA057CB5FA4C0D46FA49FE +:108310002160A060A4F53070606100F58070A061FC +:108320004FF48070E0602061F4482063F34801213D +:1083300014386063880301F0B6FE02208DF8030054 +:108340000002ADF8000018208DF80200EC4EA807DE +:1083500003D56946304600F0CDFE4FF48060ADF89D +:10836000000048208DF80200E80703D06946304637 +:1083700000F0C0FE0E208DF8040001208DF80500ED +:108380008DF806008DF8070001A801F0B2FB204629 +:108390007CBD2DE9FC41D74C0D464C34D6492160BB +:1083A000A0608020E06040202061A4F586706061BC +:1083B0008030A061D3480121A064480401F07CFE14 +:1083C00002268DF803600420ADF8000018208DF817 +:1083D0000200CB4FA80703D56946384600F08AFE55 +:1083E0000820ADF8000048208DF80200E80703D00F +:1083F0006946384600F07EFE26208DF804000120F4 +:108400008DF805008DF806608DF8070001A801F0D1 +:1084100070FB2046BDE8FC812DE9F0438946064605 +:10842000B9490024B7488FB01D4617468E4204D183 +:1084300019461046FFF768FF05E0864204D1194649 +:108440001046FFF7A6FF04464FF00008C4F820804E +:10845000C4F81C80C4F82880C4F82C90C4F8248088 +:10846000A6642571A760ADF83080ADF834800B9715 +:10847000ADF83280ADF83880ADF83680E80702D02C +:108480000420ADF83600A80705D5BDF8360040F049 +:108490000800ADF836000BA9304602F0E3F80121E0 +:1084A000304602F037F9684601F074FC301D009048 +:1084B0004FF48050CDE909088020CDF81080CDE937 +:1084C00005084746CDF81C80E80723D0206BD8B1BB +:1084D000E068CDE902702020089060690190206B6F +:1084E00001F0CEFB6946206B01F037FC0121206BC7 +:1084F00001F05DFC01224021304602F02DF9206B95 +:1085000001F06AFC206405E0012240F2255130466A +:1085100002F00AF9A80724D5606BE0B12069039046 +:10852000102008970290606B01F0AAFB6946606B0F +:1085300001F013FC01220221606B01F043FC0021D9 +:10854000606B01F047FC606B476001228021304680 +:1085500002F002F905E0012240F22771304602F0F4 +:10856000E3F80FB02046BDE8F0837FB50446002055 +:10857000ADF80400ADF808000091ADF80600ADF8C4 +:108580000C00ADF80A0020790D46C00702D0042087 +:10859000ADF80A002079800705D5BDF80A0040F043 +:1085A0000800ADF80A006946A06C02F05BF8A5600F +:1085B0007FBD826A81691144426BD160D0E9092193 +:1085C00000238A4205D9511A426B5160416A816287 +:1085D00004E00269511A426B5160836280F84430B2 +:1085E000406B012101F0E3BB016B11B14968006CE4 +:1085F00001E01C3003C8814201D0012070470020F7 +:108600007047416B11B190F844007047243003C8A3 +:10861000814201D1012070470020704710B501460A +:10862000036BC268406943B10B6CD21A805C5B1E5D +:108630000B6401D1CA680A6410BD0B6AC05C5B1C84 +:10864000B3FBF2F402FB14320A6210BD436A826982 +:10865000D154416A0269491CB1FBF2F302FB1311C8 +:108660004162416B19B10968C90706D1A1E7806C65 +:10867000012240F2277102F057B8704710B51D4C27 +:108680004FF4005001F0ABFB0021606B01F08FFB59 +:10869000D4E90901884203D02046BDE8104088E7AC +:1086A000012084F8440010BD1249886C028812062B +:1086B0000ED5D1E909329A420BD08B699A5C82803F +:1086C000886A0A69401CB0FBF2F302FB130088625F +:1086D0007047002240F2277102F026B870B5054CB1 +:1086E0004C34A06C0588A9061CD58088E16A69B164 +:1086F000884717E054130020D0D2000858000240E9 +:10870000000801400044004000380140E26961690E +:108710008854E069E16800F10100B0FBF1F201FB6F +:108720001200E06128060FD5D4E9091088420CD068 +:10873000A169085CA16C8880A06A2169401CB0FB1B +:10874000F1F201FB1200A06270BDA06CBDE87040A8 +:10875000002240F2277101F0E7BF0000FEB52C4C6B +:108760000125207878B1012823D0022820D1642067 +:108770008DF8000027488DF8015000264078E0B3BE +:108780008DF802503CE07A208DF8000022486B46BC +:108790000222B0F90000FF21C0F1B40000EBD0705C +:1087A000C0F347008DF801006D20FFF742F92570F6 +:1087B000FEBD1A4E79208DF80000B6F900000A259A +:1087C00090FBF5F05A30B4220021FEF79BF98DF8AA +:1087D0000100B6F90200B42290FBF5F05A300021F6 +:1087E000FEF790F98DF802006B460322FF216D2001 +:1087F000FFF71FF902202070FEBDFFE78DF8026031 +:108800006B460322FF216D20FFF713F92670F3E773 +:10881000C40300208C0A0020B00100203400002096 +:108820001FB5044602AB062243216820FFF73DF93D +:10883000BDF80800214640BA02B2D01702EB907092 +:108840008010ADF80000BDF80A0040BA02B2D0179F +:1088500002EB90708010ADF80200BDF80C0040BA39 +:1088600002B2D01702EB90708010ADF804007C4883 +:1088700042786846FEF744FA1FBD38B504464FF407 +:108880000050ADF8000002208DF8030004208DF8A0 +:108890000200744874490068884202D169467348EE +:1088A00004E07349884203D16946724800F022FC13 +:1088B00080226B216820FFF7F2F80520FFF72CFCDF +:1088C000002219216820FFF7EAF803226B216820B3 +:1088D000FFF7E5F8022237216820FFF7E0F8604D46 +:1088E0001A2168202A78FFF7DAF818221B2168205D +:1088F000FFF7D5F810221C216820FFF7D0F8002CD4 +:1089000000D06C7038BD1FB5044602AB06223B2177 +:108910006820FFF7CAF8BDF80800214640BAADF854 +:108920000000BDF80A0040BAADF80200BDF80C0026 +:1089300040BAADF804004A4882786846FEF7E0F98C +:108940001FBD47494C4ACB7813B14FF4FF6301E098 +:108950004FF480531380002800D0887070472DE9B1 +:10896000FE4F8146984692460D462320FFF7D4FBE2 +:108970006B46012275216820FFF797F8002804D084 +:108980009DF80000682802D00020BDE8FE8F062276 +:1089900001AB11466820FFF788F89DF809009DF8A3 +:1089A0000710C007400F01F0010140EA41009DF8A7 +:1089B00005102B4C01F0010108434FF001064FF068 +:1089C000000704D0012833D002280DD02CE06B46DC +:1089D00001220C216820FFF768F89DF8000010F0D4 +:1089E0000F0021D0042823D0E7702449C9F80010D3 +:1089F00023492448C9F804102860234868602348A4 +:108A0000E860B8F1000F02D0E17888F80010504615 +:108A1000BAF1620F19D00DDC05281ED00A281AD031 +:108A2000BAF1140F0BD114E00520FFF71FFCDCE7AF +:108A3000E670DAE7BC2806D0BAF5807F01D00320C3 +:108A400004E0277003E0267001E00220207001207E +:108A50009BE70420FAE70520F8E70620F6E7000088 +:108A6000C50300200C04002000127A00000C014015 +:108A7000001BB7000010014082010020438900085C +:108A8000078900087B880008218800081944923172 +:108A90001FB5044602AB062201211C20FFF705F892 +:108AA000BDF80800214640BA40F38D02D01702EB12 +:108AB00090708010ADF80000BDF80A0040BA40F395 +:108AC0008D02D01702EB90708010ADF80200BDF857 +:108AD0000C0040BA40F38D02D01702EB907080106A +:108AE000ADF80400334802786846FEF709F91FBD67 +:108AF00038B504462020ADF8000002208DF80300B0 +:108B000004208DF8020069462B4800F0F3FA002299 +:108B10002A211C20FEF7C3FF02220E211C20FEF793 +:108B2000BEFF03220F211C20FEF7B9FF12222B21CA +:108B30001C20FEF7B4FF02222C211C20FEF7AFFF01 +:108B400001222D211C20FEF7AAFF00222E211C202D +:108B5000FEF7A5FF05222A211C20FEF7A0FF1749DA +:108B60004FF48070002C088001D01248047038BD8A +:108B700038B5044600208DF80000114811490068FE +:108B800088420CD06B4601220D211C20FEF78DFF80 +:108B900028B19DF800002A2803D01A2801D000200F +:108BA00038BD0949216009496160024948700120C6 +:108BB00038BD0000C90300200008014082010020E8 +:108BC0000C040020001BB700F18A0008918A0008FD +:108BD000434810B50068434CA188084203D0FFF712 +:108BE00072FAA0600AE0FFF76EFAA168884205D920 +:108BF000401A3B2190FBF1F061690860E068BDE834 +:108C0000104001F03FB9E3E7E2E7FEB50125354C3E +:108C1000022110B1012810D109E04FF4807060806A +:108C20004000A080E06009202070172004E06580EB +:108C3000A180E1602570072060706088ADF80000B9 +:108C40001026274F8DF802608DF80310083F694603 +:108C5000384600F04FFAA088ADF8000004208DF8E7 +:108C600002006946384600F045FA2178012000F0FC +:108C700077FAE06801F006F9E068019000208DF8CD +:108C800008008DF809608DF80A5001A801F0B6F8C7 +:108C900094F9010000F01F018D4040094FF0E021E0 +:108CA00001EB8000C0F80051FFF727FA3C38206143 +:108CB000FEBD70B50546FFF720FA0A4C21693C312C +:108CC00088420CD3C4E9040505496088083108606E +:108CD0000B20FFF715FA024960880C31086070BD5F +:108CE000080C0140CC0300201FB5044602AB06224D +:108CF000A8216820FEF7D9FEBDF80800214640BA39 +:108D000002B2D01702EB90708010ADF80000BDF8F1 +:108D10000A0040BA02B2D01702EB90708010ADF892 +:108D20000200BDF80C0040BA02B2D01702EB9070FE +:108D30008010ADF80400264842786846FDF7E0FF51 +:108D40001FBD70B504466420FFF7E6F9F022232129 +:108D50006820FEF7A4FE10B90320FFF787FA05206C +:108D6000FFF7DAF91A4D2021287840F00F02682029 +:108D7000FEF795FE002C00D06C7070BD38B504462F +:108D80000D461920FFF7C8F96B4601220F21682014 +:108D9000FEF78BFE9DF80000D32801D0002038BDDF +:108DA0000C4820600C4860600C48E0600848362D94 +:108DB00005D04E2D07D05D2D07D0002100E04021C9 +:108DC0000170012038BD8021FAE7C021F8E70000DA +:108DD000E4030020438D0008E98C0008DDE9A73199 +:108DE0002DE9F04FB74C83468E46608926890102F3 +:108DF000B5484FF0000A4068421AA6FB027CA088E2 +:108E00004FEAE2754FEA10414FEA00430AFB02C005 +:108E100006FB05064FEAD71040EA466013EB00094F +:108E200041EBE611E6886388A6FB02C84FEA53408F +:108E30004FEAC3370AFB028306FB05364FEA1C23C1 +:108E400043EA0663FB1840EB2620A689A6FB027CBA +:108E50000AFB02C206FB05244FEAD75242EA44222B +:108E60004FF4FA654FEAE454521944F10004A24663 +:108E7000551B74F1000448DA944D5519A5FB05679C +:108E80004AF1FF3404FB057705FB047C0525A6FBAE +:108E900005480CFB0585002706FB07556F104FEAB8 +:108EA000340CB9EB0C0961EB0701A40844EA8574A2 +:108EB0001B1B60EBA500864D551B7AF1FF3424DAAD +:108EC00040F2DC555619A6FB06474AF1000505FBA2 +:108ED000067706FB05750726A4FB06C805FB068674 +:108EE000002704FB0767B9EB0C0961EB07010B27AF +:108EF000A4FB07C805FB0785002604FB0654641085 +:108F00004FEA3C055B1B60EB04006F4CA568002436 +:108F1000A5FB036704FB037305FB0030740D44EAF3 +:108F2000C0244015B4EB090360EB0100410441EAA1 +:108F3000D330BBF1000F01D0CBF80000BEF1000F21 +:108F400001D0CEF80020BDE8F08F10B500F072F827 +:108F50005D49886010BD5C48012200784030C1B294 +:108F60007720FEF79CBD10B500F064F856494860C4 +:108F700010BD5548012200785030C1B27720FEF76D +:108F80008EBD2DE9FE43054652485349006888428C +:108F90000FD04FF40054ADF8004002208DF80300CC +:108FA00010204E4E8DF802006946304600F0A2F8BF +:108FB00074610A20FFF7B0F801AB0122A0217720ED +:108FC000FEF773FD002823D001221E217720FEF733 +:108FD00066FD4FF42F60FFF793F80024DFF8E4807C +:108FE0002646A02707EB4400C1B202AB022277203D +:108FF0000296FEF75AFDBDF8080040BA28F81400A2 +:10900000641C082CEEDB2F4800F026F810B100207D +:10901000BDE8FE8342F210702880688030486860A6 +:109020003048A8603048E8603048286130486861BE +:109030000120EDE708B56B46032200217720FEF7FB +:1090400034FD9DF800009DF80110000440EA012065 +:109050009DF80210084308BDF0B5C289002102F452 +:109060007F4502F00F040123C5810A4630F81260E3 +:1090700006B10023521C082AF8DB4FF0FF36F3B983 +:109080000022D30722F0010302D0C35C594002E062 +:10909000C35A81EA132108230F0401D581F4C0517A +:1090A00049005B1E002BF7DC521C102AE9DB25432C +:1090B000C581C1F30330844201D10020F0BD3046A8 +:1090C000F0BD0000EC130020E803002030F8FFFFA3 +:1090D00024FAFFFF0C040020001BB7000010014021 +:1090E000738F0008678F0008578F00084B8F0008A8 +:1090F000E18D0008F0B500234FF0010C0A880CFA4E +:1091000003F52A4228D04FEAD30200EB82064FEA49 +:10911000437491F802E04FEAD46734680EF00F020E +:109120005FEACE6E03D591F803E04EEA02024FF0FB +:109130000F0E0EFA07FE24EA0E04BA4022433260F4 +:109140008A78282A02D0482A03D005E0C268AA43B8 +:1091500001E0C2682A43C2605B1C102BCED3F0BD75 +:1091600010B58A0721F003040649130F21440F228A +:109170008C689A4094438C608A68984002438A6065 +:1091800010BD0000000001404FF4805108B14E486E +:1091900001E04D48001F016070472DE9F041044691 +:1091A0004A4817460D460088484E0C3E1CE015B153 +:1091B00015F8010B00E0FF2080460221304601F047 +:1091C000D9FB0028F9D04146304601F0CFFB012100 +:1091D000304601F0CFFB0028F9D0304601F0C8FB43 +:1091E000C0B20CB104F8010B7F1EE0D20120BDE833 +:1091F000F081F0B501218C0389B0204600F05CFFBE +:109200000121204600F06AFF18208DF816004FF467 +:109210002040ADF814002C4E03208DF81700143EAA +:1092200005A93046FFF766FFADF8144004208DF81D +:10923000160005A93046FFF75DFFA010ADF8140039 +:1092400010258DF8165005A93046FFF753FF1F4E25 +:109250000C3E304601F040FB4FF48270ADF8020046 +:1092600068010024ADF80A000720ADF81000ADF841 +:1092700004400220ADF80E40ADF806000127ADF81D +:109280000040ADF80870ADF80C506946304601F06A +:1092900047FB0121304601F05FFB0DA000680690FE +:1092A0000120FFF771FF042206A907A8FFF775FF49 +:1092B0000020FFF769FF9DF81D00EF2802D020462F +:1092C00009B0F0BD3846FBE7140C01400C380040F3 +:1092D0009F0000002DE9F04180461D4616460C46D1 +:1092E000084600F0E7F80746404600F0D8F807EBDC +:1092F0008000C0B2102805D2734901EB00108560D0 +:1093000004710673BDE8F08151B104290BD008291E +:109310000CD00C290DD101225FF0100101F05DB9D4 +:1093200001220221FAE701220421F7E701220821A4 +:10933000F4E7704770B50D460446017B134600689C +:109340002A46FFF7C7FF217B2068BDE87040DBE7B6 +:1093500008B58DF8000000208DF8010001208DF87F +:1093600002008DF80300684600F0C3FB08BDFEB59F +:10937000064614460D46684601F0FFF853486D1E38 +:1093800044435348ADF8045069460068B0FBF4F01C +:10939000401EADF800000020ADF80600ADF8020058 +:1093A000304600F0B5FEFEBD10B504460068FFF77C +:1093B000DEFF0121206801F0FBF8607BBDE8104072 +:1093C000C6E770B50546084600F074F8044628461E +:1093D00000F065F804EB80003B49C0B201EB0010DF +:1093E00070BD70B50546022101F028F9012825D08D +:1093F0000421284601F022F901282CD00821284612 +:1094000001F01CF9012833D01021284601F016F98B +:1094100001283AD11021284601F01CF90C212846D8 +:10942000FFF7CFFF0446284601F005F9A268014680 +:10943000002A2AD0207BBDE8704010470221284630 +:1094400001F008F900212846FFF7BBFF0446284633 +:1094500001F0EBF8EAE70421284601F0FBF80421CB +:109460002846FFF7AEFF0446284601F0E0F8DDE7A6 +:109470000821284601F0EEF808212846FFF7A1FF51 +:109480000446284601F0D5F8D0E770BD1148A8E79A +:109490004FF08040A5E71048A3E71048A1E7014638 +:1094A00000200F4A01E0401CC0B252F820308B422D +:1094B000F9D17047014600200A4A01E0401CC0B2C1 +:1094C000135C8B42FAD17047FC13002040420F001E +:1094D00008040020002C0140000400400008004067 +:1094E000F4030020C4D30008016B4A6892688968BD +:1094F0000A4290F8441204D00020002900D1012033 +:10950000704701200029FBD100207047D0F834318A +:1095100001299A685B6801D021B107E090F8440204 +:1095200030B103E090F84402012801D05A6170473D +:109530001A6170470189406889B2482200F052B927 +:1095400070B5044601EB4100AC491646B1FBF0F0A2 +:1095500081B21D4603222046FFF726FF2A463146E8 +:109560002046BDE87040FFF7E5BE0189406889B23A +:10957000102200F037B900B50346032083F83C02FF +:109580001846FFF7B1FF30B1B3F8400293F8391233 +:109590000843A3F8400293F83902400083F83902E7 +:1095A00093F83E02401E10F0FF0083F83E0205D102 +:1095B000012083F83802022083F83C0200BDC26813 +:1095C000016A521E914201D3002100E0491C016250 +:1095D000704710B50124034680F83C42FFF784FF32 +:1095E00001280FD1002083F8380283F83A4293F81B +:1095F0004002A3F840021A6A59698854BDE8104035 +:109600001846DCE710BD00B50346FFF76DFF0121EA +:1096100001280BD003F23A2300201870D8800420D0 +:1096200098700820187103F8011C00BD83F83C12E3 +:1096300000BD90F83C12491E11F0FF0180F83C1269 +:1096400008D190F83A1201B1DDE790F8381201B173 +:10965000BFE790E77047D0E90910814201D10120AE +:1096600070470020704730B5044690F83B02002553 +:10967000F8B194F83D02401E10F0FF0084F83D025E +:1096800016D1B4F8420200F001014008A4F84202E9 +:109690002046FFF73BFF032084F83D0294F83F0289 +:1096A000401E10F0FF0084F83F0201D184F83B52C5 +:1096B00030BD2046FFF7CFFF0028F9D1A16AA2698B +:1096C000481CA062515C2269904200D3A5624FF40D +:1096D000007004F23B2440EA4100A4F807000A208D +:1096E00020710120A070207030BD00EBC00101EBA3 +:1096F000801010B5424901EBC0042046FFF7B3FFCC +:109700002046BDE8104094E770B53D4C06463D4804 +:10971000206003202071A66084F844123A48206338 +:109720001030C4F83401002504F134012562616170 +:109730004FF48070E060206104F59C71C4E9061567 +:10974000A562656284F83B52012084F83A0284F8ED +:10975000385284F83C02206BFFF7ECFED4F8340159 +:10976000FFF703FF01212046FFF7D0FE3220FEF76E +:10977000D3FCAFF289032A463146206BBDE8704026 +:10978000DEE6D0E90721914202D14FF00000704798 +:1097900002D9A1EB020003E0C0680844A0EB02007C +:1097A000C0B2704700B50346FFF7EBFF00280BD0AF +:1097B0005969D869095CDA68521E904201D2401C8E +:1097C00000E00020D861084600BD436A8269D15498 +:1097D000416A0269491CB1FBF2F302FB13114162B9 +:1097E0007047704708B5ADF800108DF802200221CF +:1097F0008DF803106946FFF77DFC08BDC0C62D003B +:10980000FC140020C8D3000824D300081FB5044668 +:1098100002AB062202211820FEF747F99DF8080046 +:109820009DF80910800800EB0120ADF800009DF8BC +:109830000A009DF80B10800800EB0120ADF8020033 +:109840009DF80C009DF80D10800800EB0120ADF88C +:1098500004001A48214602786846FDF751FA1FBDF8 +:1098600010B5044608220F211820FEF718F90E2221 +:1098700010211820FEF713F911494FF48050002CE5 +:10988000088001D00D48047010BD38B50446002092 +:109890008DF8000001466B4601221820FEF705F9FD +:1098A00018B19DF80000FB2801D0002038BD054804 +:1098B000206005486060012038BD000004040020DD +:1098C00082010020619800080D9800080268126863 +:1098D000104770B50C46054603E02A682846126812 +:1098E000904714F8011B0029F7D170BD0168496841 +:1098F00008470168896808470268D268104701680C +:10990000096908476E48016841F00101016041683A +:109910006C4A1140416001686B4A11400160016866 +:1099200021F480210160416821F4FE0141604FF47F +:109930001F0181606549C00308607047604A10B527 +:109940005068634B10F00C01624803D0042903D027 +:10995000082903D0036016E0416813E0516853689A +:1099600001F470114FF0020413F4803F04EB9141B5 +:1099700006D053689B03436800D55B084B43E9E777 +:10998000554B594301605168524AC1F303110832E3 +:10999000515C0268CA40026010BD3EB400210091D3 +:1099A0004FF4E01301914648CDE901314B4A046878 +:1099B00044F480340460846944F0100484614FF4FA +:1099C000A064056805F400350195009D6D1C0095A7 +:1099D000019D15B9009DA542F3D10568AD0301D5E0 +:1099E000022114E0056845F0010505600091016859 +:1099F00001F0020101910099491C0091019911B9EE +:109A00000099A142F3D10168890739D5012102915A +:109A100033490C6844F010040C600C6824F0030413 +:109A20000C600C6844F002040C60416841604168BD +:109A30004160416841F480614160116821F07041EA +:109A40001160244C22496160416821F47C1141601D +:109A5000116841F0004111602049091FCA6822F4D1 +:109A60000042CA608968090403D51E494FF4801377 +:109A7000616002990193012908D002290AD100E00E +:109A8000FEE7416843F48032114302E0416841F44B +:109A900060114160016841F08071016001688901D5 +:109AA000FCD5416821F003014160416841F00201A9 +:109AB00041604168C1F381010229FAD13EBC3DE712 +:109AC000001002400000FFF8FFFFF6FE08ED00E086 +:109AD00000127A000804002000093D000410014033 +:109AE00000200240001BB7001849084318490860CD +:109AF0007047F0B50F21C478027801234FF0E026BB +:109B0000DCB1134C2468457804F4E064C4F5E064E7 +:109B1000240AC4F10407E1408478BD400C402C4382 +:109B200021010C4C1155007800F01F018B404009B9 +:109B300006EB8000C0F80031F0BD02F01F0083404A +:109B4000500906EB8000C0F88031F0BD0000FA0536 +:109B50000CED00E000E400E010B54268464B0C79E3 +:109B60001A400B6842EA0422134343608368434A65 +:109B70001340D1E9024222434C7943EA44031A4399 +:109B80008260C26A097C22F47002491EC9B242EAAC +:109B90000151C16210BD0029816802D041F001016C +:109BA00001E021F00101816070470029816802D045 +:109BB00041F4807101E021F4807181607047816817 +:109BC00041F008018160704701460020896809075B +:109BD00000D501207047816841F004018160704721 +:109BE000014600208968490700D5012070470029F7 +:109BF000816802D041F4A00101E021F4A00181605C +:109C0000704770B5072409290AD9C568A1F10A0669 +:109C100006EB4606B440A543B3401D43C56007E0CC +:109C2000056901EB4106B440A543B3401D430561FE +:109C30001F23072A09D2446B521E02EB8202934073 +:109C40009C4391400C43446370BD0D2A09D2046BC0 +:109C5000D21F02EB820293409C4391400C43046369 +:109C600070BDC46A0D3A02EB820293409C4391405E +:109C70000C43C46270BD0000FFFEF0FFFDF7F1FF72 +:109C800001684FF6FE7211400160002101604160E1 +:109C90008160C1605749574A0839904203D14868EA +:109CA00040F00F0006E0534A1432904204D1486855 +:109CB00040F0F000486070474E4A2832904203D18D +:109CC000486840F47060F5E74A4A3C32904203D15C +:109CD000486840F47040EDE7464A5032904203D164 +:109CE000486840F47020E5E7424A6432904203D16C +:109CF000486840F47000DDE73E4A7832904203D174 +:109D0000486840F07060D5E73B4A111F904203D18C +:109D1000086840F00F0006E0374A1432904204D140 +:109D2000086840F0F00008607047334A28329042DB +:109D300003D1086840F47060F5E72F4A3C32904246 +:109D400003D1086840F47040EDE72B4A503290424E +:109D5000EAD1086840F47020E5E730B5036847F6BB +:109D6000F07293430C6A8A682243D1E904452C437C +:109D700022438C692243CC6922434C6A22438C6A79 +:109D800022431A430260CA6842600A6882604968D6 +:109D9000C16030BD0021016041608160C16001612E +:109DA00041618161C1610162416281627047002944 +:109DB000016802D041F0010102E04FF6FE7211404D +:109DC00001607047002A026801D00A4300E08A431C +:109DD0000260704741607047406880B27047C100C0 +:109DE00003D50549091F08607047024908394860D2 +:109DF00070470000080002400804024030B52349C3 +:109E00008379026853B30B6893430B600A1D136890 +:109E10000468A343136002790A4413680468234367 +:109E200013601A4A083213680468A3431360131DB1 +:109E30001C680568AC431C604479102C05D0214493 +:109E40000A68006802430A6030BD11680468214353 +:109E50001160196800680143196030BD0079084439 +:109E600001689143016030BD084A01460020126834 +:109E7000064B0A4014331B680B4202D0002A00D064 +:109E80000120704701491431086070470004014007 +:109E90005A4910B588424FF0010101D14C0501E04B +:109EA0004FF48004204600F019F92046BDE8104028 +:109EB000002100F013B970B50446808886B00D46C5 +:109EC00020F03F06684600F09FF84D490298B0FB2D +:109ED000F1F189B20E43A680228822F0010222808D +:109EE000484B2A689A421CD85200B0FBF2F080B26C +:109EF000042800D20420491C2184A083208840F03B +:109F00000100208021884FF6F5300140A8886A8939 +:109F1000104308432080A88929890843208106B07E +:109F200070BDEB88A3F53F46FF3E05D102EB420230 +:109F3000B0FBF2F080B208E002EBC20303EB0212C6 +:109F4000B0FBF2F080B240F48040020501D140F055 +:109F500001004FF4967251434FF47A72B1FBF2F163 +:109F600040F40040C7E741F2883101600021818060 +:109F70004BF6FF72C280018141814FF480418181A3 +:109F800070470029018802D041F0010101E021F071 +:109F90000101018070470029018802D041F48071DD +:109FA00001E021F48071018070470029018802D00E +:109FB00041F4007101E021F4007101807047002933 +:109FC000018802D041F4806101E021F480610180C8 +:109FD0007047002A828801D00A4300E08A438280C9 +:109FE000704701827047008AC0B2704712B141F0D9 +:109FF000010101E001F0FE010182704700540040C0 +:10A0000040420F00A086010030B53C494A683C4BF5 +:10A0100012F00C0405D03B4A042C126803D0082C23 +:10A0200024D0036000E002604A680F2303EA1212A2 +:10A03000354B9C5C0268E24042604C68072505EAAB +:10A0400014241C5D22FA04F484604C6805EAD424CC +:10A050001B5DDA40C2604968032303EA91312A4B51 +:10A060001B1F595CB2FBF1F1016130BD4B684C68BC +:10A0700003F470134FF0020514F4803F05EB934393 +:10A0800005D04C68A40300D552085A43CBE71F4AB9 +:10A090005343C6E7194A0029516901D0014300E042 +:10A0A000814351617047154A0029916901D00143EC +:10A0B00000E0814391617047104A0029D16901D0C5 +:10A0C000014300E08143D16170470C4A0029D16807 +:10A0D00001D0014300E08143D1607047074A002965 +:10A0E000116901D0014300E08143116170470348C9 +:10A0F000416A41F0807141627047000000100240E7 +:10A1000000127A000C0400202404002000093D0005 +:10A1100030B50288FD4BFE4C98420DD0A0420BD0CA +:10A12000B0F1804F08D0FB4DA84205D0FA4DA842AF +:10A1300002D0FA4DA84203D122F070054A882A4382 +:10A14000F74DA84206D0F74DA84203D022F440753F +:10A15000CA882A4302808A8882850A8802859842B2 +:10A160000AD0A04208D0F04A904205D0EF4A90426F +:10A1700002D0EF4A904201D1097A01860121818201 +:10A1800030BD30B5028C22F001020284028C83883B +:10A19000048B22F0020224F073050C882C430D89F5 +:10A1A00015434A882A43D94DA8420BD0D84DA8421E +:10A1B00008D0DD4DA84205D0DC4DA84202D0DC4DD0 +:10A1C000A8420DD122F008054A8923F440732A439E +:10A1D00022F004058A882A438D891D43CB892B43AD +:10A1E00083800483C9888186028430BD70B5028C67 +:10A1F00022F010020284028C8488038B0D8823F4E1 +:10A20000E6464FF6FF7303EA052535430E8922F033 +:10A21000200203EA061616434A8803EA0212324372 +:10A22000BA4EB04202D0BA4EB04215D122F08006EA +:10A230004A8924F4406403EA0212324322F04006C1 +:10A240008A8803EA021232438E8903EA860626438D +:10A25000CC8903EA8404344384800583C988018758 +:10A26000028470BD70B5028C22F480720284028C6C +:10A270008488838B0D8823F073031D4322F40073BD +:10A280000E894FF6FF7202EA06261E434B8802EA49 +:10A29000032333439D4EB04202D09D4EB04215D1B0 +:10A2A00023F400664B8924F4405402EA0323334329 +:10A2B00023F480668B8802EA032333438E8902EA03 +:10A2C00006162643CC8902EA04143443848085832D +:10A2D000C9888187038470BD70B5028C22F48052D6 +:10A2E0000284048C8288838B0D8823F4E6464FF623 +:10A2F000FF7303EA0525354324F400560C8903EA6D +:10A30000043434434E8803EA063626437F4CA04289 +:10A3100002D07F4CA04205D122F480448A8903EA0E +:10A320008212224382808583C988A0F84010068467 +:10A3300070BD828B22F440628283828B4FF6FF7362 +:10A3400003EA01210A4382837047828B22F00C02C8 +:10A350008283828B0A4382837047028B22F440629D +:10A360000283028B4FF6FF7303EA01210A43028343 +:10A370007047F0B5048C24F010040484078B048C1F +:10A380004FF6FF7527F4734705EA03333B4305EAAD +:10A3900002221A435D4B05EA011698420ED05C4B2F +:10A3A00098420BD0B0F1804F08D05A4B984205D05C +:10A3B000594B984202D0594B984205D124F02001C4 +:10A3C000314341F0100104E024F0A0030B4343F0BB +:10A3D000100102830184F0BD028B22F00C02028383 +:10A3E000028B0A430283704770B5048C24F0010489 +:10A3F0000484058B048C4FF6FF7606EA031313439F +:10A4000025F0F305414A2B4390420ED0404A90423A +:10A410000BD0B0F1804F08D03E4A904205D03E4A62 +:10A42000904202D03D4A904202D124F0020201E063 +:10A4300024F00A020A4342F001010383018470BD43 +:10A440002DE9F05F0D4604460888304FDFF8C0C0A4 +:10A45000DFF8C0804988AA882B894FF0804960B313 +:10A46000042832D04FF6FF7E082836D0208C9B4639 +:10A4700020F480502084A38B268C704600EA0222B0 +:10A4800023F473431A4300EA0B3010430EEA013EF3 +:10A49000BC420BD0644509D04C4507D0444505D09B +:10A4A0001D4A944202D01D4B9C425AD126F40051C1 +:10A4B00041EA0E0141F4805158E02046FFF794FF35 +:10A4C000E9882046BDE8F05F86E72046FFF751FFA8 +:10A4D000E9882046BDE8F05F3FE7208C20F48070DB +:10A4E0002084B4F81CA0208C0EEA031313432AF036 +:10A4F000F30A0EEA012B43EA0A03BC4220D064456A +:10A500001ED04C451CD044451AD013E0002C01400D +:10A51000003401400004004000080040000C0040EE +:10A520000010004000140040004001400044014081 +:10A5300000480140494A944202D0494A944204D119 +:10A5400020F4007040EA0B0002E020F42060084391 +:10A5500040F48070A3832084E9882046BDE8F05F42 +:10A56000F3E626F402420A4342F48051A0832046D7 +:10A570002184E988BDE8F05FDBE64FF6FF7181805A +:10A5800000210180C180418001727047002101805B +:10A5900041808180C180018141818181C181704779 +:10A5A00000210180418001228280C18001817047A9 +:10A5B0000029018802D041F0010101E021F00101F0 +:10A5C00001807047002930F8441F02D041F4004157 +:10A5D00001E0C1F30E0101807047002A828901D099 +:10A5E0000A4300E08A4382817047028B22F008020E +:10A5F0000A4302837047028B4FF6FF7322F4006216 +:10A6000003EA0121114301837047828B22F0080283 +:10A610000A4382837047828B4FF6FF7322F40062F5 +:10A6200003EA0121114381837047808E7047008FB8 +:10A630007047808F7047B0F8400070470246002096 +:10A64000138A92890B4202EA010202D0002A00D04A +:10A6500001207047C9430182704700000008004094 +:10A66000000C004030B50446008A85B00D464CF61B +:10A67000FF710840E98801432182A1894EF6F31059 +:10A680000140A8882A8910436A890A431043A0819F +:10A69000A08A4FF6FF410840A9890143A18268467C +:10A6A000FFF7B2FC3048844201D1039800E00298E1 +:10A6B000A1890904002900EBC00101EB0010296801 +:10A6C00002DA4FEA410101E04FEA8101B0FBF1F00B +:10A6D0006422B0FBF2F14FEA01114FEA11136FF05F +:10A6E00018056B4300EB8300A3891D044FF0320370 +:10A6F00006D503EBC000B0FBF2F000F0070005E068 +:10A7000003EB0010B0FBF2F000F00F0008432081D3 +:10A7100005B030BD0029818902D041F4005101E02B +:10A7200021F400518181704710B5C1F3421301F04B +:10A730001F040121A140012B07D0022B07D01430A8 +:10A74000002A026805D00A4304E00C30F8E7103014 +:10A75000F6E78A43026010BD002A828A01D00A43CC +:10A7600000E08A4382827047003801403948384906 +:10A7700041603949416070473648016941F08001C4 +:10A780000161704733490420CA68D20701D0012013 +:10A790007047CA68520701D502207047C968C906C8 +:10A7A000FBD50320704700B50346FFF7EBFF02E03F +:10A7B000FFF7E8FF5B1E012803D0002B00D1052026 +:10A7C00000BD002BF4D1FAE770B505464FF43026F2 +:10A7D0003046FFF7E8FF042811D11E4C206940F0F5 +:10A7E000020020616561206940F040002061304630 +:10A7F000FFF7D9FF216941F6FD721140216170BD5B +:10A80000F8B5064600204FF4005C00900D46604607 +:10A81000FFF7C9FF042816D10E4C206940F0010053 +:10A82000206135806046FFF7BEFF41F6FE770428C1 +:10A8300006D1B61C280C009630806046FFF7B3FFA7 +:10A84000216939402161F8BD0249C86070470000A4 +:10A850002301674500200240AB89EFCD144815491C +:10A86000026800608A4203D01348804713480047BB +:10A87000134E4FF0090030601248016821F07061FA +:10A88000016041020160104C182020600F491048FF +:10A8900008601048D0F800D040680047FEE7FEE7A7 +:10A8A000FEE7FEE7FEE7FEE7FEE7FEE7FEE7FEE780 +:10A8B000F04F0020EFBEADDE05990008ED00000866 +:10A8C0001810024004000140140C0140000C01402B +:10A8D0004434434400F0FF1F2A4910B588420AD18E +:10A8E000841401212046FFF7F0FB2046BDE810400C +:10A8F0000021FFF7EABB2449884202D10121041458 +:10A9000004E0224988420AD10121C4132046FFF7FE +:10A91000E5FB2046BDE810400021FFF7DFBB10BD7E +:10A9200030B502884C8802F441530A88CD8822430E +:10A930008C882C4322430C8922434C8922438C89E6 +:10A940002243CC8922431A430280828B22F4006284 +:10A950008283098A018230BD0029018802D041F03A +:10A96000400101E021F04001018070478181704782 +:10A97000808970470246002012890A4200D00120D7 +:10A98000704700000030014000380040003C0040AB +:10A9900000487047A0D50008A0F16101192900D82E +:10A9A000203870472DE9F05F994615460F468346DB +:10A9B0004FF0FF36DDF828A011E0A819441009FB7C +:10A9C000047080460146584652469047002802D0FF +:10A9D00004DA254603E04046BDE8F09F2646A5EB95 +:10A9E00006000128E9DC0020F6E740EA01039B07A6 +:10A9F00003D009E008C9121F08C0042AFAD203E0F4 +:10AA000011F8013B00F8013B521EF9D27047D2B257 +:10AA100001E000F8012B491EFBD270470022F6E747 +:10AA200010B513460A4604461946FFF7F0FF2046C4 +:10AA300010BD421E12F8013F002BFBD111F8013B63 +:10AA400002F8013B002BF9D1704730B505462A4684 +:10AA50000B4612F8010B13F8014B08B1A042F8D0D5 +:10AA60001CB1002802D06D1CF1E7284630BD10B59E +:10AA7000044604E00B7800F8013B03B1491C521E68 +:10AA8000F8D2204610BDCAB2401E10F8011F8A42FB +:10AA900002D00029F9D100207047421C10F8011B98 +:10AAA0000029FBD1801A704770B50F4D00B9286896 +:10AAB000002412E00A4602E09E4203D0521C1378A2 +:10AAC000002BF9D1DAB2224305D02BB124B10021F9 +:10AAD00000F8011B04E00446401C0678002EE9D172 +:10AAE0002860204670BD0000340400202DE9F041AC +:10AAF0000546002090460E46044600E0641C44458E +:10AB00000BD2285D00F058F90746305D00F054F98B +:10AB1000381A02D1295D0029F0D1BDE8F08170B565 +:10AB2000064600F059FC046805460A22002130461A +:10AB300000F048F92C6070BDF0B480EA0102D40F37 +:10AB40004200B2EB410F02D20246084611464A00CB +:10AB500042D0C30DDDB2C1F3C752AD1A202D35DA94 +:10AB6000C1F3160141F4000204B15242C5F12006BE +:10AB700002FA06F12A411044B3EBD05F23D0C4B1EE +:10AB8000012DA0EBC35009DCF0BC4FF0004202EAFB +:10AB9000C35200F50000DBB200F055B9400000F1EF +:10ABA000807000EBC350A0F1807040EAD170490082 +:10ABB00009E0490841EAC071A0EBC35000F500006C +:10ABC000400800EBC350F0BC00F034B961420122F0 +:10ABD00002EB4101001BF6E7F0BC704781F0004139 +:10ABE000AAE780F00040A7E780EA010210B502F072 +:10ABF0000043400026D04A0023D04FEA106101EB09 +:10AC00001261C0F35600C2F3560240F4000042F451 +:10AC10000002A0FB0220A1F17F014FEA00401404D2 +:10AC200001D000F1010050EA124001D44000491E59 +:10AC3000C2B20C0604EBD010401C4008802A02D09F +:10AC400003E0002010BD20F00100002900DA002000 +:10AC5000184310BD30B480EA010202F0004530F024 +:10AC6000004221F0004015D0A0B1C0F3C753C2F399 +:10AC7000C754C2F31601C0F31600E41A41F40001F0 +:10AC800040F400027D34914201D3641C00E049008D +:10AC9000002C02DA30BC002070474FF40000002383 +:10ACA000914201D3891A034340084FEA4101F7D189 +:10ACB00051B1914202D14FF0004105E002D24FF074 +:10ACC000010101E06FF0010103EBC450284430BCE6 +:10ACD00000F0B0B8420005D0C0F3C75252429142D2 +:10ACE00001DC0020704700EBC1507047C10F80EAC3 +:10ACF000E0700844CA079623002100F0A4B8962308 +:10AD00000022114600F09FB800F0004220F0004001 +:10AD1000C10DC0F3160040F400007F2901DA0020C5 +:10AD20007047962903DCC1F19601C84001E09639CD +:10AD30008840002AF4D04042704720F00040C10D06 +:10AD4000C0F3160040F400007F2901DA00207047AC +:10AD5000962903DCC1F19601C840704796398840B6 +:10AD600070470000002801DBC0F10040002901DB32 +:10AD7000C1F1004181427047002801DBC0F1004071 +:10AD8000002901DBC1F100418842704730B50B4614 +:10AD9000014600202022012409E021FA02F59D420B +:10ADA00005D303FA02F5491B04FA02F52844151EDF +:10ADB000A2F10102F1DC30BDA0F14101192900D856 +:10ADC000203070472DE9F04791460F4680460446F3 +:10ADD000002614F8015B2DB1FFF7DAFD0068405D35 +:10ADE000C007F6D12B2D02D02D2D18D0641E4A4657 +:10ADF0003946204600F0E1F927B13968A14201D176 +:10AE0000C7F8008071054FF002040BD540420028BE +:10AE100003DD00F0E1FA0460A007BDE8F08746F426 +:10AE20008066E4E70028F8DA00F0D6FA04606FF0F4 +:10AE30000040F2E70029A8BF7047401C490008BF46 +:10AE400020F00100704710B4B0FA80FC00FA0CF05A +:10AE500050EA010404BF10BC704749B1CCF1200492 +:10AE600021FA04F411FA0CF118BF0121214308431F +:10AE7000A3EB0C01CB1D0106000A002BBEBF002076 +:10AE800010BC704700EBC35010440029A4BF10BC95 +:10AE90007047401C490008BF20F0010010BC7047FB +:10AEA000F0B4002802DCF0BC00207047C0F3C751AA +:10AEB000C0F3160040F40000CA0701D14000491E4B +:10AEC0003F2202EB6105002211464FF4000626FAEC +:10AED00001F31344D418844201D8001B1A464000E1 +:10AEE000491C1729F3DD5100814202D24FF0FF3196 +:10AEF00000E0002102EBC550F0BCFFF79BBF10B58E +:10AF000041000CD0C0F3C751962908DC7E2909DC2A +:10AF100006DB410204D000F0004040F07E5010BD3E +:10AF2000002010BDC1F19604C4F1200100FA01F126 +:10AF3000E040FFF77FFFA04010BD2DE9FE4F8046A7 +:10AF400081EA0300C00F0C46009021F0004123F07D +:10AF50000045B8EB0200A94105D240462146904683 +:10AF60001C460B46024623F00040104304D14046E5 +:10AF7000214603B0BDE8F08F270DC7F30A00C3F3E5 +:10AF80000A510290401A0190402866DAC3F3130078 +:10AF900040F4801B0098924620B10023D2EB030AB4 +:10AFA00063EB0B0B01985946C0F14002504600F08C +:10AFB000D3F806460D4650465946019A00F0EBF884 +:10AFC00010EB08006141002487EA115284EAE7731C +:10AFD0001A433BD0009A3AB3019A012A4FEA07522A +:10AFE00010DC001B61EB02014FF0004202EA075245 +:10AFF000CDE90042001C41F5801132462B4600F09D +:10B0000038F9B6E7001B61EB0201001C41F5801323 +:10B0100000185B412018A2F5001747EB030140EA36 +:10B02000D570B6196D4111E06D084FEA360645EA54 +:10B03000C0754FEA0752001B61EB0201001C41F58D +:10B04000801149084FEA30000019514132462B4621 +:10B0500003B0BDE8F04F00F0FFB8009801224000B7 +:10B060000023D0EB020263EBE073009821464FEA25 +:10B07000E074B8EB000061EB0401E9E783F0004302 +:10B080005BE781F0004158E710B500F0004420F084 +:10B090000040C20DC0F3160040F400007F2A07DA1A +:10B0A0007D2A00DA7D22763A00FA02F1002008E0DB +:10B0B000962A09DCA2F1760100FA01F1C2F19602AA +:10B0C000D040FFF7B7FE01E0963A9040002C00D048 +:10B0D000404210BD00F0004230F000400AD0C10DE7 +:10B0E00001F56071C0F3160042EA0151C208400741 +:10B0F0001143704700200146704701F0004330B40F +:10B1000021F0004150EA010206D00A0DA2F560725A +:10B11000C1F31301002A02DC30BC00207047440F49 +:10B1200044EAC104C100E01830BC00EBC250FFF794 +:10B1300081BE0000064C074D06E0E06840F00103C8 +:10B1400094E8070098471034AC42F6D3F4F7D2FFE6 +:10B1500038DF000858DF0008202A04DB203A00FA14 +:10B1600002F1002070479140C2F1200320FA03F35E +:10B17000194390407047202A04DB203A21FA02F05C +:10B180000021704721FA02F3D040C2F12002914021 +:10B19000084319467047202A06DBCB17203A41FAAC +:10B1A00002F043EAE07306E041FA02F3D040C2F154 +:10B1B000200291400843194670472DE9F05F82460E +:10B1C0000078002715468B460AF10104B94630285D +:10B1D00001D09DB113E014F8010B0127782803D0AA +:10B1E000582801D045B10AE00DB1102D07D1002734 +:10B1F000102514F8010B02E0082500E00A250026BE +:10B20000B0460EE005FB080005FB06F1012701EB47 +:10B2100010461FFA80F8B6F5803F00D3B94614F8FF +:10B22000010B294600F077F80028EBDABBF1000F9C +:10B2300005D00FB1641E00E05446CBF80040B9F1D0 +:10B24000000F06D000F0C8F802210160C81EBDE85A +:10B25000F09F48EA0640FAE710B5002B08DA401CD8 +:10B2600041F1000192185B411A4301D120F0010025 +:10B2700010BD2DE9F04D92469B4611B1B1FA81F215 +:10B2800002E0B0FA80F220329046FFF765FF0446F4 +:10B290000F4640EA0A0041EA0B0153465A4608436A +:10B2A00003D120463946BDE8F08D114653EA01002E +:10B2B00015D0C8F140025046FFF75DFF05460E4627 +:10B2C000504659464246FFF747FF084301D0012048 +:10B2D00000E00020054346EAE0762C4337430A9815 +:10B2E0004FEA4453A0EB08004FEAD4240A304FF051 +:10B2F000000244EA47544FEAD72502D50020014610 +:10B30000D1E7010510196941DDE9084500196941D6 +:10B31000BDE8F04DA0E73A2800D2303820F02002F6 +:10B32000412A01D3A2F13700884201D34FF0FF3008 +:10B33000704770B501EB020410F8015B15F00703CC +:10B3400001D110F8013B2A1106D110F8012B03E0BE +:10B3500010F8016B01F8016B5B1EF9D12B0705D4C6 +:10B360000023521E0FD401F8013BFAE710F8013B0D +:10B3700002F10202A1EB030303E013F8015B01F801 +:10B38000015B521EF9D5A142D6D3002070BD00004A +:10B390000FB4054B10B503A9044A029800F0E8F871 +:10B3A00010BC5DF814FB0000C52400083804002020 +:10B3B0004100080218BF04200A0E18BF40F0010027 +:10B3C0004FF07F4232EA010108BF40F0020001283D +:10B3D00008BF052070470000004870473C0400206B +:10B3E0006FF05E010807FFF775BC00002DE9F04D16 +:10B3F0000E4614464FF07F41B1EB440F9EBF4FF015 +:10B40000FF313160BDE8F08D4FF0004040EA04218B +:10B41000C4F3C7507838431100F01F00DFF814C19F +:10B42000C0F12002FC445CF823500CEB8303854000 +:10B43000D3F804C02CFA02F72F439D680CFA00FCE5 +:10B4400025FA02F8DB6805FA00F023FA02F240EA76 +:10B4500002054CEA080CA7FB0132ACFB01C0A5FBBE +:10B46000015101EB0C058D4234BF4FF0010C4FF040 +:10B47000000CC1186144BCF1000F02D0814202D916 +:10B4800003E0814201D2012000E00020104400F1DD +:10B4900020024FEA92188006CA0C40EA42304F035D +:10B4A000C6F80080FFF722FC82463846FFF727FCEB +:10B4B0006FF01201FFF70EFC07462846FFF71FFC4E +:10B4C0006FF02501FFF706FC834639465046FFF72B +:10B4D00033FB5946FFF730FB00F500656FF30B05B2 +:10B4E00051462846FFF77AFB3946FFF777FB594666 +:10B4F000FFF777FB1049FFF777FB07460F49284610 +:10B50000FFF772FB3946FFF717FB07460C49284641 +:10B51000FFF76AFB3946FFF70FFB14F0004F08BF37 +:10B52000BDE8F08DC8F1805180F000403160BDE889 +:10B53000F08D00007C210000DB0FC92F22AAFD291D +:10B540000000C92F02E008C8121F08C1002AFAD162 +:10B5500070477047002001E001C1121F002AFBD193 +:10B560007047000001490860704700003C0400205B +:10B570002DE9FF4F8BB09A460F4605460026C9E0DD +:10B58000252837D100246D1C6649A04601222B785E +:10B59000203B02FA03F0084202D004436D1CF6E798 +:10B5A00028782E2817D115F8010F44F004042A2812 +:10B5B0000ED06FF02F022878A0F1300109290AD8A7 +:10B5C00008EB880102EB410100EB01086D1CF2E77A +:10B5D00057F8048B6D1C287869283FD006DC0028BA +:10B5E00071D063280CD0642804D137E0732811D0BF +:10B5F00075284ED052460D99904706F1010688E015 +:10B6000017F8040B8DF8000000208DF80100E946C2 +:10B61000012003E057F8049B4FF0FF3061074FF023 +:10B62000000401D40AE0641C44450DDA8442FADBCC +:10B6300019F804100029F6D106E0641C8442FCDBF2 +:10B6400019F804100029F8D1264404E019F8010B78 +:10B6500052460D999047641EF8D25AE001CF4FF040 +:10B660000A0B002804DAC0F100004FF02D0102E0BF +:10B67000210504D52B218DF82410012103E0E107D9 +:10B6800005D02021F7E70DF1200908910CE00021F9 +:10B69000F9E701CF4FF00A0BF9E75946FFF776FBC0 +:10B6A00001F1300209F8012D0028F6D1ADEB0900B7 +:10B6B00000F1200B600701D44FF00108D84503DDED +:10B6C000A8EB0B0001E029E000208046002406E002 +:10B6D00009A85246005D0D999047761C641C089895 +:10B6E0008442F5DB04E0302052460D999047761CE9 +:10B6F000B8F10001A8F10108F5DC05E019F8010B2B +:10B7000052460D999047761CBBF10001ABF1010B3D +:10B71000F4DC6D1C287800287FF432AF0FB030467F +:10B72000BDE8F08F092801002DE9F0474FF068428D +:10B7300002EB40030C460546B3F1654F3CBF02EBFC +:10B740004102B2F1654F3FD34FF07F42B2EB400F61 +:10B7500028BFB2EB410F03D2BDE8F047FFF7ECB9C9 +:10B7600040EA01035B0008BF44F0FF410AD0B2EB9E +:10B77000400F08BFB2EB410F06D125F0804024F006 +:10B78000804105460C461FE0B2EB400F12BF5FEA56 +:10B79000410245F0FF4004F0004115D04FEA41025C +:10B7A00092EA400310D4002AB4BF4FF03E564FF047 +:10B7B0009F463146FFF718FA054631462046FFF707 +:10B7C00013FA044628462146C0F3C753C1F3C752B3 +:10B7D0009A1A1B2A06DD10F0004F14BF5448554832 +:10B7E000BDE8F08712F11A0F17DA11F0004F06D0FA +:10B7F00010F0004F0CBF50485048BDE8F08721467C +:10B800002846FFF727FA0446FFF7D2FD042808BFB1 +:10B81000FFF7E6FD2046BDE8F0874200B2EB410F9E +:10B8200025D910F0004F19BF454F464E464F474EA1 +:10B83000224685F0004415460A4680F00041104635 +:10B840000A1A5200B2F1807F3ED248404049DFF8E8 +:10B8500004A110F0004F18D04FF03F483846FFF7D2 +:10B86000BDF9074651463046FFF7B8F917E011F029 +:10B87000004F04BF00263746E2D010F0004F19BF3A +:10B88000354F364E364F374EDAE74FF07C58384654 +:10B89000FFF752F9074651463046FFF74DF9064685 +:10B8A00041462846FFF7A0F92146FFF745F98246B1 +:10B8B00021464046FFF798F92946FFF792F951468D +:10B8C000FFF7C8F9044604E021462846FFF7C2F90D +:10B8D00004460146FFF788F980462349FFF784F9BB +:10B8E0002249FFF729F94146FFF77EF92049FFF782 +:10B8F00023F94146FFF778F91E49FFF71DF9414644 +:10B90000FFF772F91C49FFF717F905464146204633 +:10B91000FFF76AF92946FFF767F93146FFF70CF997 +:10B920002146FFF709F93946BDE8F047FFF704B9AA +:10B93000DB0FC9BFDB0FC93FDB0F4940DB0F49C03D +:10B940000000C9BF22AAFDB90000C93F22AAFD39E3 +:10B950000060ED3EC30ACE37000049C022AA7DBA7E +:10B960000000494022AA7D3A2DAD65BD8FB8D53D76 +:10B970000FB511BE61C84C3EA8AAAABE2DE9F84376 +:10B980000446024650486946B0EB420F09D94FF0D1 +:10B99000E640B0EB420F94BF00204FF0FF30009024 +:10B9A00034E04A4B22F0004083422BD948492046DC +:10B9B000FFF71AF9FFF7A3FA8046FFF7A5F900F0A1 +:10B9C0000300009043494046FFF70EF905464249FF +:10B9D0004046FFF709F9064640494046FFF704F99B +:10B9E00007463F494046FFF7FFF82146FFF7F9F8C1 +:10B9F0003946FFF7F3F83146FFF7F0F82946FFF72D +:10BA0000EDF802E01046FFF7F1FC04462546009CE5 +:10BA1000002C18DA6800B0F17F4F3CBF4FF07E5029 +:10BA2000BDE8F88309D14FF00100FFF79BFDBDE8A9 +:10BA3000F84300210846FFF70DB92846BDE8F84352 +:10BA40000121FFF747B9294614F0010F08461CD021 +:10BA5000FFF7CAF806462349FFF7C6F82249FFF761 +:10BA6000C0F83146FFF7C0F82049FFF765F83146C6 +:10BA7000FFF7BAF82946FFF7B7F82946FFF75CF851 +:10BA800014F0020F1CD0BDE8F883FFF7ADF80546AF +:10BA90001749FFF7A9F81749FFF74EF82946FFF7AE +:10BAA000A3F81549FFF748F82946FFF79DF84FF02E +:10BAB0007E51FFF741F814F0020F08BFBDE8F8838C +:10BAC00080F00040BDE8F883B61F927E490E4946DB +:10BAD00083F9223F1A61342C0020A23300A0FD39E3 +:10BAE0000000C93F336D4C39DA82083CA0AA2ABE57 +:10BAF000B93AB2BACA9F2A3DDDFFFFBE70B505460E +:10BB0000FFF7C2FA04464000801C0DD12846FFF71B +:10BB1000F6F905462046FFF7E9F82946FFF722F92E +:10BB20001CBF0120FFF71EFD204670BD2DE9F04D22 +:10BB30000F460E46A0F50001804604464FF0007007 +:10BB400084B04FF07E554FF0000B00EB47004FF0F4 +:10BB50007F4AB1F1FE4F04D2B0F1804F80F00181F5 +:10BB600041E0B0F1804F3ED304F1FF40B0F1FE4F11 +:10BB70001FD200BF28F00048C6F3C75044467F28B4 +:10BB800009DB97287DDAC0F19600012101FA00F067 +:10BB9000411E314209D00120FFF7E4FC04B000212E +:10BBA000BDE8F04D0846FFF755B8304218BFFE4DCE +:10BBB000D7E0600000281CBF4FF08070B0EB440F4E +:10BBC0000BD91B214046FFF785F8804604466FF0ED +:10BBD0001A0B10F0004FCDD1C3E0A4F50000B0F176 +:10BBE000FE4F1BD2BDE0B0F1007F11D300213846DB +:10BBF000FFF7B8F806D16000002818BFBAEB440F71 +:10BC000071D8B1E706F0004040F0FC563746ABE78C +:10BC1000B0F1807F38BFA6F50007A5D324F000401F +:10BC20006FF0FF42E14B8118994210D326F000419A +:10BC30000A449A420BD3B4F17E5F18BF5FEA460212 +:10BC400051D0B0F1FF4F98BFB1F1FF4F06D904B00A +:10BC500039464046BDE8F04DFEF76EBFB4F1FF4FE8 +:10BC600010D0C6F3C7507F2809DB972812DAC0F13D +:10BC70009600012101FA00F0411E314206D0002059 +:10BC800009E06EE016F0004F5DD127E0304218BFAA +:10BC9000012000D1022014F5000F13D024B3B4F119 +:10BCA000004F27D014F1814F56D04FF0FE40B0EB3B +:10BCB000440F94BF01200020012101EBE67188426E +:10BCC00041D10BE016F0004F02D001283FD03AE0FE +:10BCD000012802BFB64804B0BDE8F08D4FF0FF4028 +:10BCE00004B0BDE8F08D37E016F000400ED104B08E +:10BCF000BDE8F08DB6F1FF4F25D016F5000F05D049 +:10BD000016F0004F18D008B101280AD00220FFF722 +:10BD100029FC04B00021BDE8F04D4FF07E50FEF745 +:10BD200099BF0220FFF71EFC04B04146BDE8F04D6C +:10BD30004FF07E50FEF78EBF002804BF04B0BDE870 +:10BD4000F08D012803D004B00020BDE8F08D04B0D0 +:10BD50004FF00040BDE8F08D04B04FF07E50BDE8DC +:10BD6000F08D94482044B0F5005F44D84046FFF77A +:10BD7000B1F90022904BFFF781F9FFF7BEF90446B5 +:10BD80006FF00101FEF7A6FF8C49FEF72AFF21465E +:10BD9000FEF72AFF4FF07C51FEF723FF06462146AF +:10BDA0000846FEF721FF80F000403146FEF71CFFF9 +:10BDB000804683492046FEF717FF064681494046E4 +:10BDC000FEF712FF804680492046FEF70DFF4146F0 +:10BDD000FEF7B2FE044601463046FEF7ADFE00F522 +:10BDE000006B6FF30B0B59463046FEF7F7FE21460A +:10BDF000FEF7A2FED4E004F58020C00C00F00F0690 +:10BE0000C0F307107F38A4EBC05483443046FEF7DC +:10BE10006DFF6FF00301FEF75DFF4FF07E51FEF7FF +:10BE20008BFE014602902046FEF7D8FE0190204688 +:10BE30000299FEF781FE00F500686FF30B08009091 +:10BE400041460298FEF7CAFE2146FEF775FE0290B3 +:10BE50004FF07E500099FEF7FDFE014600900198DC +:10BE6000FEF7C2FE00F500646FF30B042046029952 +:10BE7000FEF7BAFE029041462046FEF7B5FE019954 +:10BE8000FEF7AFFE0299FEF7A9FE0099FEF7ACFEA1 +:10BE9000014600902046FEF74FFE0146FEF7A4FE45 +:10BEA00080464A49FEF7A0FE4449FEF745FE41465A +:10BEB000FEF79AFE804600212046FEF70BFF019018 +:10BEC00020460099FEF738FE4146FEF78DFE0446F7 +:10BED00000210098FEF7FEFE2146FEF72DFE80466B +:10BEE00001460198FEF728FE00F500646FF30B048D +:10BEF00021460198FEF772FE4146FEF71DFE804680 +:10BF000033492046FEF770FE009032494046FEF766 +:10BF10006BFE804630492046FEF766FE4146FEF73E +:10BF20000BFE804601460098FEF706FE00F5006411 +:10BF30006FF30B0421460098FEF750FE4146FEF7D2 +:10BF4000FBFD80462548784450F8361000EBC600CB +:10BF5000019146684FEA0B10FEF7C8FE009031468B +:10BF60004046FEF7E9FD2146FEF7E6FD0199FEF7A2 +:10BF7000E3FD0099FEF7E0FD00F5006B6FF30B0B9E +:10BF800058460099FEF72AFE0199FEF727FE214642 +:10BF9000FEF724FE3146FEF721FE4146FEF721FE64 +:10BFA000804607F500641BE0000080BFFFFF3F00F4 +:10BFB000000080FF001080C00000F03FABAAAA3E46 +:10BFC00000B0B8413BAAB841D49A38BB7EE24C3E9F +:10BFD00000B038423BAA3842D49AB8BB9214000051 +:10BFE0006FF30B0421463846FEF7F8FD074621465D +:10BFF0005846FEF7F9FD064639462046FEF79CFDF9 +:10C000004146FEF7F1FD044639465846FEF7ECFD81 +:10C010002146FEF791FD074601463046FEF78CFDAE +:10C0200000F500646FF30B0421463046FEF7D6FDA1 +:10C030003946FEF781FD804601462046FEF77CFD2D +:10C04000FFF722F807460611FEF750FE2146FEF7DD +:10C05000C8FD4146FEF770FD04463549FEF7C4FDB4 +:10C060003449FEF769FD2146FEF7BEFD3249FEF771 +:10C0700063FD2146FEF7B8FD0146304807F00F0486 +:10C08000784450F82400FEF7AFFD2D49794451F86B +:10C090002410FEF751FD2B49794451F82410FEF786 +:10C0A0004BFD06F17D01FC2908D23146FEF712FE58 +:10C0B00004B02946BDE8F04DFEF796BD06F1BF017C +:10C0C000B1F5BF7F16D83146FEF704FE2946FEF7CC +:10C0D0008BFD0446BAEB440F1AD060000CD020460A +:10C0E000FFF766F9042808BFFFF77AF9204604B085 +:10C0F000BDE8F08D002E0BDA0220FFF733FAFFF7D0 +:10C100006FF90146284604B061F31E00BDE8F08DCA +:10C110000220FFF727FA61214FF0E040FEF7DAFD39 +:10C120000146284604B061F31E00BDE8F08D000012 +:10C13000FC596337C9FF753A1872313D5814000035 +:10C140000C140000C01300002DE9F8430446024619 +:10C1500053486946B0EB420F09D94FF0E640B0EBC7 +:10C16000420F94BF00204FF0FF30009034E04D4B61 +:10C1700022F0004083422BD94B492046FEF734FD84 +:10C18000FEF7BDFE8046FEF7BFFD00F00300009005 +:10C1900046494046FEF728FD054645494046FEF71C +:10C1A00023FD064643494046FEF71EFD0746424929 +:10C1B0004046FEF719FD2146FEF713FD3946FEF70E +:10C1C0000DFD3146FEF70AFD2946FEF707FD02E0A8 +:10C1D0001046FFF70BF904462546009C002C1DDA9B +:10C1E0006800B0F17F4F09D22846FFF7E1F8042834 +:10C1F00008BFFFF7F5F82846BDE8F88308D101200D +:10C20000FFF7B0F9BDE8F84300210846FEF722BD6C +:10C210002846BDE8F8430121FEF75CBD294614F02D +:10C22000010F08461ED0FEF7DFFC05462349FEF746 +:10C23000DBFC2349FEF780FC2946FEF7D5FC2149AB +:10C24000FEF77AFC2946FEF7CFFC4FF07E51FEF751 +:10C2500073FC14F0020F08BFBDE8F88380F00040C3 +:10C26000BDE8F883FEF7C0FC06461749FEF7BCFCA4 +:10C270001649FEF7B6FC3146FEF7B6FC1449FEF748 +:10C280005BFC3146FEF7B0FC2946FEF7ADFC2946C3 +:10C29000FEF752FC14F0020FE0D1BDE8F883000075 +:10C2A000B61F927E490E494683F9223F1A61342C0B +:10C2B0000020A23300A0FD390000C93FB93AB2BA4C +:10C2C000CA9F2A3DDDFFFFBE336D4C39DA82083C40 +:10C2D000A0AA2ABE70B50546FEF7E2FD044620F08E +:10C2E0000040C0F1FF40C00F08D025F00040C0F171 +:10C2F000FF40C00F04BF0120FFF734F9204670BD96 +:10C300005DD60008BAD6000818D700085AD600082B +:10C3100061D60008F9D50008F4D5000848D6000811 +:10C32000E9D5000812D70008FCD50008CBD60008D4 +:10C3300027D7000813D600088BD6000824D600089B +:10C34000E2D5000854D60008ADD60008F3D60008A0 +:10C35000E6D6000884D600080000000099D6000840 +:10C3600002D7000868D600081ED70008C0D600080B +:10C3700007D7000830D600083FD60008FED60008D0 +:10C380000AD60008D5D6000831D70008DBD6000849 +:10C390009DD6000807D6000879D6000800000000E6 +:10C3A000A8D6000803D60008A3D6000820D60008A7 +:10C3B000D5D60008FED600081CD6000800000000F4 +:10C3C000B6DD0008ECD50008D3D5000876DD0008FE +:10C3D000DBD500088ED800080000000091DD0008C1 +:10C3E00024DD0008330300088CDD000818DC000899 +:10C3F0008703000871DC0008D2DC0008A9060008E9 +:10C40000E8DB0008FFDA00085B0700089FDC000893 +:10C41000B6DD0008D1080008B7D800086ADA0008BD +:10C42000F5080008D2D9000821DA0008C10900087F +:10C43000E3DB0008B6DD0008D9090008DFDB0008EF +:10C44000EDDB0008050A000826DC0008EFDC000828 +:10C45000D50C00085EDC00082CD900085B0D000834 +:10C460003FD80008C4D50008EB0D000847D90008E4 +:10C47000C2DC0008AB0800089BDC000802DD0008F5 +:10C48000250E000894DC000888DC0008690F00080D +:10C490003CDB0008B6DD00081310000885D8000852 +:10C4A000020000007C04002000000000282300009F +:10C4B00045D700080200000084050020B0040000F9 +:10C4C000A40600006DD8000802000000400500200E +:10C4D00000000000D007000079D80008020000002A +:10C4E0004205002000000000D0070000EFD7000840 +:10C4F000020000004405002000000000D0070000FA +:10C5000000DA00080200000086050020000000009C +:10C51000D007000009DA00080200000088050020AA +:10C5200000000000D007000067DD000802000000E6 +:10C530004605002000000000D0070000C2D9000816 +:10C54000020000004805002000000000D0070000A5 +:10C550004BD70008020000004A0500200000000040 +:10C56000D007000047D80008020000004C0500205A +:10C5700000000000D0070000E6D80008020000001C +:10C580004E05002032000000F2010000D7D800085C +:10C59000020000005005002032000000F2010000FF +:10C5A000F2DA0008000000008A0500200000000008 +:10C5B0000100000074D70008000000008B05002077 +:10C5C000000000006400000007D90008040000001B +:10C5D00090050020B004000000C2010003D900084B +:10C5E000040000009405002080250000004B00009E +:10C5F00080D700080000000098050020000000001F +:10C600000100000093D80008000000008D05002004 +:10C61000000000000300000017D90008010000001E +:10C620008E050020FFFFFFFF040000009CD80008DB +:10C630000000000082050020000000000200000051 +:10C640003BDA00080000000099050020000000000F +:10C650000100000035D80008000000007605002029 +:10C660000A000000C80000000DD80008000000000B +:10C67000770500200A00000032000000FAD7000809 +:10C6800000000000780500200A00000032000000D1 +:10C690007EDA00080000000079050020000000009C +:10C6A00009000000A3DB0008000000005205002084 +:10C6B00000000000080000003BD700080000000058 +:10C6C00053050020000000000800000072D9000897 +:10C6D00000000000540500200000000008000000D9 +:10C6E000C5DA000803000000560500204CFFFFFFDC +:10C6F0006801000091D900080300000058050020DF +:10C700004CFFFFFF680100004BDD00080300000044 +:10C710005A0500204CFFFFFF6801000054DB0008B1 +:10C72000010000005C050020FFFFFFFF010000008A +:10C73000AAD80008000000005D05002000000000ED +:10C74000050000009CD700080000000068050020DC +:10C75000000000008000000069D90008020000000D +:10C760005E05002000000000000100003BDC000826 +:10C77000020000006005002064000000E8030000E3 +:10C780004CDC00080200000062050020640000008C +:10C79000E803000009DC000800000000EC070020AE +:10C7A0000000000001000000E6D7000800000000C3 +:10C7B000520800200000000020000000E3D700081D +:10C7C000000000005308002000000000640000008A +:10C7D00050DA0008000000005408002001000000AA +:10C7E000FA00000020D800080000000055080020D2 +:10C7F000000000000100000078DB000800000000DD +:10C80000560800200000000064000000BFD80008A7 +:10C81000000000000B08002000000000FA000000EB +:10C8200092DB0008000000000C080020000000005F +:10C830006400000094D70008000000000D080020EC +:10C8400000000000640000009ADB00080000000007 +:10C850000E0800200000000064000000C7D8000897 +:10C86000000000000F08002000000000640000002D +:10C8700024D900080000000010080020000000007B +:10C880006400000095DD000800000000980800200A +:10C8900000000000C8000000A4DD00080000000047 +:10C8A0009908002000000000C80000005BD80008C4 +:10C8B000020000009A080020E8030000D0070000F2 +:10C8C000ACD70008020000009C08002064000000B3 +:10C8D000D007000090DA0008010000008C0500205D +:10C8E00000000000040000006ADB000801000000F6 +:10C8F0009E080020FFFFFFFF01000000AEDB0008E4 +:10C90000010000009F08002000000000010000005E +:10C9100064DC000800000000A00800200000000007 +:10C92000FF0000002CDC00080000000018080020B8 +:10C9300000000000FA000000C6D700080000000058 +:10C940001A0800200000000064000000D5D700088D +:10C950000000000019080020000000006400000032 +:10C9600012DA000800000000280800200000000083 +:10C9700001000000ABD900080300000016080020E9 +:10C98000D4FEFFFF2C010000DDDA000803000000E8 +:10C9900014080020D4FEFFFF2C0100004CD9000831 +:10C9A000000000001B080020000000003000000014 +:10C9B0005AD90008050000001C08002000000000F3 +:10C9C00001000000A1DA0008050000002008002096 +:10C9D0000000000001000000AADC000805000000C3 +:10C9E00024080020000000000100000044DB0008D3 +:10C9F0000300000012080020B0B9FFFF50460000FD +:10CA0000CBDB000800000000F10700200000000060 +:10CA1000C8000000ECD9000800000000FB0700205F +:10CA200000000000C800000060D7000800000000FF +:10CA30000508002000000000C8000000C0DB00085E +:10CA400000000000F207002000000000C800000005 +:10CA5000E1D9000800000000FC07002000000000F1 +:10CA6000C800000055D7000800000000060800209C +:10CA700000000000C8000000D5DB00080000000036 +:10CA8000F307002000000000C8000000F6D90008ED +:10CA900000000000FD07002000000000C8000000AA +:10CAA0006AD700080000000007080020000000000E +:10CAB000C80000007ADC000802000000A208002084 +:10CAC00000000000D00700007CD900080000000032 +:10CAD000A608002000000000010000002EDB000876 +:10CAE00002000000A80800200A000000D007000093 +:10CAF0007EDD000802000000AA0800200A000000F5 +:10CB0000D0070000F5D8000800000000A5080020AC +:10CB10000000000064000000BAD900080000000016 +:10CB2000EE07002000000000C8000000A3D90008A4 +:10CB300000000000F807002000000000C80000000E +:10CB40009BD900080000000002080020000000003F +:10CB5000C8000000EBDA000800000000ED0700202C +:10CB600000000000C8000000D6DA00080000000045 +:10CB7000F707002000000000C8000000CFDA00081E +:10CB8000000000000108002000000000C8000000B4 +:10CB900061DD000800000000EF0700200000000039 +:10CBA000C80000005BDD000800000000F90700205D +:10CBB00000000000C800000055DD00080000000073 +:10CBC0000308002000000000C8000000BCDC0008D2 +:10CBD00000000000F007002000000000C800000076 +:10CBE000B6DC000800000000FA070020000000008A +:10CBF000C8000000A4DC00080000000004080020B9 +:10CC000000000000C8000000BDDA000800000000BD +:10CC1000F407002000000000C8000000B5DA00089A +:10CC200000000000FE07002000000000C800000017 +:10CC3000ADDA000800000000080800200000000035 +:10CC4000C800000041455254313233340000000026 +:10CC50000000803F00000000A8AAAA3F00000000DA +:10CC60000000803F000080BFB0AA2ABF0000000083 +:10CC70000000803F0000803FB0AA2ABF00000000F3 +:10CC80000000803F000000000000803F000080BFE7 +:10CC90000000803F000080BF000000000000803FD7 +:10CCA0000000803F0000803F000000000000803F47 +:10CCB0000000803F00000000000080BF000080BF37 +:10CCC0000000803F000080BF0000803F000080BF68 +:10CCD0000000803F000080BF000080BF0000803F58 +:10CCE0000000803F0000803F0000803F0000803F48 +:10CCF0000000803F0000803F000080BF000080BF38 +:10CD00000000803F0000803F0000000000000000A5 +:10CD10000000803F000080BF000000000000000015 +:10CD20000000803F00000000A8AAAA3F0000803F4A +:10CD30000000803F000080BFB0AA2ABF000080BF73 +:10CD40000000803F0000803FB0AA2ABF000080BFE3 +:10CD50000000803F00000000A8AAAA3F000080BF9A +:10CD60000000803F000080BFB0AA2ABF0000803FC3 +:10CD70000000803F0000803FB0AA2ABF0000803F33 +:10CD80000000803F000080BFD0B35D3F0000803FC7 +:10CD90000000803F000080BFD0B35DBF000080BFB7 +:10CDA0000000803F0000803FD0B35D3F0000803F27 +:10CDB0000000803F0000803FD0B35DBF000080BF17 +:10CDC0000000803F00000000D0B35DBF0000803F46 +:10CDD0000000803F00000000D0B35D3F000080BF36 +:10CDE0000000803F000000000000803F000080BF86 +:10CDF0000000803F000080BF000080BF00000000F6 +:10CE00000000803F000000000000803F0000803FE5 +:10CE10000000803F0000803F000080BF0000000055 +:10CE20000000803FD0B35DBF0000803F0000803F26 +:10CE30000000803FD0B35DBF000080BF0000803F96 +:10CE40000000803FD0B35D3F0000803F000080BF06 +:10CE50000000803FD0B35D3F000080BF000080BF76 +:10CE60000000803FD0B35DBF00000000000080BF25 +:10CE70000000803FD0B35D3F000000000000803F15 +:10CE80000000803F000080BF0000803F000080BFA6 +:10CE90000000803F000080BF000080BF0000803F96 +:10CEA0000000803F0000803F0000803F0000803F86 :10CEB0000000803F0000803F000080BF000080BF76 -:10CEC000000080BF0000803F0000803F0000803FE6 -:10CED000000080BF0000803F0000803F000080BF56 -:10CEE0000000803F0000803FF704353FF70435BF66 -:10CEF0000000803F0000803FF70435BFF70435BFD6 -:10CF00000000803F0000803FF70435BFF704353F45 -:10CF10000000803F0000803FF704353FF704353FB5 -:10CF20000000803F0000803F00000000000080BF44 -:10CF3000000080BF0000803F000080BF00000000B4 -:10CF4000000080BF0000803F000000000000803F24 -:10CF5000000080BF0000803F0000803F0000000014 -:10CF6000000080BF0000803F0000803F000000BF45 -:10CF70000000803F0000803F000000BF000080BF35 -:10CF80000000803F0000803F000080BF0000003FA5 -:10CF90000000803F0000803F0000003F0000803F15 -:10CFA0000000803F0000803F0000003F000080BF85 -:10CFB000000080BF0000803F000080BF000000BF75 -:10CFC000000080BF0000803F000000BF0000803FE5 -:10CFD000000080BF0000803F0000803F0000003F55 -:10CFE000000080BF0000803F000000000000803F84 -:10CFF0000000803F0000803F000080BF000080BF35 -:10D00000000000000000803F000000000000803FA2 -:10D01000000080BF0000803F0000803F000080BF14 -:10D02000000000800000803F000080BF0000803FC3 -:10D03000000080BF0000803F000080BF000080BF74 -:10D040000000803F0000803F0000803F0000803FE4 -:10D050000000803F0000803F0000803F000080BF54 -:10D06000000080BF0000803F0000000000000000C2 -:10D07000000000000000803F0000000000000000F1 -:10D08000000000000000803F0000000000000000E1 -:10D09000000080BF0000803F000000000000000092 -:10D0A0000000803F000000000000000003010000BD -:10D0B00034CC00080400000064CC00080400000028 -:10D0C000A4CC000802010000E4CC0008000100002C -:10D0D000000000000600000004CD0008060000006B -:10D0E00064CD000801010000000000000400000001 -:10D0F000C4CD00080600000004CE000808000000AF -:10D1000064CE000808000000E4CE0008080000001B -:10D1100064CF0008010100000000000000010000D1 -:10D1200000000000000100000000000004000000FA -:10D13000E4CF00080600000024D000080001000031 -:10D14000000000000201000084D00008010100007E -:10D15000000000000000000000000000524F4C4C96 -:10D160003B50495443483B5941573B414C543B5039 -:10D170006F733B506F73523B4E6176523B4C45563A -:10D18000454C3B4D41473B56454C3B0000C20100DE -:10D19000E1DE000804DF000800E10000BFDE000857 -:10D1A000ABDE00080096000075DE000897DE000880 -:10D1B000004B000053DE00083FDE00088025000021 -:10D1C0009ADD00089ADD0008B56206010300F0054B -:10D1D00000FF19B56206010300F00300FD15B562FA -:10D1E00006010300F00100FB11B56206010300F027 -:10D1F0000000FA0FB56206010300F00200FC13B54F -:10D200006206010300F00400FE17B5620601030088 -:10D210000102010E47B562060103000103010F4937 -:10D22000B56206010300010601124FB56206010353 -:10D23000000112011E67B56206160800030703000D -:10D24000510800008A41B56206080600C8000100C6 -:10D250000100DE6A1048494A4B4C4D44454647FFA1 -:10D26000202122232425262748494A4B4C4DFF10D4 -:10D2700048498A8B8C8D84858687FF202122232430 -:10D2800025262748498A8B8C8DFF000060D2000834 -:10D2900054D200087BD200086FD20008000C014075 -:10D2A00008001002000C01401000100200080140AC -:10D2B0000010140231860008CD85000801860008A0 -:10D2C0004F850008E7850008000000400008014085 -:10D2D00001000000001C00000000004000080140A8 -:10D2E00002000000041C0000000000400008014093 -:10D2F00004000000081C000000000040000801407D -:10D30000080000000C1C0000000400400008014060 -:10D3100040000000001D0000000400400008014023 -:10D3200080000000041D000000040040000C0140CB -:10D3300001000000081D000000040040000C014036 -:10D34000020000000C1D0000002C014000080140FC -:10D3500000010000001B0100002C014000080140FA -:10D36000000800000C1B010000080040000C0140F8 -:10D3700040000000001E000000080040000C0140BA -:10D3800080000000041E000000080040000C014066 -:10D3900000010000081E000000080040000C0140D1 -:10D3A000000200000C1E00000004080CAF970008EB -:10D3B0006797000889970008C79700083B96000800 -:10D3C00000000000000000000000B33FB2BE7D3A44 -:10D3D00000002E40DFCF513800007E40BF51FABA26 -:10D3E00000E0A44019DAC3BA00E0C840C2ED8AB92F -:10D3F0000040EB40CD1F2CBA001006412AFFFABABC -:10D4000000C01541DFCFD13700D024419A97703A40 -:10D410000050334189478E3600404141E75B9D38DB -:10D4200000B04E41C00A98B900A05B41558F943AB4 -:10D4300000306841DA92C0BA0040744162B3C63A23 -:10D440000000803F00A0853F00908B3F00C0913FCF -:10D450000030983F00F09E3F00F0A53F0050AD3FE8 -:10D460000000B53F0000BD3F0060C53F0020CE3F3B -:10D470000040D73F00C0E03F00C0EA3F0020F53F3A -:10D48000000000007D36AC397D3C3839EBDCF438E7 -:10D49000320A7E39124C26399B6AED39A4EE833963 -:10D4A0007F661E39F6398A392B426539A4821139D3 -:10D4B0005B991F39C3EECD39DDE7C637A5A22F39F9 -:10D4C0000000803FC3AA853FC2958B3FD3C3913FE5 -:10D4D000F037983F32F59E3FD7FEA53F3F58AD3F0E -:10D4E000F304B53FA408BD3F2A67C53F8C24CE3F57 -:10D4F000FD44D73FDFCCE03FC7C0EA3F7D25F53F85 -:10D500000040404040404040404041414141414056 -:10D51000404040404040404040404040404040400B -:10D52000400502020202020202020202020202029A -:10D53000022020202020202020202002020202029F -:10D5400002029090909090901010101010101010F7 -:10D550001010101010101010101010100202020203 -:10D560000202888888888888080808080808080847 -:10D570000808080808080808080808080202020243 -:10D580004000000001D50008000000006E83F9A2F1 -:10D590002915444ED15727FCC0DD34F5999562DB3F -:10D5A0004190433CAB6351FE696E6465782028303E -:10D5B00020746F203229004D5055363035300042EE -:10D5C0004D4132383000565441494C3400593400F2 -:10D5D0004144584C333435004845583600593600DC -:10D5E0004F43544F583800414343003344004641B1 -:10D5F000494C5341464500414952504C414E45002B -:10D600004750532B4D41470048454C495F39305FE7 -:10D61000444547004759524F5F534D4F4F54484977 -:10D620004E47004C45445F52494E4700464C5949CD -:10D630004E475F57494E47004845583648004249D3 -:10D64000005452490047494D42414C00494E464C16 -:10D65000494748545F4143435F43414C00534F4661 -:10D660005453455249414C00435553544F4D004883 -:10D67000454C495F3132305F4343504D0050504D6F -:10D6800000564152494F004241524F004759524FB4 -:10D690000050504D5F544F5F534552564F00515507 -:10D6A000414450004D4F544F525F53544F50004F20 -:10D6B00043544F464C41545000534F4E415200503A -:10D6C0004F5745524D455445520053494E474C45DE -:10D6D000434F50544552004455414C434F505445DC -:10D6E0005200475053005642415400534552564F42 -:10D6F0005F54494C540048455836580051554144F0 -:10D70000580053455249414C5258004F43544F46DC -:10D710004C4154580054454C454D455452590061B4 -:10D720006C69676E5F616363006D69647263006E4C -:10D7300065757472616C3364006770735F706F73CA -:10D74000725F64006770735F706F735F640067700F -:10D75000735F6E61765F6400666C6170735F737097 -:10D7600065656400736F667473657269616C5F6987 -:10D770006E766572746564007468725F6D696400CA -:10D780006D6F726F6E5F7468726573686F6C640042 -:10D790006661696C736166655F6465746563745F17 -:10D7A0007468726573686F6C640061636378795F35 -:10D7B0006465616462616E64006163637A5F64657D -:10D7C000616462616E64007961776465616462615D -:10D7D0006E64006D696E636F6D6D616E640076627C -:10D7E00061746D696E63656C6C766F6C746167658E -:10D7F00000766261746D617863656C6C766F6C74D1 -:10D8000061676500616C745F686F6C645F6661730B -:10D81000745F6368616E67650076626174736361EB -:10D820006C650070726F66696C6500646561646246 -:10D83000616E6433645F7468726F74746C650066E3 -:10D8400061696C736166655F7468726F74746C652E -:10D85000006D696E7468726F74746C65006D6178C8 -:10D860007468726F74746C65006C6F6F7074696D3E -:10D8700065004E6F6E65006770735F747970650048 -:10D8800073657269616C72785F7479706500616349 -:10D89000635F686172647761726500666561747563 -:10D8A00072650072635F7261746500726F6C6C5FA9 -:10D8B00070697463685F7261746500736572766F16 -:10D8C0005F70776D5F72617465006D6F746F725F0A -:10D8D00070776D5F72617465006E61765F736C6501 -:10D8E000775F7261746500736F66747365726961E6 -:10D8F0006C5F6261756472617465006770735F620A -:10D900006175647261746500796177726174650034 -:10D910006765742F736574206D6F746F72206F75F7 -:10D92000747075742076616C75650073617665003E -:10D930006261726F5F7461625F73697A65006261D0 -:10D94000726F5F6E6F6973655F6C70660067797286 -:10D950006F5F6C706600616C69676E5F6D61670018 -:10D960006E61765F636F6E74726F6C735F68656112 -:10D9700064696E6700616C69676E5F626F61726493 -:10D980005F706974636800695F70697463680061DF -:10D9900063635F7472696D5F706974636800705F60 -:10D9A0007069746368006465616462616E643364A5 -:10D9B0005F68696768006770737061737374687219 -:10D9C0006F756768006770735F706F73725F69006F -:10D9D0006770735F706F735F69006770735F6E610C -:10D9E000765F69006D696E636865636B006D617871 -:10D9F000636865636B006163635F756E61726D651B -:10DA00006463616C00706173737468726F756768CA -:10DA10002067707320746F2073657269616C007485 -:10DA2000656C656D657472795F736F66747365722A -:10DA300069616C00616C745F686F6C645F746872BC -:10DA40006F74746C655F6E65757472616C006C697F -:10DA50007374206F72202D76616C206F7220766156 -:10DA60006C00706F7765725F6164635F6368616E9D -:10DA70006E656C00727373695F6175785F6368616E -:10DA80006E6E656C006261726F5F63665F76656C77 -:10DA900000645F6C6576656C00695F6C6576656CCB -:10DAA00000705F6C6576656C00616C69676E5F62C3 -:10DAB0006F6172645F726F6C6C00695F726F6C6C27 -:10DAC000006163635F7472696D5F726F6C6C00708C -:10DAD0005F726F6C6C0072657461726465645F6123 -:10DAE000726D007072696E7420636F6E666967751F -:10DAF0007261626C652073657474696E6773206906 -:10DB00006E2061207061737461626C6520666F7253 -:10DB10006D006E61765F73706565645F6D696E0040 -:10DB200076657273696F6E006D61675F6465636CC3 -:10DB3000696E6174696F6E007961775F636F6E748F -:10DB4000726F6C5F646972656374696F6E0079618E -:10DB5000775F646972656374696F6E007468726F71 -:10DB600074746C655F616E676C655F636F7272651C -:10DB70006374696F6E0072635F6578706F007468BC -:10DB8000725F6578706F00616C69676E5F6779724C -:10DB90006F007472695F756E61726D65645F736545 -:10DBA00072766F006770735F706F73725F7000677B -:10DBB00070735F706F735F70006770735F6E617614 -:10DBC0005F70006D61700068656C700064756D70E9 -:10DBD000006D617070696E67206F662072632063EC -:10DBE00068616E6E656C206F726465720070696446 -:10DBF0005F636F6E74726F6C6C65720064657369DD -:10DC0000676E20637573746F6D206D69786572003F -:10DC10006163635F6C70665F666163746F720067F7 -:10DC200079726F5F636D70665F666163746F7200B7 -:10DC30006779726F5F636D70666D5F666163746F45 -:10DC400072006D6F746F720067696D62616C5F6600 -:10DC50006C6167730064656661756C7473006770EE -:10DC6000735F77705F7261646975730073686F7753 -:10DC70002073797374656D207374617475730073A8 -:10DC80006574006578697400645F616C740062613A -:10DC9000726F5F63665F616C7400695F616C7400D2 -:10DCA000705F616C74007361766520616E642072D0 -:10DCB00065626F6F7400726573657420746F2064A1 -:10DCC000656661756C747320616E64207265626F45 -:10DCD0006F74006D69786572206E616D65206F727A -:10DCE000206C697374006E616D653D76616C75655D -:10DCF000206F7220626C616E6B206F72202A20662A -:10DD00006F72206C69737400666561747572655F0B -:10DD10006E616D6520617578666C6167206F722039 -:10DD2000626C616E6B20666F72206C697374006147 -:10DD30006C69676E5F626F6172645F7961770069B9 -:10DD40005F79617700705F79617700646561646213 -:10DD5000616E6433645F6C6F77004D4D41383435CC -:10DD600078006E61765F73706565645F6D617800E1 -:10DD7000636D697800617578006661696C736166CE -:10DD8000655F64656C6179006661696C7361666585 -:10DD90005F6F66665F64656C61790043414D535403 -:10DDA00041423B0043414C49423B004750532048CD -:10DDB0004F4C443B0048454144465245453B004199 -:10DDC0004E474C453B0047505320484F4D453B0084 -:10DDD0004D41473B0043414D545249473B00484564 -:10DDE000414441444A3B0041524D3B00484F524957 -:10DDF0005A4F4E3B00564152494F3B004241524F11 -:10DE00003B004245455045523B00474F5645524E18 -:10DE10004F523B004C4C49474854533B00504153F0 -:10DE200053544852553B004C45444C4F573B004FD0 -:10DE300053442053573B004C45444D41583B00242C -:10DE4000504D544B3235312C31393230302A323248 -:10DE50000D0A0024505542582C34312C312C3030CE -:10DE600030332C303030312C31393230302C302AB4 -:10DE700032330D0A0024505542582C34312C312CA9 -:10DE8000303030332C303030312C33383430302C8B -:10DE9000302A32360D0A0024504D544B3235312C85 -:10DEA00033383430302A32370D0A0024504D544B69 -:10DEB0003235312C35373630302A32430D0A0024C2 -:10DEC000505542582C34312C312C303030332C30DA -:10DED0003030312C35373630302C302A32440D0A70 -:10DEE0000024505542582C34312C312C30303033F2 -:10DEF0002C303030312C3131353230302C302A3129 -:10DF0000450D0A0024504D544B3235312C313135FA -:10DF10003230302A31460D0A000000003CDF000894 -:10DF2000000000204004000016B300082CE00008A8 -:10DF3000400400205025000038B500080196032059 -:10DF40007A44CBDC050281023701136934025C0894 -:10DF5000021A030936B3914BE7DDBC29491ABF0CFD -:10DF6000290832021AEC0C2908297C1AFC0C290811 -:10DF700032041AF50C290832051AD00C2908320689 -:10DF80001AB50C290832071ADE0C290829591A9BE0 -:10DF90000C290832091AD50C2908320A1AC60C298C -:10DFA00008320B1AAB0C2908320C131DDE2A0808A4 -:10DFB0002A0D88190C2908320E1A370C2908320F3D -:10DFC0001A270C290832101A140C290832111AA425 -:10DFD0004829082A12641918290832131A2F0C2903 -:10DFE00008721402A7FF021001E20452038B803F63 -:10DFF0000401165A03494AD931E91D12010A1C02CB -:10E0000085C208342C01401A408C1A40193A405BF2 -:10E0100014A24A048B127A33380B02030406070851 -:0CE02000090204063B29106914C100002D +:10CEC0000000803F000080BF0000803F0000803FE6 +:10CED0000000803F000080BF000080BF000080BFD6 +:10CEE0000000803F0000803F0000803F000080BFC6 +:10CEF0000000803F0000803F000080BF0000803FB6 +:10CF00000000803FF704353FF70435BF0000803F45 +:10CF10000000803FF70435BFF70435BF0000803FB5 +:10CF20000000803FF70435BFF704353F0000803F25 +:10CF30000000803FF704353FF704353F0000803F95 +:10CF40000000803F00000000000080BF000080BFA4 +:10CF50000000803F000080BF00000000000080BF94 +:10CF60000000803F000000000000803F000080BF04 +:10CF70000000803F0000803F00000000000080BFF4 +:10CF80000000803F0000803F000000BF0000803FA5 +:10CF90000000803F000000BF000080BF0000803F15 +:10CFA0000000803F000080BF0000003F0000803F85 +:10CFB0000000803F0000003F0000803F0000803FF5 +:10CFC0000000803F0000003F000080BF000080BFE5 +:10CFD0000000803F000080BF000000BF000080BF55 +:10CFE0000000803F000000BF0000803F000080BFC5 +:10CFF0000000803F0000803F0000003F000080BF35 +:10D000000000803F000000000000803F0000803FE3 +:10D010000000803F000080BF000080BF00000000D3 +:10D020000000803F000000000000803F000080BF43 +:10D030000000803F0000803F000080BF00000080B3 +:10D040000000803F000080BF0000803F000080BFE4 +:10D050000000803F000080BF000080BF0000803FD4 +:10D060000000803F0000803F0000803F0000803FC4 +:10D070000000803F0000803F000080BF000080BFB4 +:10D080000000803F000000000000000000000000E1 +:10D090000000803F000000000000000000000000D1 +:10D0A0000000803F0000000000000000000080BF82 +:10D0B0000000803F00000000000000000000803FF2 +:10D0C00000000000000000000301000050CC000838 +:10D0D0000400000080CC000804000000C0CC000860 +:10D0E0000201000000CD0008000100000000000067 +:10D0F0000600000020CD00080600000080CD0008DA +:10D10000010100000000000004000000E0CD000864 +:10D110000600000020CE00080800000080CE0008B5 +:10D120000800000000CF00080800000080CF0008C1 +:10D1300001010000000000000001000000000000EC +:10D1400000010000000000000400000000D0000802 +:10D150000600000040D000080001000000000000B0 +:10D1600002010000A0D00008010100000000000042 +:10D170000000000000000000524F4C4C3B5049544E +:10D1800043483B5941573B414C543B506F733B50D4 +:10D190006F73523B4E6176523B4C4556454C3B4D6E +:10D1A00041473B56454C3B0000C20100FDDE0008F4 +:10D1B00020DF000800E10000DBDE0008C7DE000819 +:10D1C0000096000091DE0008B3DE0008004B00006E +:10D1D0006FDE00085BDE000880250000B6DD000879 +:10D1E000B6DD0008B56206010300F00500FF19B5C1 +:10D1F0006206010300F00300FD15B562060103009D +:10D20000F00100FB11B56206010300F00000FA0F07 +:10D21000B56206010300F00200FC13B562060103CB +:10D2200000F00400FE17B562060103000102010EC2 +:10D2300047B562060103000103010F49B56206010B +:10D240000300010601124FB562060103000112013D +:10D250001E67B562061608000307030051080000A8 +:10D260008A41B56206080600C80001000100DE6AB6 +:10D270001048494A4B4C4D44454647FF2021222344 +:10D280002425262748494A4B4C4DFF1048498A8B94 +:10D290008C8D84858687FF202122232425262748FC +:10D2A000498A8B8C8DFF00007CD2000870D2000868 +:10D2B00097D200088BD20008000C01400800100231 +:10D2C000000C014010001002000801400010140280 +:10D2D0004D860008E98500081D8600086B8500085A +:10D2E0000386000800000040000801400100000023 +:10D2F000001C000000000040000801400200000087 +:10D30000041C000000000040000801400400000070 +:10D31000081C000000000040000801400800000058 +:10D320000C1C000000040040000801404000000008 +:10D33000001D0000000400400008014080000000C3 +:10D34000041D000000040040000C0140010000002A +:10D35000081D000000040040000C01400200000015 +:10D360000C1D0000002C01400008014000010000DD +:10D37000001B0100002C01400008014000080000D3 +:10D380000C1B010000080040000C014040000000A0 +:10D39000001E000000080040000C0140800000005A +:10D3A000041E000000080040000C014000010000C5 +:10D3B000081E000000080040000C014000020000B0 +:10D3C0000C1E00000004080CCB970008839700088F +:10D3D000A5970008E3970008579600080000000092 +:10D3E000000000000000B33FB2BE7D3A00002E40B6 +:10D3F000DFCF513800007E40BF51FABA00E0A440B0 +:10D4000019DAC3BA00E0C840C2ED8AB90040EB4067 +:10D41000CD1F2CBA001006412AFFFABA00C01541F0 +:10D42000DFCFD13700D024419A97703A0050334172 +:10D4300089478E3600404141E75B9D3800B04E4140 +:10D44000C00A98B900A05B41558F943A00306841FA +:10D45000DA92C0BA0040744162B3C63A0000803F1D +:10D4600000A0853F00908B3F00C0913F0030983F67 +:10D4700000F09E3F00F0A53F0050AD3F0000B53FDB +:10D480000000BD3F0060C53F0020CE3F0040D73FB9 +:10D4900000C0E03F00C0EA3F0020F53F0000000070 +:10D4A0007D36AC397D3C3839EBDCF438320A7E39D4 +:10D4B000124C26399B6AED39A4EE83397F661E39FA +:10D4C000F6398A392B426539A48211395B991F39A3 +:10D4D000C3EECD39DDE7C637A5A22F390000803F66 +:10D4E000C3AA853FC2958B3FD3C3913FF037983F86 +:10D4F00032F59E3FD7FEA53F3F58AD3FF304B53F01 +:10D50000A408BD3F2A67C53F8C24CE3FFD44D73FCA +:10D51000DFCCE03FC7C0EA3F7D25F53F00404040FB +:10D5200040404040404041414141414040404040F6 +:10D5300040404040404040404040404040050202A2 +:10D540000202020202020202020202020220202061 +:10D5500020202020202020020202020202029090BD +:10D5600090909090101010101010101010101010BB +:10D57000101010101010101002020202020288880F +:10D58000888888880808080808080808080808081B +:10D590000808080808080808020202024000000003 +:10D5A0001DD50008000000006E83F9A22915444E25 +:10D5B000D15727FCC0DD34F5999562DB4190433C9F +:10D5C000AB6351FE696E64657820283020746F204B +:10D5D0003229004D50553630353000424D413238F9 +:10D5E0003000565441494C34005934004144584CA1 +:10D5F0003334350048455836005936004F43544FB0 +:10D60000583800414343003344004641494C53419C +:10D61000464500414952504C414E45004750532B1E +:10D620004D41470048454C495F39305F444547000C +:10D630004759524F5F534D4F4F5448494E47004C46 +:10D6400045445F52494E4700464C59494E475F5743 +:10D65000494E47004845583648004249005452490F +:10D660000047494D42414C00494E464C49474854B9 +:10D670005F4143435F43414C00534F46545345522F +:10D6800049414C00435553544F4D0048454C495F68 +:10D690003132305F4343504D0050504D005641529F +:10D6A000494F004241524F004759524F0050504D90 +:10D6B0005F544F5F534552564F00515541445000FF +:10D6C0004D4F544F525F53544F50004F43544F46A9 +:10D6D0004C41545000534F4E415200504F57455209 +:10D6E0004D455445520053494E474C45434F5054C5 +:10D6F0004552004455414C434F5054455200475009 +:10D7000053005642415400534552564F5F54494CC2 +:10D710005400484558365800515541445800534527 +:10D720005249414C5258004F43544F464C41545873 +:10D730000054454C454D4554525900616C69676E23 +:10D740005F616363006D69647263006E6575747216 +:10D75000616C3364006770735F706F73725F640035 +:10D760006770735F706F735F64006770735F6E6183 +:10D77000765F6400666C6170735F737065656400EA +:10D78000736F667473657269616C5F696E766572DA +:10D79000746564007468725F6D6964006D6F726FA8 +:10D7A0006E5F7468726573686F6C64006661696C43 +:10D7B000736166655F6465746563745F74687265E0 +:10D7C00073686F6C640061636378795F646561643A +:10D7D00062616E64006163637A5F64656164626163 +:10D7E0006E64007961776465616462616E64006D86 +:10D7F000696E636F6D6D616E6400766261746D69F0 +:10D800006E63656C6C766F6C7461676500766261DF +:10D81000746D617863656C6C766F6C7461676500BC +:10D82000616C745F686F6C645F666173745F63687A +:10D83000616E676500766261747363616C65007028 +:10D84000726F66696C65006465616462616E643301 +:10D85000645F7468726F74746C65006661696C7380 +:10D860006166655F7468726F74746C65006D696E73 +:10D870007468726F74746C65006D61787468726F2F +:10D8800074746C65006C6F6F7074696D65004E6FB9 +:10D890006E65006770735F74797065007365726997 +:10D8A000616C72785F74797065006163635F686151 +:10D8B0007264776172650066656174757265007285 +:10D8C000635F7261746500726F6C6C5F7069746322 +:10D8D000685F7261746500736572766F5F70776DF3 +:10D8E0005F72617465006D6F746F725F70776D5FEA +:10D8F00072617465006E61765F736C65775F7261EB +:10D90000746500736F667473657269616C5F6261E0 +:10D91000756472617465006770735F6261756472CB +:10D920006174650079617772617465006765742F51 +:10D93000736574206D6F746F72206F757470757479 +:10D940002076616C75650073617665006261726F47 +:10D950005F7461625F73697A65006261726F5F6EA6 +:10D960006F6973655F6C7066006779726F5F6C706A +:10D970006600616C69676E5F6D6167006E61765FFE +:10D98000636F6E74726F6C735F68656164696E67F4 +:10D9900000616C69676E5F626F6172645F70697469 +:10D9A000636800695F7069746368006163635F74D2 +:10D9B00072696D5F706974636800705F7069746329 +:10D9C00068006465616462616E6433645F6869679E +:10D9D0006800677073706173737468726F756768DD +:10D9E000006770735F706F73725F69006770735F59 +:10D9F000706F735F69006770735F6E61765F690057 +:10DA00006D696E636865636B006D617863686563FB +:10DA10006B006163635F756E61726D656463616CF9 +:10DA200000706173737468726F75676820677073D4 +:10DA300020746F2073657269616C0074656C656D2C +:10DA4000657472795F736F667473657269616C0077 +:10DA5000616C745F686F6C645F7468726F74746C0F +:10DA6000655F6E65757472616C006C697374206FAC +:10DA700072202D76616C206F722076616C00706F61 +:10DA80007765725F6164635F6368616E6E656C0089 +:10DA9000727373695F6175785F6368616E6E656CE0 +:10DAA000006261726F5F63665F76656C00645F6CD5 +:10DAB0006576656C00695F6C6576656C00705F6C9F +:10DAC0006576656C00616C69676E5F626F61726438 +:10DAD0005F726F6C6C00695F726F6C6C0061636386 +:10DAE0005F7472696D5F726F6C6C00705F726F6CE7 +:10DAF0006C0072657461726465645F61726D007060 +:10DB000072696E7420636F6E666967757261626CAC +:10DB1000652073657474696E677320696E20612077 +:10DB20007061737461626C6520666F726D006E6106 +:10DB3000765F73706565645F6D696E00766572739C +:10DB4000696F6E006D61675F6465636C696E6174B7 +:10DB5000696F6E007961775F636F6E74726F6C5F6F +:10DB6000646972656374696F6E007961775F646977 +:10DB700072656374696F6E007468726F74746C653B +:10DB80005F616E676C655F636F7272656374696F06 +:10DB90006E0072635F6578706F007468725F65789D +:10DBA000706F00616C69676E5F6779726F00747285 +:10DBB000695F756E61726D65645F736572766F0023 +:10DBC0006770735F706F73725F70006770735F7000 +:10DBD0006F735F70006770735F6E61765F70006D6A +:10DBE00061700068656C700064756D70006D6170C7 +:10DBF00070696E67206F66207263206368616E6E65 +:10DC0000656C206F72646572007069645F636F6E2B +:10DC100074726F6C6C65720064657369676E206303 +:10DC20007573746F6D206D69786572006163635FF1 +:10DC30006C70665F666163746F72006779726F5FA4 +:10DC4000636D70665F666163746F72006779726F8F +:10DC50005F636D70666D5F666163746F72006D6F98 +:10DC6000746F720067696D62616C5F666C61677387 +:10DC70000064656661756C7473006770735F7770BC +:10DC80005F7261646975730073686F77207379736D +:10DC900074656D20737461747573007365740065C9 +:10DCA00078697400645F616C74006261726F5F63B5 +:10DCB000665F616C7400695F616C7400705F616CB9 +:10DCC00074007361766520616E64207265626F6FA7 +:10DCD0007400726573657420746F20646566617585 +:10DCE0006C747320616E64207265626F6F74006D76 +:10DCF00069786572206E616D65206F72206C697342 +:10DD000074006E616D653D76616C7565206F722083 +:10DD1000626C616E6B206F72202A20666F72206CBD +:10DD200069737400666561747572655F6E616D65B7 +:10DD300020617578666C6167206F7220626C616E1D +:10DD40006B20666F72206C69737400616C69676E1A +:10DD50005F626F6172645F79617700695F79617793 +:10DD600000705F796177006465616462616E64333D +:10DD7000645F6C6F77004D4D4138343578006E61CB +:10DD8000765F73706565645F6D617800636D697857 +:10DD900000617578006661696C736166655F6465D2 +:10DDA0006C6179006661696C736166655F6F666658 +:10DDB0005F64656C61790043414D535441423B00BF +:10DDC00043414C49423B0047505320484F4C443B51 +:10DDD0000048454144465245453B00414E474C456D +:10DDE0003B0047505320484F4D453B004D41473B7A +:10DDF0000043414D545249473B004845414441444A +:10DE00004A3B0041524D3B00484F52495A4F4E3B0E +:10DE100000564152494F3B004241524F3B00424560 +:10DE2000455045523B00474F5645524E4F523B00DE +:10DE30004C4C49474854533B00504153535448526B +:10DE4000553B004C45444C4F573B004F53442053E7 +:10DE5000573B004C45444D41583B0024504D544BDA +:10DE60003235312C31393230302A32320D0A002429 +:10DE7000505542582C34312C312C303030332C302A +:10DE80003030312C31393230302C302A32330D0AD7 +:10DE90000024505542582C34312C312C3030303342 +:10DEA0002C303030312C33383430302C302A32366C +:10DEB0000D0A0024504D544B3235312C3338343058 +:10DEC000302A32370D0A0024504D544B3235312C54 +:10DED00035373630302A32430D0A00245055425827 +:10DEE0002C34312C312C303030332C303030312C3C +:10DEF00035373630302C302A32440D0A0024505544 +:10DF000042582C34312C312C303030332C303030DE +:10DF1000312C3131353230302C302A31450D0A0068 +:10DF200024504D544B3235312C3131353230302A7A +:10DF300031460D0A0000000058DF000800000020F4 +:10DF40004004000032B3000848E00008400400200C +:10DF50005025000054B50008019603207A44CBDC1C +:10DF6000050281023701136934025C08021A0309B1 +:10DF700036B3895C4ADEBC294913DBDD2A08083246 +:10DF8000021A08182908297C1A180C290832041AC0 +:10DF9000110C290832051AEC30290832061AD10C66 +:10DFA000290832071AFA0C290829591AB70C290826 +:10DFB00032091AF10C2908320A1AE20C2908320B2C +:10DFC0001AC70C2908320C1A39602908320D1A1E9A +:10DFD0000C2908320E1A530C2908320F1A430C2947 +:10DFE0000832101A300C290832111AC04829083298 +:10DFF000121A2618290832131A4B0C290872140217 +:10E00000A7FF021001E20452038B803F0401165A5D +:10E0100003494AD931E91D12010A1C0285C208349C +:10E020002C01401A408C1A40193A405B14A24A0451 +:10E030008B127A33380B0203040607080902040620 +:08E040003B29106914C1000026 :04000005080000ED02 :00000001FF From 531aa9e1b5b530c57e6e58ac3e76890654aa4f13 Mon Sep 17 00:00:00 2001 From: Hyon Lim Date: Fri, 29 Nov 2013 02:54:42 +0900 Subject: [PATCH 56/56] Update Makefile # In some cases, %.s regarded as intermediate file, which is actually not. # This will prevent accidental deletion of startup code. --- Makefile | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Makefile b/Makefile index 14720dc8b..174a62fe4 100644 --- a/Makefile +++ b/Makefile @@ -100,6 +100,10 @@ OLIMEXINO_SRC = drv_spi.c \ drv_pwm.c \ drv_timer.c \ $(COMMON_SRC) + +# In some cases, %.s regarded as intermediate file, which is actually not. +# This will prevent accidental deletion of startup code. +.PRECIOUS: %.s # Search path for baseflight sources VPATH := $(SRC_DIR):$(SRC_DIR)/baseflight_startups