From fba47e641d3ddbd490581e539f2eee4c30a1bf5c Mon Sep 17 00:00:00 2001 From: Vincent Poon Date: Wed, 3 Jul 2024 14:18:39 +0800 Subject: [PATCH 01/16] Update Pixhawk6C hwdef.dat Fix https://github.com/ArduPilot/ardupilot/issues/25840 The overcurrent detection of the HIPOWER current limiting chip is connected to PC11 on the Pixhawk 6C. --- libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat index 7872fc8e50a107..b35390b3aaf04f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat @@ -177,7 +177,7 @@ define HAL_SPEKTRUM_PWR_ENABLED 1 # power sensing PE3 VDD_5V_PERIPH_nOC INPUT PULLUP -PF13 VDD_5V_HIPOWER_nOC INPUT PULLUP +PC11 VDD_5V_HIPOWER_nOC INPUT PULLUP PA15 VDD_BRICK_nVALID INPUT PULLUP PB12 VDD_BRICK2_nVALID INPUT PULLUP From 35bdadb8ec8b01a3133507df24d01adb5d71dda9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 3 Jul 2024 19:34:05 +1000 Subject: [PATCH 02/16] AC_AutoTune: adjust variable names to include _cd postfix --- libraries/AC_AutoTune/AC_AutoTune_Heli.cpp | 12 ++++++------ libraries/AC_AutoTune/AC_AutoTune_Heli.h | 4 ++-- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp b/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp index b227d3b2f402f7..7e8c49297ec706 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp @@ -822,8 +822,8 @@ void AC_AutoTune_Heli::dwell_test_run(sweep_info &test_data) filt_att_fdbk_from_velxy_cd.apply(att_fdbk, AP::scheduler().get_loop_period_s()); } else { target_angle_cd = 0.0f; - trim_yaw_tgt_reading = (float)attitude_control->get_att_target_euler_cd().z; - trim_yaw_heading_reading = (float)ahrs_view->yaw_sensor; + trim_yaw_tgt_reading_cd = (float)attitude_control->get_att_target_euler_cd().z; + trim_yaw_heading_reading_cd = (float)ahrs_view->yaw_sensor; dwell_start_time_ms = now; filt_att_fdbk_from_velxy_cd.reset(Vector2f(0.0f,0.0f)); settle_time--; @@ -865,17 +865,17 @@ void AC_AutoTune_Heli::dwell_test_run(sweep_info &test_data) break; case YAW: case YAW_D: - attitude_control->input_euler_angle_roll_pitch_yaw(trim_angle_cd.x, trim_angle_cd.y, wrap_180_cd(trim_yaw_tgt_reading + target_angle_cd), false); + attitude_control->input_euler_angle_roll_pitch_yaw(trim_angle_cd.x, trim_angle_cd.y, wrap_180_cd(trim_yaw_tgt_reading_cd + target_angle_cd), false); command_reading = motors->get_yaw(); if (test_calc_type == DRB) { tgt_rate_reading = radians(target_angle_cd * 0.01f); - gyro_reading = radians((wrap_180_cd((float)ahrs_view->yaw_sensor - trim_yaw_heading_reading - target_angle_cd)) * 0.01f); + gyro_reading = radians((wrap_180_cd((float)ahrs_view->yaw_sensor - trim_yaw_heading_reading_cd - target_angle_cd)) * 0.01f); } else if (test_calc_type == RATE) { tgt_rate_reading = attitude_control->rate_bf_targets().z; gyro_reading = ahrs_view->get_gyro().z; } else { - tgt_rate_reading = radians((wrap_180_cd((float)attitude_control->get_att_target_euler_cd().z - trim_yaw_tgt_reading)) * 0.01f); - gyro_reading = radians((wrap_180_cd((float)ahrs_view->yaw_sensor - trim_yaw_heading_reading)) * 0.01f); + tgt_rate_reading = radians((wrap_180_cd((float)attitude_control->get_att_target_euler_cd().z - trim_yaw_tgt_reading_cd)) * 0.01f); + gyro_reading = radians((wrap_180_cd((float)ahrs_view->yaw_sensor - trim_yaw_heading_reading_cd)) * 0.01f); } break; } diff --git a/libraries/AC_AutoTune/AC_AutoTune_Heli.h b/libraries/AC_AutoTune/AC_AutoTune_Heli.h index 269d3047c172ef..c696c8674fbbd3 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Heli.h +++ b/libraries/AC_AutoTune/AC_AutoTune_Heli.h @@ -276,8 +276,8 @@ class AC_AutoTune_Heli : public AC_AutoTune // trim variables for determining trim state prior to test starting Vector3f trim_attitude_cd; // trim attitude before starting test float trim_command; // trim target yaw reading before starting test - float trim_yaw_tgt_reading; // trim target yaw reading before starting test - float trim_yaw_heading_reading; // trim heading reading before starting test + float trim_yaw_tgt_reading_cd; // trim target yaw reading before starting test + float trim_yaw_heading_reading_cd; // trim heading reading before starting test LowPassFilterFloat command_filt; // filtered command - filtering intended to remove noise LowPassFilterFloat target_rate_filt; // filtered target rate in radians/second - filtering intended to remove noise From 3dff46b2b277eef2d979747c15ece51885d086e3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 3 Jul 2024 19:35:28 +1000 Subject: [PATCH 03/16] AC_AutoTune: remove unused variables --- libraries/AC_AutoTune/AC_AutoTune_Heli.h | 6 ------ 1 file changed, 6 deletions(-) diff --git a/libraries/AC_AutoTune/AC_AutoTune_Heli.h b/libraries/AC_AutoTune/AC_AutoTune_Heli.h index c696c8674fbbd3..a9dfee98d698b9 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Heli.h +++ b/libraries/AC_AutoTune/AC_AutoTune_Heli.h @@ -263,10 +263,6 @@ class AC_AutoTune_Heli : public AC_AutoTune uint32_t settle_time; // time in ms for allowing aircraft to stabilize before initiating test float trim_meas_rate; // trim measured gyro rate - //variables from rate FF test - float trim_command_reading; - float trim_heading; - // variables from dwell test LowPassFilterVector2f filt_att_fdbk_from_velxy_cd; LowPassFilterFloat filt_command_reading; // filtered command reading to keep oscillation centered @@ -274,8 +270,6 @@ class AC_AutoTune_Heli : public AC_AutoTune LowPassFilterFloat filt_tgt_rate_reading; // filtered target rate reading to keep oscillation centered // trim variables for determining trim state prior to test starting - Vector3f trim_attitude_cd; // trim attitude before starting test - float trim_command; // trim target yaw reading before starting test float trim_yaw_tgt_reading_cd; // trim target yaw reading before starting test float trim_yaw_heading_reading_cd; // trim heading reading before starting test From ce48932f4d71a88f5cc4b6824055716dccdc72f6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 4 Jul 2024 14:37:13 +1000 Subject: [PATCH 04/16] AP_NavEKF3: remove storedRange member variable if rangefinder measurements disabled --- libraries/AP_NavEKF3/AP_NavEKF3_core.cpp | 2 ++ libraries/AP_NavEKF3/AP_NavEKF3_core.h | 2 ++ 2 files changed, 4 insertions(+) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp index 67298272ffe85e..a35a95920bd84c 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp @@ -394,7 +394,9 @@ void NavEKF3_core::InitialiseVariables() storedGPS.reset(); storedBaro.reset(); storedTAS.reset(); +#if EK3_FEATURE_RANGEFINDER_MEASUREMENTS storedRange.reset(); +#endif storedOutput.reset(); #if EK3_FEATURE_BEACON_FUSION rngBcn.storedRange.reset(); diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.h b/libraries/AP_NavEKF3/AP_NavEKF3_core.h index 322ebc6907ab20..d930bbb0fc5b95 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.h @@ -1056,7 +1056,9 @@ class NavEKF3_core : public NavEKF_core_common EKF_obs_buffer_t storedMag; // Magnetometer data buffer EKF_obs_buffer_t storedBaro; // Baro data buffer EKF_obs_buffer_t storedTAS; // TAS data buffer +#if EK3_FEATURE_RANGEFINDER_MEASUREMENTS EKF_obs_buffer_t storedRange; // Range finder data buffer +#endif EKF_IMU_buffer_t storedOutput;// output state buffer Matrix3F prevTnb; // previous nav to body transformation used for INS earth rotation compensation ftype accNavMag; // magnitude of navigation accel - used to adjust GPS obs variance (m/s^2) From 6ce7e179d7115f80f59bf466b0fe4c48f53c0540 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 4 Jul 2024 15:40:08 +1000 Subject: [PATCH 05/16] RC_Channel: produce error if feature compiled out and aux func initialised --- libraries/RC_Channel/RC_Channel.cpp | 46 ++++++++++++++++++++++++++--- 1 file changed, 42 insertions(+), 4 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index f3cecf7e4a4ae9..33be28afd41ae5 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -626,26 +626,41 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos // the following functions do not need to be initialised: case AUX_FUNC::ARMDISARM: case AUX_FUNC::ARMDISARM_AIRMODE: +#if AP_BATTERY_ENABLED case AUX_FUNC::BATTERY_MPPT_ENABLE: +#endif +#if AP_CAMERA_ENABLED case AUX_FUNC::CAMERA_TRIGGER: +#endif case AUX_FUNC::CLEAR_WP: case AUX_FUNC::COMPASS_LEARN: case AUX_FUNC::DISARM: case AUX_FUNC::DO_NOTHING: +#if AP_LANDINGGEAR_ENABLED case AUX_FUNC::LANDING_GEAR: +#endif case AUX_FUNC::LOST_VEHICLE_SOUND: +#if AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED case AUX_FUNC::RELAY: case AUX_FUNC::RELAY2: case AUX_FUNC::RELAY3: case AUX_FUNC::RELAY4: case AUX_FUNC::RELAY5: case AUX_FUNC::RELAY6: +#endif +#if HAL_VISUALODOM_ENABLED case AUX_FUNC::VISODOM_ALIGN: +#endif case AUX_FUNC::EKF_LANE_SWITCH: case AUX_FUNC::EKF_YAW_RESET: +#if HAL_GENERATOR_ENABLED case AUX_FUNC::GENERATOR: // don't turn generator on or off initially +#endif case AUX_FUNC::EKF_POS_SOURCE: +#if HAL_TORQEEDO_ENABLED case AUX_FUNC::TORQEEDO_CLEAR_ERR: +#endif +#if AP_SCRIPTING_ENABLED case AUX_FUNC::SCRIPTING_1: case AUX_FUNC::SCRIPTING_2: case AUX_FUNC::SCRIPTING_3: @@ -654,21 +669,30 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos case AUX_FUNC::SCRIPTING_6: case AUX_FUNC::SCRIPTING_7: case AUX_FUNC::SCRIPTING_8: +#endif #if AP_VIDEOTX_ENABLED case AUX_FUNC::VTX_POWER: #endif +#if AP_OPTICALFLOW_CALIBRATOR_ENABLED case AUX_FUNC::OPTFLOW_CAL: +#endif case AUX_FUNC::TURBINE_START: +#if HAL_MOUNT_ENABLED case AUX_FUNC::MOUNT1_ROLL: case AUX_FUNC::MOUNT1_PITCH: case AUX_FUNC::MOUNT1_YAW: case AUX_FUNC::MOUNT2_ROLL: case AUX_FUNC::MOUNT2_PITCH: case AUX_FUNC::MOUNT2_YAW: +#endif case AUX_FUNC::LOWEHEISER_STARTER: case AUX_FUNC::MAG_CAL: +#if AP_CAMERA_ENABLED case AUX_FUNC::CAMERA_IMAGE_TRACKING: +#endif +#if HAL_MOUNT_ENABLED case AUX_FUNC::MOUNT_LRF_ENABLE: +#endif break; // not really aux functions: @@ -678,9 +702,13 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos case AUX_FUNC::AVOID_ADSB: #endif case AUX_FUNC::AVOID_PROXIMITY: +#if AP_FENCE_ENABLED case AUX_FUNC::FENCE: +#endif +#if AP_GPS_ENABLED case AUX_FUNC::GPS_DISABLE: case AUX_FUNC::GPS_DISABLE_YAW: +#endif #if AP_GRIPPER_ENABLED case AUX_FUNC::GRIPPER: #endif @@ -692,22 +720,30 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos case AUX_FUNC::MISSION_RESET: case AUX_FUNC::MOTOR_ESTOP: case AUX_FUNC::RC_OVERRIDE_ENABLE: +#if HAL_RUNCAM_ENABLED case AUX_FUNC::RUNCAM_CONTROL: case AUX_FUNC::RUNCAM_OSD_CONTROL: +#endif +#if HAL_SPRAYER_ENABLED case AUX_FUNC::SPRAYER: +#endif case AUX_FUNC::DISABLE_AIRSPEED_USE: case AUX_FUNC::FFT_NOTCH_TUNE: #if HAL_MOUNT_ENABLED case AUX_FUNC::RETRACT_MOUNT1: case AUX_FUNC::MOUNT_LOCK: #endif +#if HAL_LOGGING_ENABLED case AUX_FUNC::LOG_PAUSE: +#endif case AUX_FUNC::ARM_EMERGENCY_STOP: +#if AP_CAMERA_ENABLED case AUX_FUNC::CAMERA_REC_VIDEO: case AUX_FUNC::CAMERA_ZOOM: case AUX_FUNC::CAMERA_MANUAL_FOCUS: case AUX_FUNC::CAMERA_AUTO_FOCUS: case AUX_FUNC::CAMERA_LENS: +#endif case AUX_FUNC::AHRS_TYPE: run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT); break; @@ -1049,9 +1085,9 @@ bool RC_Channel::do_aux_function_camera_lens(const AuxSwitchPos ch_flag) } #endif // AP_CAMERA_ENABLED +#if HAL_RUNCAM_ENABLED void RC_Channel::do_aux_function_runcam_control(const AuxSwitchPos ch_flag) { -#if HAL_RUNCAM_ENABLED AP_RunCam *runcam = AP::runcam(); if (runcam == nullptr) { return; @@ -1068,12 +1104,10 @@ void RC_Channel::do_aux_function_runcam_control(const AuxSwitchPos ch_flag) runcam->stop_recording(); break; } -#endif } void RC_Channel::do_aux_function_runcam_osd_control(const AuxSwitchPos ch_flag) { -#if HAL_RUNCAM_ENABLED AP_RunCam *runcam = AP::runcam(); if (runcam == nullptr) { return; @@ -1088,8 +1122,8 @@ void RC_Channel::do_aux_function_runcam_osd_control(const AuxSwitchPos ch_flag) runcam->exit_osd(); break; } -#endif } +#endif #if AP_FENCE_ENABLED // enable or disable the fence @@ -1328,6 +1362,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch break; #endif // AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED +#if HAL_RUNCAM_ENABLED case AUX_FUNC::RUNCAM_CONTROL: do_aux_function_runcam_control(ch_flag); break; @@ -1335,6 +1370,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch case AUX_FUNC::RUNCAM_OSD_CONTROL: do_aux_function_runcam_osd_control(ch_flag); break; +#endif case AUX_FUNC::CLEAR_WP: do_aux_function_clear_wp(ch_flag); @@ -1415,6 +1451,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch } #endif +#if AP_GPS_ENABLED case AUX_FUNC::GPS_DISABLE: AP::gps().force_disable(ch_flag == AuxSwitchPos::HIGH); #if HAL_EXTERNAL_AHRS_ENABLED @@ -1425,6 +1462,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch case AUX_FUNC::GPS_DISABLE_YAW: AP::gps().set_force_disable_yaw(ch_flag == AuxSwitchPos::HIGH); break; +#endif // AP_GPS_ENABLED #if AP_AIRSPEED_ENABLED case AUX_FUNC::DISABLE_AIRSPEED_USE: { From 2363e972bc9c19482bdaaf6ebd99b6918dc8711c Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Mon, 24 Jun 2024 11:22:58 +1000 Subject: [PATCH 06/16] AP_Bootloader: fix return check for otg2 serial deadline --- Tools/AP_Bootloader/support.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/AP_Bootloader/support.cpp b/Tools/AP_Bootloader/support.cpp index 9a02124b1a10d9..416e40d1e6c6fe 100644 --- a/Tools/AP_Bootloader/support.cpp +++ b/Tools/AP_Bootloader/support.cpp @@ -506,7 +506,7 @@ bool update_otg2_serial_forward() chnWriteTimeout(&SDU2, data, n, TIME_IMMEDIATE); } - return (AP_HAL::millis() > otg2_serial_deadline_ms); + return (AP_HAL::millis() < otg2_serial_deadline_ms); } #endif From 4260acb21a5d4de562dba032a06bfb606049aeb3 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 26 Jun 2024 14:59:47 +1000 Subject: [PATCH 07/16] waf: use debug option 3 which records defines as well --- Tools/ardupilotwaf/boards.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index c8d1bbbc42b2e0..f3b35585af3b94 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -286,7 +286,7 @@ def configure_env(self, cfg, env): if cfg.env.DEBUG: env.CFLAGS += [ - '-g', + '-g3', '-O0', ] env.DEFINES.update( @@ -294,7 +294,7 @@ def configure_env(self, cfg, env): ) elif cfg.options.debug_symbols: env.CFLAGS += [ - '-g', + '-g3', ] if cfg.env.COVERAGE: env.CFLAGS += [ From c8fe71b6b0bb32bb43526e603dd58c7715edc274 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 26 Jun 2024 15:00:29 +1000 Subject: [PATCH 08/16] AP_HAL_ChibiOS: use debug option 3 which includes defines as well --- libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk b/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk index 893b358f549685..9d30c86701c856 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk @@ -9,7 +9,7 @@ ifeq ($(USE_OPT),) endif ifeq ($(ENABLE_DEBUG_SYMBOLS), yes) - USE_OPT += -g + USE_OPT += -g3 endif # C specific options here (added to USE_OPT). From b93c9256c704c42852e729547a466ae32a1433ae Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 26 Jun 2024 15:01:05 +1000 Subject: [PATCH 09/16] AP_HAL_ChibiOS:hwdef/common: disable second core on dual core MCUs --- libraries/AP_HAL_ChibiOS/hwdef/common/board.c | 3 ++ .../AP_HAL_ChibiOS/hwdef/common/stm32_util.c | 28 +++++++++++++++++++ .../AP_HAL_ChibiOS/hwdef/common/stm32_util.h | 2 ++ 3 files changed, 33 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/board.c b/libraries/AP_HAL_ChibiOS/hwdef/common/board.c index 99c48dfd6d5fb8..618fe597ac1fa4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/board.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/board.c @@ -269,6 +269,9 @@ void __early_init(void) { STM32_NOCACHE_MPU_REGION_2_SIZE | MPU_RASR_ENABLE); #endif +#if defined(DUAL_CORE) + stm32_disable_cm4_core(); // disable second core +#endif #endif } diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c index c91e68930f547f..755290b765d919 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c @@ -581,3 +581,31 @@ bool check_limit_flash_1M(void) return false; } #endif + + +#if defined(DUAL_CORE) +void stm32_disable_cm4_core() { + // Turn off second core for now + if ((FLASH->OPTSR_CUR & FLASH_OPTSR_BCM4)) { + //unlock flash + if (FLASH->OPTCR & FLASH_OPTCR_OPTLOCK) { + /* Unlock sequence */ + FLASH->OPTKEYR = 0x08192A3B; + FLASH->OPTKEYR = 0x4C5D6E7F; + } + while (FLASH->OPTSR_CUR & FLASH_OPTSR_OPT_BUSY) { + } + // disable core boot + FLASH->OPTSR_PRG &= ~FLASH_OPTSR_BCM4; + // start programming + FLASH->OPTCR |= FLASH_OPTCR_OPTSTART; + // wait for completion by checking busy bit + while (FLASH->OPTSR_CUR & FLASH_OPTSR_OPT_BUSY) { + } + // lock flash + FLASH->OPTCR |= FLASH_OPTCR_OPTLOCK; + while (FLASH->OPTSR_CUR & FLASH_OPTSR_OPT_BUSY) { + } + } +} +#endif // DUAL_CORE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h index 828ceed09ca69a..7d78d41b82b15b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h @@ -191,6 +191,8 @@ extern stkalign_t __main_stack_end__; extern stkalign_t __main_thread_stack_base__; extern stkalign_t __main_thread_stack_end__; +void stm32_disable_cm4_core(void); + #ifdef __cplusplus } #endif From bf2ccec4d787536f139bb106059395a75e7cde59 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 26 Jun 2024 15:03:47 +1000 Subject: [PATCH 10/16] bootloaders: update Cube with dual core mcu bootloaders --- .../bootloaders/CubeOrangePlus-bdshot_bl.bin | Bin 38304 -> 40100 bytes .../bootloaders/CubeOrangePlus-bdshot_bl.hex | 4899 +++++++++-------- Tools/bootloaders/CubeOrangePlus_bl.bin | Bin 38688 -> 40092 bytes Tools/bootloaders/CubeOrangePlus_bl.elf | Bin 176244 -> 175792 bytes Tools/bootloaders/CubeOrangePlus_bl.hex | 4614 ++++++++-------- Tools/bootloaders/CubeRedPrimary-PPPGW_bl.bin | Bin 93312 -> 94216 bytes Tools/bootloaders/CubeRedPrimary_bl.bin | Bin 29628 -> 29684 bytes Tools/bootloaders/CubeRedPrimary_bl.hex | 634 +-- Tools/bootloaders/CubeRedSecondary_bl.bin | Bin 10632 -> 12144 bytes Tools/bootloaders/CubeRedSecondary_bl.hex | 1204 ++-- 10 files changed, 5825 insertions(+), 5526 deletions(-) diff --git a/Tools/bootloaders/CubeOrangePlus-bdshot_bl.bin b/Tools/bootloaders/CubeOrangePlus-bdshot_bl.bin index fcbf811dfc76cd912e90a5d24b5ef40230bc2152..a2281bddfe649696298906a6dd270c418c06ce69 100755 GIT binary patch delta 21258 zcmch zGZCxe5t{?y9tc}_1ECzkP}#r7_3H<}Ieszi^-ulJ75*K;|6hK^ zPy@ff|KI93{#)Vy!!pPJI7RpRXLnFlo z)Y8hnGU;}6+U%6l?bd0oLYavQct_3F{UVnP-%@Oi)>~Y+!dEK<*^4;cuV6G%CgA$E zFLBQBxo=zPi?_*4%H~9Ajh{2@S7p%dG1z}Mamau;gb>UAfI1=O$fh*EgjiDk zAcQ&y`41qj6ISy^5YMZ}Xw}l!FfO$;T}EF9y$Bs{rWkruK`WN7^k7lW+v035Ta!e+CL!nfU~~(T>SQcs^&u&FfQ8&@*~BAB+Y6n|_};7HuXvFQBh5h; zux%HsG%2Rndg+7r$V^{BtJ%2WTKwjbCA1LLqLQvF$T+;TtmikY6G~Ll*NXVICM&x% zkZY{8XV=l$8c(H=-9~X(vIGEVZKb`Soeb%H4PqONh}$M&cBCWi7=ajejItraVtehZ zZ2&>O%B{0)vrAL?Bmw6jX{(dT6RonRLYN6FVY#~AS!`<(XdkMiucN$1>$w zoZ|npa*GY=8*6qgOo&9k~#qSPp`s;LxI=nbaaw3;`Bwe3w)v9z0^>42m9Yi`?_F zfTfn+mePc}-ECNZuq3{gwudo>C(9Q^#(km5+6$A_2{|&As41c4_cqj+Y=2YyA|ee> z5eFjD9BI9DlYVMi_IDll^#!s~`ZyA?J_wtl;8cZpD2$9otTzU+7(yk4ry;aJAm2|9 z#*<Y%8NUNm+mtnaTV0oI&> zz(RZQ28Nod$e&9hE0qc6}_VbOM1EN${zZoYfn*+%{K8^#1bc~q0t#VD-Pf$ zRrdx}o|iN`TkMLSLG{XFR!lCA6Yq%`Gp4VffW5GvX+TnpawP=j3za>yA4#doSD}*c z#C(}lHTZ3K_ee3JU#NUWN z#E#eX1e*oMr)6__bK^2i2Z9vW{+(2aq-`g3W+ZjJhmf|F0mPER z@!Ixq`idet<8tvc;^DaQBR}7cSVEtFxIW`?4PPi=L)IQj+9vwrjQAg7inbh&5g*qs z9KlKz^6M#Vw;GSwQBt)#cHB29k)y?<>wV^q`&ov&m?iw2YurHB!22sy<>TfSNv1^3k*n4 z&bTLfja8(~xU90Oa+%_v(68sU1~adbp6=uLMF7?QU9AO4%f*Sw<&k>_5Z6Q6&l4My z?{|Eihqy$b%jPFBs%?#&htebGswBDB>@*2^n>Se53o7Y{-fV#>#(77sqZ!%utLJLr z4EYx7HA7HI2al1}C2Na>+F2yM1Cg9c$~lIR%9bpsY$=k&@^59aO|8| z-cxUl;;FOa477~1ne>R#5u5j08Bc?Cqw9q_D67WPC?7*z^DIgxLnUpc8xYMk?+`0e zZ{cd8$8hjJJg22_Tn2A)6=taWRMOHEMr!Eq@z%DB&8hD>j6gPj_pqJW%jxd*^akr+ z-HJa6%0BTRAbWWO=K8#3K$I=H4ni#%6j=)`tcBc~G$#p2YZQ}``JTI{N_f)>SiPE z&(H!{?LCd+u+e5m)(JAcArcq@kXm0mxcVJrg!3-lnVHNd0p&kFP}bvqKwmmNBcaN8 z{H(0ai8@Zh=0@ea?6h!Nj&{?+y^uB#|-iFX6#&5N3gfub(Rd7F1zRTl^u;Cz)dQvMk@6P5I-T>g$8HYTtX z3x?=Vd^>HN1M4?i3tTL(lALWU+~D>O-hVbEAQ95mKVZBfHiju>FzclH1> z8f&%f-@$YognjqXO^6#+0!K?By&}5}8_If|x6TIwZVx2Q%d3lOQT!bWoj$S*jyg7B z?r=Dw|0pv~S{gZE;%RCAJ$)rDcp6EL8c38B=0^|5=hwz{M$g8EXgJ*;3}Rl_LcagK z|B9D|b0J>FoVgZ`zk1{%jgyW{gLNUD`5w|oAdWi%x5vTSSz<@pG;tbt5EqC)aM_NZ z`m_>8-5#UR?Ja1H;VoAe0{%>_Iz>H-}}r3)zDq7bnQj?5ReUu6+lMz)qwG?5gN)2fw#}2rPvR|OxXyR4>l{w$jI&p* z_F*;aq9(iVro_MN(;V*rAtUK6r>YonG~Xd>xgD}m+hXnLK-m`Q6(<^xq$VdaW)$yx zxNoGZ05#ByH#UZ*EjkI6C+MEr0H!QXv@7yidHi|xbHJ=O3Bk{Wt@V>7Pu#j zefm(TxXLibq46c-Kl&8PawWo|FNRZ7DQVF_uc@2rq2JNwhP#pJvZsJ=^PxCcT}tOd zoKe^KaI?3CpUnT@onhSlFg6;Ck$%_136Iikm21!ahVrE%TAD!{*CM0hcLq6orTyI2 z%KC(-AMPkR-%xIuG0%EfN96m= zj%;-YYtbA%vb!W;=+uvSR+23F>1IB zqxqBPcSsFmV|s!Qagj4Wkr>7asxe4_IYt2yJEhc3;@W4>$BL`QOrow09DZ}m6WF2R@pi=@ zIRFfWX|_k@n-hU|nc&z)Yk>di)AM_lYWNbkM&IwP*|L;^6Q~UMgdS83DaXVM9M4Eg zfdewP7`;~WVCP(OcY9H$4`vo(B*Sf@_}}R#OoP>91Oa2RXUsZ0 zG2a7ZpvIvtn*m})@9oAy!y5fYxit4JBXd2bcB5RzZIo@f3yd3O^RSITC>!Ou=5om8 z3@g|u&x34U?rT*WNAkF}`M?xq0Hk>@gWP2h@CnwWMQ1 zYDFdE`yIMmq4>=K)J?IB?yYXUi>iCIRD^`zB%gOC+usVSMrhUpn=6W>D+}K`_$`*2Yq`dq9 zSpvnM*4tbjp4VjY`1p76Gl$ns7)9Yv#qH*V`EqM4kPq-Tg5qxvG_Y_a<>e%x@uAzzD4D|86n=!F24X5t>CL6m^w&cN+TCG3AMJ@`tsnqmd z@yXnD$0C6IHUtTKwNvr02_VxYH@Q;CJqFYy?5$Q;feh2j@LXGWb#mRNEZR+_b3B2` z7lxLPEMl+ckvcrtfq(C_)8rtz(m{Aj#h;-tCWgQ4My7vy_Ewu<96!orOI>n! z2+EULfAgq)9QE(WUXYFEIK#NS!+lq;z1v-scKTeIWMRW7`-24KF+kZii1LFF%0nTH z?`QqNa}+L~h_mW$_CN5lK8~F=^J2%*>+w2AV~3d!`qPxPz^3kW?-1AJWH>r|xi&IF ztwr(IxU}tLf6)TW?wHgn4xr^=b1jOzzpk^^#CO#w{*QXO7RqFT^X}v!xjj6>mB7*W zKxY^j7*Tlav=+f{uP0mhvKCG7y2&u`EsB40uygP(1wv=lu*!_+$sLY)(VMHMMk-=t zUc-GOf@Hd0a3ka4$|K%=)=%6@hR^%wnP0gB-tlcgza?myi9IO&O)uFk*OtESWzxU% zZWhCm4$?n$5L6v9+NSsudYyc2+pf?ho#(kAN24I@L!3V=ZmtYD^Ljo{9*(fYi+ARy z;U~mL^4G=pD%Gj?e z8JMU81IV<)GZ%Wqu%&SDlioZ(*rRQ-?cgrxQ;O8AvPeR`TDU6Y%EQgTKzQ=%7`XnQ za>f~BCvkjh-?i&|Qx(53P!BWki1_}bl+lm(&OZ+0%qVfiFd=r}Zt!E>U=!R4i zUs)UUX9hRQ=?Fz`lrtQtgij)e_j52Cni!upGDX61FMg*%TOlCnoYMl$lcsIv_xNkV zQJ*TV5x%_r9gW7xRCd{wVb*74#NBnFVYHPu%TyW~YxTtV;-WQrN{Wl!&JT--^_kHW z(`Hw!Z!*GDqGcRGx!ZhkaX)tG_Bo#57V9W^QFH;14BM@0H}Eu{P(B>{o{x*mfjePF zv}P>isTWHBHn!VJoui9g>w7lmu9x)Gdp;cP^ZedxoyYI>uHjF4^{_&(bG{hx%^*3onSfy>ohhj3$=6chb7Il6Q4+A=AQ`cm!`f0}%^ z<9J^fgXsXC{;nsbvrJM)=)DZ!OgjMccrZnx;y6CV6+J0Nk26~PeAnR)oir8((mz-; z3TkfkgxkD-uuXgb^PHixI_Ot=FIUrl)!FZ|AFG?Pxp7TWJ)!A;R@0J>PFRaa8?V(~ z`IZnd(J4go`R1Vi;l9mw2KdmRf35gKK~BOJequIkvxC^ZBs;=W$|uxq7jvdecP#0r zVeq$kE&&fq_|~9*Oy8L`u#m#)UGN3_Nk7Ct>r1>>Lj=8sw2?AU5h%>ocwidQOk?qOw6=P5Id~ z(;;!H5X$+A|A&4uD#Cbsos22UvrA1&3}x|s?nGIjxNt)AgdGSs{v4C>sh65ac@{z= ze{ydh{nYVrLuevMAN9F%0!rd>9%t%xN3=~aVb4s7R&5(?hOSJ2O9#*B1(MaAv~|RxLZo#2zloa=%lk)mx{~uE`|Z7AK1O_l6vO(CK(~dG|97D z(2E~TO>!&`8U-}wqL3uxD5C3&I6!1Rv;#>t;2PP(X(rU@_&K=eO`3{HP*E$6Jy*!XY=voOR%-0d~@jcudz4@nC)AG&Gx@|)!fBzRb0on$i>1w zfhl5T;P%s6KkY)1T6#|+Pj3(Uk@)DeF>xQkjRySjL2Y|fdcZqPY?+oYbwNEP%}~>O z@t#~b6%GPNZ;|+Vx~Z(^89O7=(z5}gLPe4V%0M@?2Jh;yGkcQD6+a~^(}p`fb)s=| z+{`$Ohuj3|{p8NP*~3e$nr=$2W3nvL2B!{`T-kQTe|ms!8V#3%u8J}b`1dIEOGuw= z;Hokq_nKm?;ta{F)2nD{Qvmaz0LUkoM>c4lnLR008)QAF_?HG4eo@uR5>ScL^IYEk#vq&4Ag!nAd#}Kn|2Rw9R zjwWH3SX1KSC5yUi>At1fI>xldqi%Xx9;wZ)V4Jj6MoFQgipKKQ6(gJW0h?Pf@P!=R zjM9-o<(tnQlO1Zap11HH$f$WAh|Qa1vwf4CW2ssCL07Di$Sec?Ny;Jh!p~6pK`$*O z!N}0Igoao+$Xs$l1KKqLQpaTarG#Bv9cYOMI3qGR`A^nxe8R4v-yg@VDc=_KzZjbIde3a0ZV3991Yp8=)~A>kl|Sr7;~YH? z9Uyb?xw`B#9URvi-5r|s=QZh7Ud2BQv?+V+7^LE$e~nySZYtmAJ>SJt-Ek#?e$#zS zj%?m5h~M9$n^bz>!)q*!vUj-Ym&mHr%Ix8XBeAiN=dXNx$NHq@OYL=(^g%x}8qWXp zTrXLh55*}nM(H@^i)t_jP^!AIv&ypi8V8Hc)Pf1#v`~=9GEeR8Sr;2;%G}2 zHK|`LwQ!LCX+T_QxtSWUmdLl24Zpq=PJp=w96r$m&kwr`4 z=wbH*683m_1889b6w6|5;Rt+8e5!C%5iJ$Spqx2a+YXZ~>VRAlJhs<781TLAzgi({?HT^`f_Me9TY4+9T5`PdeO4$8ayMh;4QJOnf^G=QI=d(459DpAIrqHH|*(la;nY##lm zL%?^l(ZGABj^wWcj48B%aVH!JRqFwc{H9ydBiG9rmgK60br;l2TtyPd-U+LRX6}@S za4Bzxc<}c;WDbWx=iUY0qt$c5YiwlpQ9dqOE3ml>pqW&@VkUjY_=_>!IXI?$aAF|S z(2!p6ga@%BGzd>fdU@6}c~^{Y6dmIm??BiWL%}53HdsNnvh{j&oADT}v#Cz3eOXR1 z(=T0AFADYalQrJjPkwVr{r340jae`&d)#FEu7K^$@jy@mnE$ASq#8nG;OJR$fNt0( zuYfCBgxN*D8a&|t7LLO&Yo89WQ*#cy<5j0em%vWpVTa5jJ49DJjVgITyrVdiL{AiN zbu_@~{><}WpKaCHG^JpOl&0fd_Jv^k+$J>4YX6S4(9&~9LuNutF^J7&yDm@3V+NvSgb^iey0bJ&E9LW&ag;jv}25jX~2ZcBr$V znOy~V39JJMjFQU#19+&np{ZS!&~jFGq9N3!H)aeOqi1VdlliDQQTE$pBcklMy9hCP zR=XwpXOE_oNYSGGoc)x{=AV+I^FamRA~Rj`A~+xb-Nl(4a;x@&)}(dEo8sNWOspp^ zUBi7TAL+!I|B%uAW-xi7%-Nj`=%VA&5$E%2()+yX0P;__T0HtWWmiz@^dhDkjfm|& ziT(mLP6E5wcgWU~QnI0%SUxsX(kn?!-%qa`+2bgSa3_YoP~k5Q;6cf!+dzV+1*4Qk z({`0GT*9h857Qk@Pfr)+=#%#eOdz^vnq8l+vKN;RYiW2CNk{t4yxfk>fAEGz16F%7 zGHt6leIwZ175@%!Tp-r>u<_IhHCpJ-GCULMsJYdc**ufy5Vo)}w$HNq2ZTU>4Japo?rytsnI z7nfaHQB;Er$;&QQB-<%{tI&$0CAcg!{jNYC?$BfY>mIn8XAz zK@#d1j9S}TT%(??_}40SyHT)S)z%h)bYipy*72#=Lp`I;!0!H0y%+0#M) zv_w%A&FpdBp8t?tZhufv&z=T_3lyfPxW{?hgLYzsMc*rmQwmU)y2ml;-eP+)_=+H8 ztr7psa|}X7HKN2PMiSF_VbA7Ui)+N#StCYp3g)!!6ui0EsyYxDx_d zUrB1>3F-^cAly>G4A;Ua+Fe>Ojv%xaCI)z?47{Vf`nAf8W#5be?)Kv#o&c7prYt^M zKUCoj7eN>vMgtkfDTjf%faX>R*xjn)<~L|Gnf3tQLk1~#dr zZ32HYk9Tn^C}|9AJ(@@Y8-_|o_y4mdth0Sck-RwbM=#r{43Lhe@kKRw2Xtu7Jp#jT z=EEIbi8et;f4<(@clG-1MfX4_9i9QM1%tCe81WMn-pj4XC8oSS!lU`zl{L8WGkMOo z#$_02JWSi+5xi1itiGhS@ryugE-~SWRzBszu#f_|D|oW)0_dN#wggL4TV;*)sz?#5 z$;FC)g1S=*I)QV|4Gn6h1DblT&*hER|I-^TqNF2z|EvicS)!CfgCn|D_`e-d)!=~0 zs!R3%8qkZs7|_24Q$^O}Sy&G;nr~|^sq=m@o}>#&q4BH_9&F1M;$SplXf)e@F`BJG zHDAz%cTM8S61~=U%B$0V?F}zjlRqKr=i zMf!D5*f!K#t-6jL!ukFFH-q1KVGxCiKMwenVGeHY;V!GrSw*VquUTLBqye=r-htszIL^r9LI2!EefVrf(#ImY44luIoR#@1Lv z6*Ypdm$pdvK*}m|9FYTfa_g8mW9E|6)HJ~O5)s;oLK32JHj+;F5?RpzcEJKD*V~XZ zEx_5%bd8+Eh0fo&U)4y38gGSaBoEd|f*Qs^5~<;sqzhH~xj)oMsEOgTp)qNDZ=#Jf zlQ38bNs)p0P$Tp~GhDVD9Ny@w>#C(UBW|e$aq;uv;w?s&XP|uPGzeD2=}B1$vdE6hV@u@j!j(GPWpYuMgd!xM6T+ki~*i`Na z`292JxSWgOa3@`#N2d|)svd1gJUEooo5eU`Rmk) z=PT612C<*-N-#EBSx;0F7sm0x19iIi|P5t85c?N1rzqo&1 zYVvRT@vfWsP9X>29t^>Cc?s0Ye(~#hrSZdhLHZ!qkhu>oo7z^hIHPPjbx9VVC`-j= zv8hZ?9hb!uW%D2tGk*&8uq>9$&!?&ZV15W-zMh&20Q2w1Pl*|~j={UcxwnpV9PZCp zUC@rfxQ!5Plv?T4o4}%>_~!-*$1K;&VXw_KpBmzCx1onLxwQSvjJ0EQz?k87NV*BeZCU_ zDvh9?j-x3snCx{f&3Jwu;VO{yutM*Hvp9r$30U;bgWQXU(M^hW5*X!wG%m7hxv;9F+& zj64vYgMGm-K=nj}+v}6w@H~ABYqhzTb+jS95)4YTKY9!GREE(Jl4_Exu1-y2*&k#b(l_8hdTAyemXQm z?)~&W$`GF8rJ*mk{&Dcr>HR7oF%z!>eF|Gv>t)MUhVE+QR8At?MkDkt4e9y7Z#jLy zVImB9>Roy=*gvA@VrVcXGz(M2mv0*tZwhvK!DRtXZ^FTlUG~Xs*%4>u39BX0?oAVw z+lG%9;79~P!^rUDP=!3V<~1jMbUs~A3pPibTHEGWL;P{#7)a#Q?U!Ch8;ksAf{ zT25RLp`&8b9n%>~ss?|EJCaL(I59L9O7cQ_j+v5NaFdhqk#rlR6CpkxhJ&$CQtKex z(_y$=0=LN}p15NIH8&{!c*lZ?%0PsT`FW?6bOWTOouF$6hRCv(l0FQA<5&9;7?ElT zV#nT%*hs-FuDWv^#W}^7@5~&_?;T`Kv&9BYg(Tj?o5w<2QK+JDB}@m zEhxq=dLmk-ENTJH5}3U?L9t;`CY+V7Mf!+ILEJ#^r6i-+wP-q&jk#<5oyGw|l1Bz_ ztAchSiePC$I|h{`Gw9I%8X ztRp8xW-&*3PKcR{IR;C!Tw>|sWJjO>A3^niLn+4j{I#qVa zlqFNYz!z^UnZ71Ewb*iyy&o=oPu1KJ2Qv|vNYQnHm*j$FIMG z4w4V!-40mjY?YhIj&WzVk%?j3pI#1106W=@8;JY~)OpqG=|Z^)pcJ^~rFpHRHAQH! z((adpt-?;L42^>l#2yb8V?qOPTe;M>3qn0O0q6uuSO`)$Hgwpb!(6Yw!zJ+Gzi%_Q zej(UWi9bf1JDZOvg;MFIUb38DDdfEa$-mOOXSoIrQpNvwrPoX9U8qDXV{;@6mxOIV zI1SdF;9-bC0w5nFY}(dTp+hhXHuQNFb;SfV`O2&8*7)@De3DzN{Z}P%~peldS^fI8MS1k3mm|hYrz%vd!Pt{41uF8 zU3#mqP`Ep}!P?gmk}kBU^J%-S5*hzgj(jF6s**BBmOs4_8#kBN%b8~E)6%DwmzF2k zPgh{yIGW`@sUSPW-Gy@~p-|RMd(HO}T`=VnJ6%;Mr%x+_Uv3(0gSSW19H#}UMDe>_ zqnL09*jB}VSs}V+IPKwtENG3jeGdM_<5bNRoy+%FxWnS%$euL%BZdVnVAK z2hP*vfFA3j1>!JfRJ@^S4%3F>zXZ78h0h?ZurQbDL{H@ik%`K7Nzk{@_J#@?J^=p? zj3pU4nGssZZUIe*UB~YNwDJiuGBv_oPQ~Be7@?9oESzc1KLgR$?assa;q9f2F9E~TxkNoP}VwLwW>W?JWM!{ zs|*Ws%H^p#E)*w^OES5}0aoe)@#AnbDF$#kq)Wm;PlTqt4iKK~qK(L?Jp%8rY(-!W z{wu7X7Tn*BRSnh{cfH^q+{KMTWN{uRgG5KLv{=$ z-E~Y9>V>Fc5%xn-z)qY9*RW(m@m24z z?udx7pq40bmBO@j2V1>^uBQ5AONuJiohvNlr@*S8l@qsF`HyCSz6!kFNtYP# z3c%^Imnct%@HqZAh;;u4M3Y;I;-$9jR$!f@Jera!o)%KT0HkfhO$@jNaG*ppx09v^ zwYG4=k{5(z8^eYb7d|jX!`m!ZmDMxF`Ugfk%(vK*Ya)x1mo~19ESfgE@&2Zjir=H8 z=Ai3NJ9%q2l=|b1)TtY(_8Y0AH&Tahr1sxP?Y)uu-Hp_%3YK2%$9i$PFvg)PJuNqL zBW)L}7Eq(lH&(ed%=zJ^jdsdcoZD!RhjI_Rnn+#_I%z7oqOr1+X}Wl^n?$=Gd@rgpP}z&5Q!?Ju=idO&)2a$|;hjLkvHz4DR#HG0UAo!gZ>kCy#Xs|?_)b;U zf-sb}6zlOe;#`UwD1A(+;_s4Upl0M?&G19bFs!B|=>JT)>K(!#1e1TacM){vF$jP^ zclk|oq;kZOKITKwEfD5HAm=Cx$5#NVe|QKunS8n~s!hk&w&wz474Wx$vhJD(bMV*% zUPwr@$lHj3|AZnQSzfIDrY&Q_1dqm02wOJbcPb)Voyi3JARy#c=fsqjqXP{0O4=O7|ExlI6^*H~{EVEKGpfS~C*MN~O%+M$ z^kw^HP+mD9HdZZ$btPW755ViZb_K)}crv;#KuUfKcPF_APrA;)TO7rIhte#5QKNTU z0AGFB@v!3X#-ogkK+Derv(G=&lsokB=s8YGLvY|7gwU+`Z&tvP#TL(`Vcd%UcI5{z zXCO=_B|R-`+qg+wzU0m3RX&bN6V|1E;bGuWYA?9c*A=Cdq|Q5h-IlE zT^Ag@2ehM#A1fOB8{JHF9$e|En7mZVvm4VuFI_uQQfUGnFpf`r+B!$3xgL+}TG?}o z|GOZW63(FKX}gKf1G^ZhLrEpzjCd}H|7+4|%EeVh(k9>@Erk0d8#eW|3 zt`7352W9uWxmt42gVWpzc!>pfFveXpnzmNK z1EfivXu@Q7gf9*2r8LmTVK%2sB{B4u@}HYkSJ}(21|j^JA{cI+&G(0gBL+pA#XpfvV?(A^_r0ayZw{2*N#cP2wE=Jfoq*wR5#$6ZLCyfe>431L2wqn}%(h_ZD-b2&naO=b8q>fw0AHCKZrTTcAr5ol zS6sENZ?#yiU^)R5k#U}gIk@-@VTDG0K10}JrO(|jOe)@6X=N_ZdC~d9vV9(8(8BH| zjgzzOgCGsJAId$cvvy<5wwsqBuE=(-3mM0ET`No|ddv+ss$wZcMl`0^zY`wV#_-c2 z*X#c+95ab5w*NzuLTicUJ%|~0WTH@Hx~oeBo)vV&MXjswy@%V zS0Tn+>!Wbn3!s7kQwA{=Ocg5ayM=vL?b(DD4$6gK<)bD(8*twZ?~J&%X8UE($>@W! z_YFHIs2m}b1Yv=l9159hKLc|hc=5C#VY5}`u?uWV!2e($Ja=15=9qLQkte1t=2xBB zFxVNeh(M#ogPqwY><)E=xc#RGs~-jRB6MUV44G@&WB&#^GUkf`+55JAijV{kWlTcA zKcmkCTb_(_s8e?+6V|%L8Ef^a1u&t=LTt#2AD(2vOU{$moOZUIl#4spav(FeuAPKA zv3qS2q*V`&Pk%G0ZBg3@yQi}Cc?o9)&-q>CVnaWn&WRvQUk#l&u4}8FBPS1u3E2GHpQwq4cwD+uo*Ch{vNWFjYW1i5%?TisphMaTfB*`!wl zrrVluD?TS9G5euH#}-U11-P89YEt)qHjE4UV^3&XBf-!T^zRKs*v`n?%q;xwG_#?y zR|A?*nL1RaZJ$Oa5V4jHAoz|@nz4LMc3vxJI>1u0$TP#{mbY0Nthafl+hX<0xJJ0< zQ3WyOL#(MFw)_H{xSvgl1ZT;;{W-SF_8jrWhsWgXAIJ-F5u{UlAPr~eMU-jc-vqK+ zqEriT%YgI=w-tm`q4IdD=zBPU(}5A?V^6#d%qaFyQ)>pBT0>fjwu$2&NwIB4NkkT4Pbf6ae3A@^g;;JSLjZNL9@y^tiFkdJ*z`yl&J?>J zxs^K7B;Hc@A+8ry>&oz5;_d4uQo~OiesWzF28wC<%?A#-2&&u3#aD*a-GvF~WOfVj z8$Jzjs{3!Uw&0RRcOG@u)91j;;&VCC46D<5QFvjd`Rwc6u@vF;lkKO$!W`x=$Yo9V zdmZ=-kAnL71vv9fOP+P4Th+ah#`)*vZSx7HuMbTu25b&a)y?Fe1(df6t7j&jI}a6% zSJdhc z+ZlJcW1GHi_PZl2)3d4sE>)e-k~dwD&A&aX#WTd=5iSfd_FujT3NNP zYP4lUk8{z=a@q}zmVuL)3r!ey@w|*~X%fdjmX@F>lU1toWOD2JiG$fU%0cnI$42Gm zXj0Bs!a}FC?E|M(mflxx1RYwmhtzD;sN5trg6jiFK(~;3e}(7yk3E6^Br1<3ISx9_ z^m$pgXcEXm^m!E0F!RB;ARV@6Sc27%rb6X62PZ;0Y{SS8en-*gnNazJ;9f|pLTOWQ zIi%I0v>})c>99Q`HTV;z&xcJjBZ9TG#rJz>mxgu>Hu-AsEzMAqyMon_4mT+VCqg>h zva)k94_72E^qaFg}HDoBT$d^DH^>2Q+|1-n%b!hErMGN0h0cLH8oZv$G10wy8y zGuW~B1uCERHwmv=XZ&1nAfkH~5FQ#!^;istt~)1k9+E>@sTWCXm9|+=LmV#ayEKId zWC#eY&#)yjpt)waLes{2ru!-S5@>r8T8J&CVOEq6NBv2B{D~wyLwxax96VP1_z8U` z+e#Sh2ZLcv%DiJ_cZJKA50(`l>sTfZb5x`-!1Pl^gyYv1EdqXj=)_`Mr-=_aijuyx zSm5nk#{(U!I7zW^JqrAtfG;ha|G(m+@aINL_HE?l^V`8L>9`uVoSD~MpS zc-h5OB)<3nW4N@+X1i!#ENo}`&zF`GZCay!cIibB)sxFX#cgdYFS0dO?SQW!YxFqR zB-^cGyE6q(6)!l`9QmaeEAmT|%R}FClkF2hGTBZK!Y&~438^{0bo}hb3hIBL(qstW69jV19)M4S`jli^aL8x6uh&yzXoNm&uDDokF(g-{m0nz$ zR+_vlt#mPj#$~z2G)HNIJwXT?x&j_;X+jn8_DLvDr~=1bT9+LFvoV^lfbtp6J>W4f zLX0fo75MA~a-v&95?BeGaVL?)0E-ot%oL0^Z)0;gJF282@T^!B`$d!s!-)?6u{J{6 z2@%%9U6{2#Q{4ithez%g?|@`eIJq8@o5IQckX#i`UWDXb;iP(loyj~3m6mU)aRmK8 zfQIA9{b6$G_s{7k9Sr*a8FFeOB+~D<4us1(LPq;=S;1i0UtGlc9WI+NSa!xmtl?}c zlHMJ}b{zOSwVo(v`+?b1>or`z|7D0-2PAeuA_C&)A&!K2JH#U)eimXA#9Ia;^uK|4 z6T~?X*AHm)xez}-5UtOIcpb!JAbtqq1)$$zE&cvgz{C*#VI2sjMg0T*S-o(0$pijT zectuub#&GVcNYVObL=@K7(g(bFEdl4hb8tqPT6SK0(2?)GeFP4f)oHd0j`Lg z#x~okZCxU8$*d(wSf9KVSlrjGxMMLGA9-TSPjv*P#n&3C+bG=cvs@U9^ZO6zDFyjbF&Jh;dn%d0Bu zD}(-PeT>gUzhPfid8R8e5B|gp4R50IhyVv~`iswWsV6D^4}#e|1(vO8nB&iMu|}sc zrgYf@1OB+awL+&os+6w4Mzn+21O)!7fOq6p5phOs`?QO3Od9Z;`_y0pBRXptI2;MW z$G-)YhVf(<7>n$5dF`y))>NB{-zfY;SaSG?HNity;XEjB-)-MX3=J*n?BSl~<$C_J zK^5YF|CYe+b_$?q-=fI6NF3?)xP=~as1O9?zbk&n~ zf;O-EwB20k4(XczwI(NStVt4>4>kx-!+LU_FylZ~;hU-QLv4(3T4=ULRgQL-RyTnY z!B*%zErgZE$<-U|r|h~)9W;yr1OEAe&>D*~%7-slZ~TqW$US#XrEGYuXZr z*eUUdeIMd_2x#zM7kqmj@~h$7H<0#0Sa{pqyxfw>GiJ;{gUP(QiIa2dhI09N6DLn1 z!7P?OvsjaL^R!zYGt4-=@0r<*LyIU23jzMtlLaAoJ_Tu#XCSY}(B;8A3wbRSgBA_u zqaiq&$`TDhOX@RmX!Bq`k?1Hcf z!gdIcL#TpqJA^kN5V$ROBlaN(Ef8LYuouGf5b7bUfY1(szzubw(u{_q@4y5_3dz4t zpl-6o4& F{}1Tk2H*ey delta 19406 zcmch<4R}*U_Aowk?@e<10ZnOv^o!mkEu;+}X$w*)+B7YfwgFl`bOBM*7TlDA25}Wc zP0ELYpn@0O(t?YiyCADjuu8!a5I=X<-9*6ULzg0IDAn}_in&SK-2a)R__6=}|Nigu zKJWAPc_wr2+?jLEoS8Xu=A5~GwVm3vpK>B4;$BlAc3CE3vmwnG$frX7Cn*1AdU3_C zpMUx8KjATJ5IY~zdPuF1zJ&Cjb>P|g-wJ;!i&^_$8~ybDzaaeS-DPNd6VkH(5r;EM zVEI(UW~}?)C-y%v^55R!0lI&3{zAkt{|6cP{>lHf&N%-YcmEg5vVR({|B2|~LWZHU zs7@pzDeNmMcTIcfZTP*xZkPL|qmz@-Wfoj!ENpDpx- zxe}AMVOr3K#8PR<^dY}01G-b(2rY-@LzWiOK|%l{$l>|pZ2&{rxq-CEj<{VEVt+~k zW=1&`;;wMmrx3sIN0-7rgbLe~VrjpESBi!(!*{l;tvfAg9$c`~QgVI61jdcCP&VR} zVo`s5D-s`*usFIGi(dzkII^FGlI4TeAlrt;oxxpxj-F?k zSHgCv+Dfhup(){jD#q|ekUn^i#Pk-nar(745;qJlKV^?=Rfs=?k$z}pRnKF~lgbt1 zpTk0@D%ZInl&`O|8CTLqmAB4rY^OLZR)?U{iaJ|i2kGpyD#Z5a5%(RytX1Qn4e{qL zT}2|Rpjc9S+)?tYJ4#uRZh_4)jnpIcrM7Bob!9rAV#j$%-0oru1dHUYwNHmJGhg58 zvRYg0^n5?6qi>>uW{XSQ;6i|CX^`UNz+dI5R-`>GUFA+mSJkH_wf2;xP9*th={qR< z4$6|DEE&p@p-hA_5y~`BrhzhzR(Nt%nsA9Nz&ar*=C@o_6zh31^|)zL2SOCfL6T)0 z8CGFeO#0~8f~}QFEBCZx?ZNUy$0=L1QB-=D`jLKrM0)!`dOP}st1%{gyO0u_>C^}5 z7Hv_c@#;Ced$yz(--t!*SxEJ9hz-X4oOXUlkIfM1u2$Ph$&kv4G?16H|jDTjRtyI?l+tQI;Ht6;{Wk z48Pg0;*p`ngE=%3iC@U1RZ;jpVSii+P7%J3yPXR43!~%b<%lqv|2Y#FG8-VpLlPl< z42|oBH{$h~NbHeuv#fQNV{xcdb!{*G@r|dc$14mx7Ov$Kl;V(cp~K`($L8?BR5> zHg+!(t7SRxLSH(JNpDDaXzN&$y;>`ZtX>7L=58GRnYj9WTRN~Zr zflADceP%Oa`(Pk;Y!Yru982x&6YftOi#G}{CTcCiBqTl@*0iH+17C4a?5O8+%PH{> zASbIgXFA7I;wQ2JNbahxz?NQyxjejW5r$j9(Mfd1J9ojC~UBS>FDLcm!v!YF<7;pc`7R>f~UVxCgT z&n#1knnqeDEzxTa1@-l$Oux9UzHYG`7~7}i)jAVM zvP9zec~Gn4s>6&xP}bC%*f0A)u>gJZc;W5T`^(JZ5tj@zZ`V^8Ioe`pqO8~%3h^b$ z{j{S4xh>GHuK;lh@!od9mZqsVdjuhcHPx=L zrfq0RU2CDvtIHJPq9cfNOd}OZgF-UCGjduDcCM`BYN1&nE#xTe)_hs3KmYGckEM;X*x2(xY1ZHOCD4hyQpBUR@Yv}0XW zk82jXne0%AXM-s-3s%Op%7M>iI%{|pEOIt!hJjD6cv@1pXwm5GHSn}JH(1_^rw}Nw zH(8XKe|tH8yd$AAz5?swL36zq#=NGLyzdTO^ReYfOq4KZa=^lGge3qB5N4*3UI9bp z0NWr>cnfjNK@etJ%fTOR#5CG2xUWKR(?Ubrat6PztJUnF_yfO8nXko|wPkYP4tZBA!AafL$e#mtn(ju1E8ccLN`NUyYuqRsdhp0AzE*w$ z|8Fqm{6d;OWukrs(#ruyn6uT{PCrxEn6znuPn{jdAN3XMarT}^iX%oO=;f>l5*5d` zb9`Y3CH`4>P_G?=3uDX3ux_=$Ko$pK7=`Eb9JMzn9MtQmmx96>{YdKGpwOo`IE%e+ zNtLrJf4oz_)1vgo=|)sA{^=mTxbUvS+ob8HZX@l{6kI%njrw!9YO%UuQ0rx=CH0G~ zZ%Mx~Ef|q%N%9`PiJWThHfcVxx0a63m}3E6Xu?IeiZ!?SO|{Z;5wP z94#EnidVTe!xCxQEPR$V7Oxg?cB6K(tZuCmWs}tLVEP9)SVe1tiJwr0yMLp7QJP*Y z2Xciy**SQq@M(6&P$i7pU%am(CGgGkgdgTW=E;Jb{hK6D7#X&CccJOGp`NhA1m%~6 z`jJlT6}m>=i5CjRqqLcIeMoeeRi%?6TTpG^xK7+Xi*0Pc-Sf0^V2a=zRgBXG_oxXJ z4j=w;)RWk$9*g}s^Zqc z6j&$CFx9}5X~;Thrm1k9RFJ<;%7ce|-7EES;9RJtp1C>LAqP%}Y8#69JRaxUR_i0e6$FA zjH9y0hLn7hrTpC5^x8Vc|0=ptD+jVdsGDLL{|@xNWOm7cbm0eMc3MoRvu<&F-NwTf z?fJ_MghGC(F@@w`3*$yl1*`9OqxFdgdXeEvuR;XZO1BHBxP^VAN9mhD*Z0e^a|h&P z4UpM?99C1UZDc#+cR;;n;l}79{J1b~%-wjVuxZRVJVH1&CNpnju*u@=S$2T-%X65U z@gTX3ARKn)a0R5i<^UN2Igk|GRTGu#U?FboJGlAqsj(RpJ}X={B{|6+2jgnr*Pw(U zcr3{9TzgkT+{*Q^T&XOMC)*JR786Y2;G-+?L?`}}-$oM_e>kV*4N&fq83V&#^&o@K zyRX4umjk~6EXdI5C3sF4FM2uMK@A8h_>!bICFn*M9PYh-(#8i_5 z_e9Wq0BGJHKr=pqrXzypr16ON2&i1@3pv^k2s?BoXakm;yWK!E;9%;eQ0wyPhn%WioD-DG}`v*xFoTtH* zFe)#@N!y7`M${|#DiN~;?G*W-1I0eNQgj&juBCE-2{HWWR%*1tO=Wc+A`*)B`)!Hz z`#SVDkH6X=2c87uaIHkU(73CfsH{E+bGI=(F1`e->f};uI-$hy3cIo))BDXRLhlt- z1Chp7NvO@sN_`pD;Be@}+-a-kug}g(eTd1Ef4&Ng~YOP;r;S zEY>tC?bq%3(ohpJR(cCoGO$5EGp1|>Ky*F;|OP2$o{zj1UBVK(2p0KBT>d-5z z7O1{iG(nhjTil3^!Rlks@BEs`68uim9NS|z9@g^AUO8~GU#PvU(D`k@rnQlu+=(Z= z>HEBkp1WR;v}PR#Y+mWZI=$nBelQID$@p~=XL^n|>ls+>_oXuueL_4$6)=*jQ`b5H z4l}W>IPa4~!(+di%SyC^D!8P)?uBv(z7380*1I-+oupSA_&P^8FfqJN%0ei1os^Br zg|vxr&UhWOcM?!63GbBBKv-t~KU`)#41eq;NooY8X#(NxE95_y;!Q1@T8m#?s)%1j3>iRol63V*7c2^5ra9wiKaS@N<3N8GBULUu(Z6?V_Ho*c8l2zcPK4?zvMl+fy}5>+w3_o+Eb#PPG)`0i3VsmE2Uaj(6`(zx)3_YL11{(vuz zKj^FDKk#W`EMDoJnn>0W!Q|}8c8u-|!yLdor|WD82U>gMbdz`j@%?1-e$_yW8ainO&eGp-h~FZ& zR*eyvv*g?z%a1pO1CRA?urXjAh69fZ_e{!5+Q5%9!m2umJqwL7UJIYJa*OcFq}!d! zJ~&Gm=6f$nAgxG!WAFQ24E=(nHPLX!xw4!XrN(S zAsyi55OCAwnk)@bCjl2+PS6wAJ~jt?r;4-!>ft=7Gd34{@Et*zBPb?L$7va--wa~< zFjU2}y7}por6h#6imjZ1_KYB~ty2}B;g-Xe z3EsHe(O%pcm#dGEiqmbA%%*RQj9UT5gxSRAGHy4L52?g>Iv%zyl}OXHk+4N6_N$!5 zH&-7BtIFL|MYUpOBxe=NeFQNTA${(g8^!6WL^cM$Bp*8Ja~g)6ho&?+deARW0uq<> zsYO@9mt9o8+Jj*8F0Eh}W`N;ksUXHNGA{G1wFD!q-N&grWrKKr)`*Q$>C>cRTb=w? zAJZL!6|pgX9MdS7t220brpeP<$&A+criqm5rVr(^ZUuL{Z-J`#X3>E?t1c?dXImtM z7(>2yk6p`uwMt*BuZM|*^rB2BmDbf>S-J=8k;lV&I~sXfir=M?a2)YVWgZ}`BXL|` zQ){Nd>HKl{fpJiL;mw8c`_DI>hT-hhU|~`KQw-Z?HH8 zOx*j!yKG*cg6sKqm%oH=Ih102{roO}O$2(`%@s})vC4I5JLvPb!0LVj(yNd%+dl0= zYI<)nPj3wexDXQhr(`E|f^VARnS<(%xU7(`NyxiBsi>-v5{s4eKD;*{mjB1F)0xH6 zM!Kb{XS0nFDA5@49wPB}CYKOP%hcRs+3}+#o!e7lAZCd`~1~b22GTHXSDRsS+XI{GKgRa4Pa#9EfZb*le zbIzcw!#-N{Ntj1ll9~oX*Zv_THKFap0Q!qW??~Ftt&{_I_H%lqbMb#=AL96=?cu;p z!4J&5>M7xwy{Dz}E#bi7h#c2>D|oso9C#`OQs7y?Y?@cI%7;cfdsc$t9cKDMS$#$$ zQVCCc&Z*X)Rb?&p$$=5zzus%Z{&ZOGYovx6Lyh1&+r`x1buEVeqla$UXFn{(?y9<0 znG4L!`rgMa`cjHNs9ib_Y9&a*AI-TVGr(ZK=-n1H zakvHL#$B*2J(1P~o-!i(Sv=cq=E8wxLE%U9WG)e^?uT=#2^71NhC_~tZo>M>{4CxK zeE%yXRF|YP;eaV9I7&3;RuFS%JDKW~IJ{TEpKGOln&ebul1se|Z*JcioCBs%?8OnS zc|5h3@MVCxhI)mMOGf0Z0VM3P=!#LpiupD~PH6XotZ%Isbp+LiLV_iOp~Sz11e0Z0 z&gNd_%R43BbWy23qlTq3Jz}E(e|y9<+?n$HCM`hWET#P!r-{ z03QQ`^r-h!9|b2g26+0H;I?Eq3uH=17IQd2MW#@pH_BKtFt#|t7!p5q{mfc>aoD zhK}u&T41g0f;DmkYLLY{&zn+j1}iBXm?2f`40{K4!?8IqO+woZz()>gWhnLLHVP86V>K+rc|MzL|sK9xtgnJ#vWn0hnR-nPJth+dOUM7D;al2ecC1Vt^HX zp94tNuYof1n`O?5T_a_iQ|psfomVb&mx>&nv^*TRUnV5~>P-fgwng9%yhL1PVC4ic zNsfCz@^L!-c4lvXphv#NbARC9a+GIJM2=+xJpa)fWpa0f$xuYDJG~QkBWE7 zx)R~h+4JxLx@n8F4EFNfKpOd%;{Jd!Ot)NeG)D}nMF)=ilvy@dKKH`1xz8tjT{ea4 zd0x;>9Z9mvsn4)wVEPn3k659wa=bIf`reZ57K1wlP7%}dH(Ate)vJ`}7mS#WsO}Q_ zaBt5IO&J`u+}yjzA!ZScZ=o!uRavg(zo^6F6Y@HU7?ML7B~EgK2it*We*p(ybz2O? z5s>(X%vuq6Y3ml{aqo8}=#|#@yIx3&0YAMO{Pa5KyTmh!7SvLtA$se5=G2n7_5|yx zT6z^WCVB^3n=FI9gTP^VhO_jz@=rm2TIw5s`v`3ENaguRmug#JyHLBJmN=$+wnSaN zsEnFN@Mt{0t`if%8Ut9JXE@z2&_>}XT7oFT93WA*0RoGvLJrtvn@w-GTvt0v!7S0+ zNI$T6`8aaBQk4+Bg?h7b&Qd#U{uNo^Cf2waXf;D-O3Qj&bC*Jh)Fp-}^U5c1grzu$ zfTltW6drWK%T`WDN=v{u-E2E=ThK5>*>~2ZYp!!lQ@54$Y?uXaEkdVtnDb^BbLx(o zdNrS73&G*@=hwS!mu)o-iQ-hM*R#7WQB+X0M-F`XAN8XLRRfp6591+(8a^YHQy(lr z{&{#PSXsrMHA~J&)f6Q@+OKZMBzV;r9eOy7 zv)$A|2L$O#dYU2w01{6Am57TYA|4}Lnx5iB$k_%W6{w|yU`3VZGyH;DB%bca+Y4L4 z#rHY}=i%EjCQknjV3T5-L3%xC&Z$~prC@EHQvX!#`o%E)_mi_)9JnyAc$HSVImwKS z|MHUdqc(^o9^@=|{(i6hJCHX!ZqyJioba3DsQt zg6v(_SDk_P3QsP+4lRvckK^pbak zfq#N|_k-u^FBq^y7;u&kFmQMO)%O3+z<-iXiID#NFG!CXAguw?>`$Z#wk=H~MMYkpUEejP1Wr>YgA5*F2 ziJzzr#CX%I=q}@k0Z_u@@%@3AV3#jC3Fo?d3K2Je_4w!bizC zfXu(Wc>FEI_6TAUEqtNc?3~y(YWk=dL|0DkXZ*Pl5!g4xH+RP_DHi z(Guc7gASj-MYOB-S1r<^#lc96)PWW$&>|<45^14{v|ytxA{2&J04=BZ`(Uz_kVzV7 zghX{HG17!SXad#WGZ{4W<(rDaDG=7QATGuVA>1-#wiUti9grY~0fbmoj?8}}WoE?X zz;huF?N%Z){kW;EU^>dtxZ`=y#oj#7z6tP4E^AnNW+71OS3!}hwJ=oyCO0L* z2axWP?!hdZ_Te%GKhfS(uT_n&P4Og)EY`SP+OOa=S|W0IkE+TEW(IjMV;d>#aV;kr z%a8%r6W~$}fxlA3o*mGsJ!m<3^N)cyRU#JyN-;KBFO21s>a!c6 zZ8c1m`@wa1+XYrjS{@3I5?yqGEsA-SGWo2cRypJ>Cp& z3WMRgdSh8#je*}|zdLP@jcABL=kxgkX?Sa2;93}OpUijK^Pu_HVbZ+IM;iYtEJ$-I z6Wo#Qjpz&cb9VEeD_?$lD;_T81M?Wtx| z2tJy9E~rqa2e(uLO@T*rziUzUj+w-!z+zUgC?lVbYWc@NGH1Q3?a1i5{-R*~O^S0| zF9lZXN$~R((sYFUBT%Ouo;8Zy4KYw+1m@G>=yJeY#P4oUMd~bqum>{y5j?E7CRcGX6aJPHzM zs8mJ>j0Yx`c^6l#wx^g|Lyi85n8+RxEQ$n@)R8*6$eF>}v*^IxGmGp65YM>pfW9F~ z9Gn37sMQ`S*V%K|fh$W=R^c2ZzU-nRzX*P}x-Lm`8wp0|UqCt*{)x^+;7wO22hId% z`|$0~o_PlfeHAknjjX7=B&i!g$+(B|Ka2kxSSrpQ!-3WIq-$(~vqyiRC?l88iLm94 zyi0|5$SD6>-5Iu>_IU%;`H7FUJV`jGZT-&H5ShxBqDbaHn?bmnY`u=m$DS4Ska?4vh}GALbC=&K{Ijt{&#`lbRVoq=a3c0^)4 zmn4Jhe%~c2%T)&+9bzXSmwW=@b{g_(Fc@8aS#}}x4vjD*>K%F_cthi7;QhNB21O)e z6}HaLNc>pt@)1M8)Io5NHS3;lw0o_D`}2Y#x9MA%A+HjKGZmlXw4w zn^RCPkHB7l$-BI0y?g>20VeyZ95`{5a0Xo2PIOTPz~RG$v%+6-2H~|{;Ok*T>DLOE z7YxtXC+C1QnT#OR1J}xw7r2b79#;*yz9R=(grRreZl}dD(i!R1a*D?-+Ett#9IinM z++c(~N<84c)eTDA2k><89W)+^mJxV0z@*+2(R$Dgu&@W}&4|{^C-tTs5suzHmP(L? zYj@A4PKJd$7HWoWkcrJ`gC4~E2BJTAAvV^|2@MNJ6YjS!G!APFlL-AfX>Rp{BF2Pk zBtCjvxUeuQer4oU_M?>h1QAdH*neU$i( z@XbB9Lz({GG58x{*1bcW{BaDE9BGNq97(34zQ8*{q<_B)7m&{XJfc~;5*yOSoB9HO z3W7Qmr-wnpj$0$|XhYqNw1Tg$AIvB77i^kVxId)r3v3PUs=ozq3g&@Nj+ow9EC%7M zwR1X@rlm!kM2N4osR8*aKps7M9d*BOALslhR21LB*?^u=ZG6`Jwf*+eMfHkCJxqb! za8p8jmlBDD9c`2zWix!1j&|hmC!`J4@g}pxEbI$d0OLBzQH{k-;W~SoUEfMfO~Qs| znxlhW>5?{^6nffG3hxLXajlHDX&Tb+v4H>*&=zSkS8AsmY2@atR(Siq5xPg^I(v)# zaQimN1>O*wVuA<3!lFcND4HjRgdgwA2Px;+GVyYu!uCDIhK0f!LtNA@AiChV&`>i? z^H>-g7!L(XEct-Z+Uzr0n|xTT2@8Lz8Nn6>-|$i5=%66hjL1|6o8bWmfA34yL2o#+ z0FAJLN3Hf{!kF3&!@c4DZ{z;U+eP6kpenY&1ls^<^H$-ZTK=vmD^U~>1P_yaIu_jY z4%6Vy&C}Z;_n6u7E8j+ zy3~YQn4)+t2#?ljQ<-u_WF4P?nHCRsCodg=Ra_32j5iAT&yK_&3G<)L8FpR5O)-8I z{=|<4>-a4DqIM)+mxQKgAHi=63D1q83d@B%p3|w7M%Or|k=uQ#R+oKe zefiQ<#O$y>6-(}nVrz%2o~N-kZ}WZw^Xn=Rj+R&?Ha zgTw_+@BnH-Y$xQUwMsZ?lU4h|5qwI?G>cM|ffzTEJ>~23V%;sdma%ZM(2!t?fPAxmpcakQs0Z z^b^S$MWyaYx9@?zziQuYDRk@ji}uUD-8L~oms##Ezz(t4h z@^RYkBtf^9urD(1w-(q%*iPV!2|oJFaz7v2*barYrC!@g+ve5MQ0_TS&NH_rByBgg zA{}MZ@bdwy<2aFIMXSTZ!DXhfgq5bL9sVEP;RKU-X(#JJh26+$G#*QBC zMk%qTT-yg-IP1eM)tzKFqr@NDTbGokUeOe~(|G|FJ$0TTH|Wt}JI(DW;GB6%r=|+14_VVaQa&S-n2u8(IVunFxiFx97;DRtB%5OzShFkOQa+SK9NXgcV@MqRuFzM1n`(;Hd|h5% zBurW|!U@ipPA<0e6#Sl+SS^8A?YK&S^T^rwZ!)^+vQhqYEC)UufC~YJT`5vN7vQ4< zumj+?2H?#Azc~Q!1$gfO{64_D2jEVCGj|L;^ufbRGIewFa)MY6Y?0yiQr}?VpG!t9 zQB@b8$ZQ;@@LXRR&*GvH%l z@?t5{5jGKlmJ=CnSD^)F}wFAGnu#YO!$W zf!QQeK3M*sqfNn2Jtqfjy*k*hoU#(;&NDJmC8{xXHSbHwdE7aDjU0GLHd3Wx7JbEb z1zdP8$o2ILRDEa2y}3m)cqa4Uq8#jYyF=vK;wJcfrvz@~M}6~0-S3055N^xLuL-RW zYMr0M?QBN}m?yJgIaQgjQE=FZ2Y1prCFO~H$ng9qF;jI(I&+Zhprgv(h0iH4EaTa- z2+=-bC1dy?PuB;V``~}bnaIrD`v4m`|bu;njCAjPl%f=#76ojuiUFHRN zGfY${L*CgEQ~Zo&I^5Ff@w#tRJue5&he1^N(3T_ZbOUW*?+9@^a{G{+t&rh$kBR?- zFBv+l)}q-?H38tm2>nV!Yg)S;_#g~kEBFus8T&jS7_c!Q76ienrxp`!8mJn~lMr*A z2jWDkTJNNG7GyxAToH+2PV=%lxWyK8Njl+DiVS^8dUu!dT1?zAxT8MGb52TDf2`7< zAva%Ge>~gnS2`2?-sjtOGjn(`1-&2#MgkhcF>WGi-ZierOTr2nP}13snsfNnayc-J zkU0i%5pu=i`8}-!Wg=XzIP1ybW4kNVaQ6fpDm2vk5+G#w#FGpA3CFXYt*Y zeG4fezyLxkAS^G1yNSepXq5wljyR?{+SD`Gz;yc{sDLs1xG&#M^II$hwu$bz%Gioo z_GJ5QZk*@sLM5|oOp1XgmzT*!@^{Gjc{>R`A-Da0xCHFDA9?|wf&5dZD?fu>?u5qD zjWOG?63R=hr$Intx^9#tl|Jr)St^?=L13eTfjfdqSpT=fQxGn}Abm27Zw^1HG8o7U z3b`vT3?a?QM>non7;VwVq3UhIu!mpIDhiUXTmoJetPj^i$yv=c^i9_sR@YpErw~UW z+_eu1Uq4*y+z~d|_!U#Y`FR`kcx%{b*Vs_&4x0n)#k;}*P%I9(raKgNM|3#OUTRxw z7cA<}l3I~n4y*~+tv2vRX!kq#pn+@O6=_uzmVB?-IJ?51iA^@Gn2F`UD>CM|6+iee z_q~rCzs=BogGJ%B-EU`GLxIjd_~2&+%=4d!afg3NXy#9ZN`65|6(N*oPif8NIeRG3 z(f4bjt0F{+1I#BhJffvs_Y2QGGA!K%68p;`xLX8@D{%E?AhEHRaDq+c^Pnu(`apiH9TP$&>d7GlUL{n{dOpQH_b!VmVg;WUp_17@|KpL-s^|toSZbZK;sm*&J{;!8mP&5^< z9y;8;E|P!%bI@IREPJJx{+VTqVG!>Z(dOJK&_ z1hAuxUJ1*@c#pTj3SBWbS>}7ESqEzu!{&VsHgZ&Z3Uc^-NlRe%6aeG_zTF+6I@Vig zy<#gA_N*H9z+K^j`iroK5YDOr2K{#djWqCo1T!LCZm`3yVZR8!$&k{)^*h@&upCdJ42r zq~Bn&n3Ewc2A}?*DW(&o|19JZM5VWwK_6=&`g1=yrDh469;?D9go}^OqU_s*v8zAC z4+=L|SK(>G)W^qBA9WmlDN6)81mvHo*uykWmN z$ub1AGO=4pg#OgK;8P9Z>-0uFY_fFY7YPyzH=DloG)?=O1eO|wh0YOi$!;`u$c3{K zy5kSRdS_;mQ8pIA^phrg>b9m+4+h!#cR> zs=jDXTk?C0Sv=%2(Pt&iya{K!X!6cvH9mU@8Ky503*l8X$3ouTu0` zCQ`mCyboYS1YQwd01qq zUxyn2j*|RWcpSh{lIOzzR^B4{S$HqNQIdZP*8?0S`C&L0U?2$;PlUS_kAPHIZ4n#_ zs=(Sg4j)f$LF5C1*fX$R?h8HL+hT8-TKwar12NrJ7+jP?^_X>sZo0;0dC3#X1;>2j z(7gFPv_x{?qh8&{*ihUJ-8GulH!|Iu=!@WxNNSxA1K2c;{K|nQ9vMEnEw1LoVxeK}Mkf+|?Zl3z=G9oSjvOUyV3qg4Vy3_N)VVfnhu#FEMjwI!9QHIWwiskTYNE9-`4Pp+I?(Oe7v zgrF{^Zc@dCy6trf78O>eLb^~(+V7p6YBLI#*QGhfRbE&G+u-cf#bYWLKx$r`uOCyH zWJ`j80Eyv+ylK|ddJ8CUpaBQdLQ0bxf`K7t4>bGM*&_-^&K{t($U72uj-E@R@Gsw? zpWj(U@(?|=kdr@hp;?iGPdOZZP9Tv1a|ZlF7;V_X=5sbwN5$X_ib2yD1=}A7n-~HO ztL}ta7zvx#!mP2vu#KWghZ3KpHi#h`U2lT&O&|}@)*d!ggh4V^G*PU18^2{1LWSm80}+_e+qdX zA3HeFLM?u~J`E2n0ux1EfK=_DQQ}uA*dm_{ySTFSlMnSq8;4#5) zATh!iT%S0K5O@&_=pFbW@HzF;*(Ytn^bO;w%Wh!}WJle?kqueY?`7d%8^(hwPTDvP ze(&D6I)&@qv*g~gd&=%E+f(ZUqlMbR6yS#dgYd(~q7m_KPZy(a1`ox1b{(9^swJi< z4$kN#d>ZQItC@Joii?;QZ(rE5W~M1yvq8ykV0PQ?ri|iIrftXWSE8sHULOYkrnp5m+Qi%g|n+2a8w%YRe52$(Io!$&nZR|gl34hSmt50& ze8i-q;Oltzjk}*GY%GNCv298Y!FTkS>krh0L0IFr&UI$y5U2bgo;g2EPZNigsj$Pc zbV%!L@cmiaiEq>-zSWUdr5t;@O&uC0vAOMpdS&}>7%UhJvW%B z#P|3xoT>}kR5Rd{3^+|E!X@v*BLe9)NLwN8gtQUT z?;zDcYK25FJ_`ZFRgl^sy#nbCNZTQ;hqN5hNk|dOapXIE z&^qXw+Gxc?+im#XH|9Z~=YwH~%t)$*p#q--MOwih9nH{UcuznzBn`YLFhNBA$Xy9L0*A5uBl`w5?J&}_C6A7dL2VQdvp#T5? diff --git a/Tools/bootloaders/CubeOrangePlus-bdshot_bl.hex b/Tools/bootloaders/CubeOrangePlus-bdshot_bl.hex index 3b7850fc5a908c..14c08d15d9167c 100644 --- a/Tools/bootloaders/CubeOrangePlus-bdshot_bl.hex +++ b/Tools/bootloaders/CubeOrangePlus-bdshot_bl.hex @@ -1,2396 +1,2509 @@ :020000040800F2 -:1000000000060020A50500086D1F0008251F000838 -:100010004D1F0008251F0008451F0008A705000800 -:10002000A7050008A7050008A705000895730008A4 -:10003000A7050008A7050008A7050008A7050008F0 -:10004000A7050008A7050008A7050008A7050008E0 -:10005000A7050008A70500082D820008598200089E -:1000600085820008B1820008DD820008A70500082B -:10007000A7050008A7050008A7050008A7050008B0 -:10008000A7050008A7050008A7050008A7050008A0 -:10009000A7050008A7050008A705000809830008B0 -:1000A000A7050008A7050008A7050008A705000880 -:1000B000A7050008A7050008A7050008A705000870 -:1000C000A7050008A7050008A7050008A705000860 -:1000D000A7050008A7050008E1830008F5830008CC -:1000E0006D830008A7050008A7050008A7050008FC -:1000F000A7050008A7050008A7050008A705000830 -:10010000A7050008714500081D840008A705000820 -:10011000A7050008A7050008A7050008A70500080F -:10012000A7050008A7050008A7050008A7050008FF -:10013000A7050008A7050008A7050008A7050008EF -:10014000A7050008A7050008A7050008A7050008DF -:10015000A7050008A7050008A7050008A7050008CF -:10016000A7050008A7050008A7050008A7050008BF -:10017000A7050008017F0008A7050008A7050008DB -:10018000A7050008A705000809840008A7050008BE -:10019000A7050008A7050008A7050008A70500088F -:1001A000A7050008A7050008A7050008A70500087F -:1001B000A7050008A7050008A7050008A70500086F -:1001C000A7050008A7050008A7050008A70500085F -:1001D000A7050008ED7E0008A7050008A705000890 -:1001E000A7050008A7050008A7050008A70500083F -:1001F000A7050008A7050008A7050008A70500082F -:10020000A7050008A7050008A7050008A70500081E -:10021000A7050008A7050008A7050008A70500080E -:10022000A7050008A7050008A7050008A7050008FE -:10023000A7050008A7050008A7050008A7050008EE -:10024000A7050008A7050008A7050008A7050008DE -:10025000A7050008A7050008A7050008A7050008CE -:10026000A7050008A7050008A7050008A7050008BE -:10027000A7050008A7050008A7050008A7050008AE -:10028000A7050008A7050008A7050008A70500089E -:10029000A7050008A7050008A7050008A70500088E -:1002A00053B94AB9002908BF00281CBF4FF0FF31DD -:1002B0004FF0FF3000F074B9ADF1080C6DE904CED9 -:1002C00000F006F8DDF804E0DDE9022304B0704731 -:1002D0002DE9F047089D04468E46002B4DD18A42F9 -:1002E000944669D9B2FA82F252B101FA02F3C2F12C -:1002F000200120FA01F10CFA02FC41EA030E9440BD -:100300004FEA1C48210CBEFBF8F61FFA8CF708FBDD -:1003100016E341EA034306FB07F199420AD91CEBB5 -:10032000030306F1FF3080F01F81994240F21C81E7 -:10033000023E63445B1AA4B2B3FBF8F008FB10332F -:1003400044EA034400FB07F7A7420AD91CEB040464 -:1003500000F1FF3380F00A81A74240F20781644434 -:10036000023840EA0640E41B00261DB1D4400023B9 -:10037000C5E900433146BDE8F0878B4209D9002D1D -:1003800000F0EF800026C5E9000130463146BDE8A7 -:10039000F087B3FA83F6002E4AD18B4202D3824211 -:1003A00000F2F980841A61EB030301209E46002DC0 -:1003B000E0D0C5E9004EDDE702B9FFDEB2FA82F215 -:1003C000002A40F09280A1EB0C014FEA1C471FFA73 -:1003D0008CFE0126200CB1FBF7F307FB131140EA5A -:1003E00001410EFB03F0884208D91CEB010103F127 -:1003F000FF3802D2884200F2CB804346091AA4B2E9 -:10040000B1FBF7F007FB101144EA01440EFB00FEBC -:10041000A64508D91CEB040400F1FF3102D2A64521 -:1004200000F2BB800846A4EB0E0440EA03409CE7C0 -:10043000C6F12007B34022FA07FC4CEA030C20FA6D -:1004400007F401FA06F31C43F9404FEA1C4900FA8D -:1004500006F3B1FBF9F8200C1FFA8CFE09FB18110A -:1004600040EA014108FB0EF0884202FA06F20BD97D -:100470001CEB010108F1FF3A80F08880884240F2CD -:100480008580A8F102086144091AA4B2B1FBF9F011 -:1004900009FB101144EA014100FB0EFE8E4508D90C -:1004A0001CEB010100F1FF346CD28E456AD9023891 -:1004B000614440EA0840A0FB0294A1EB0E01A14276 -:1004C000C846A64656D353D05DB1B3EB080261EBE4 -:1004D0000E0101FA07F722FA06F3F1401F43C5E9BE -:1004E000007100263146BDE8F087C2F12003D840F4 -:1004F0000CFA02FC21FA03F3914001434FEA1C4736 -:100500001FFA8CFEB3FBF7F007FB10360B0C43EA27 -:10051000064300FB0EF69E4204FA02F408D91CEBD7 -:10052000030300F1FF382FD29E422DD902386344D5 -:100530009B1B89B2B3FBF7F607FB163341EA034175 -:1005400006FB0EF38B4208D91CEB010106F1FF38C4 -:1005500016D28B4214D9023E6144C91A46EA0046BB -:1005600038E72E46284605E70646E3E61846F8E64D -:100570004B45A9D2B9EB020864EB0C0E0138A3E796 -:100580004646EAE7204694E74046D1E7D0467BE777 -:10059000023B614432E7304609E76444023842E7EF -:1005A000704700BF02E000F000F8FEE73B488047DC -:1005B00072B63B4880F308883A4880F309883A4885 -:1005C0004EF60851CEF20001086040F20000CCF275 -:1005D00000004EF63471CEF200010860BFF34F8F79 -:1005E000BFF36F8F40F20000C0F2F0004EF688516A -:1005F000CEF200010860BFF34F8FBFF36F8F4FF053 -:100600000000E1EE100A4EF63C71CEF200010860E7 -:10061000062080F31488BFF36F8F06F079FF06F091 -:100620001BFF06F0A9F84FF0553020491C4A9142B3 -:100630003CBF41F8040BFAE71D491A4A91423CBFFE -:1006400041F8040BFAE71B491B4A1C4B9A423EBF78 -:1006500051F8040B42F8040BF8E700201849194A36 -:1006600091423CBF41F8040BFAE706F033FF06F075 -:1006700007F9154C154DAC4203DA54F8041B8847B2 -:10068000F9E700F043F8124C124DAC4203DA54F88B -:10069000041B8847F9E706F01BBF0000711F000824 -:1006A00000060020002200200000000800000020BA -:1006B00000060020C894000800220020D822002054 -:1006C000D822002064680020A0020008A0020008D0 -:1006D000A0020008A00200082DE9F04F2DED108ABD -:1006E000C1F80CD0D0F80CD0BDEC108ABDE8F08F6A -:1006F000002383F311882846A047002005F0A0FEC0 -:10070000FEE705F0EDFD00DFFEE7000038B506F07E -:1007100043FD054606F028FE0446E0B9104B9D4215 -:100720001BD001339D4241F2883504BF01240025CE -:10073000002006F03BFD0CB100F07AF801F02CFB34 -:1007400001F0E4F900F026FD08B100F071F8284648 -:1007500000F01CF9F9E70025EAE70546E8E700BFE5 -:10076000010007B008B501F09DF9A0F1200358423F -:10077000584108BD07B541F21203022101A8ADF8A6 -:10078000043001F0ADF903B05DF804FB38B5202367 -:1007900083F311881748C3680BB105F0EFFE0023FF -:1007A000154A4FF47A71134805F0ACFE002383F329 -:1007B0001188124C236813B12368013B23606368DE -:1007C00013B16368013B63600D4D2B7833B96368E7 -:1007D0007BB9022001F05AFA322363602B78032B95 -:1007E00007D163682BB9022001F050FA4FF47A73F5 -:1007F000636038BDD82200208D070008F423002054 -:10080000EC220020084B187003280CD8DFE800F019 -:1008100008050208022001F02FBA022001F022BAD6 -:10082000024B00225A607047EC220020F423002083 -:10083000F8B5504B504A1C461968013100F09980B8 -:1008400004339342F8D162684C4B9A4240F2918053 -:100850004B4B9B6803F1006303F500339A4280F031 -:100860008880002001F06CF90220FFF7CBFF454B98 -:100870000021D3F8E820C3F8E810D3F81021C3F81A -:100880001011D3F81021D3F8EC20C3F8EC10D3F8F2 -:100890001421C3F81411D3F81421D3F8F020C3F8AD -:1008A000F010D3F81821C3F81811D3F81821D3F891 -:1008B000802042F00062C3F88020D3F8802022F02C -:1008C0000062C3F88020D3F88020D3F8802042F063 -:1008D0000072C3F88020D3F8802022F00072C3F8A1 -:1008E0008020D3F8803072B64FF0E023C3F8084D73 -:1008F000D4E90004BFF34F8FBFF36F8F224AC2F8D1 -:100900008410BFF34F8F536923F480335361BFF3D7 -:100910004F8FD2F8803043F6E076C3F3C905C3F3B6 -:100920004E335B0103EA060C29464CEA8177013914 -:10093000C2F87472F9D2203B13F1200FF2D1BFF349 -:100940004F8FBFF36F8FBFF34F8FBFF36F8F53691D -:1009500023F4003353610023C2F85032BFF34F8FAA -:10096000BFF36F8F202383F31188854680F30888B7 -:100970002047F8BD0000020820000208FFFF010820 -:10098000002200200044025800ED00E02DE9F04F65 -:1009900093B0B44B2022FF2100900AA89D6801F07B -:1009A000A5F9B14A1378A3B90121B0481170C36009 -:1009B000202383F31188C3680BB105F0DFFD00230A -:1009C000AB4A4FF47A71A94805F09CFD002383F3EC -:1009D0001188009B13B1A74B009A1A60A64A13789E -:1009E000032B03D000231370A24A53604FF0000A78 -:1009F000009CD3465646D146012001F03DF924B172 -:100A00009C4B1B68002B00F02682002001F04AF866 -:100A10000390039B002BF2DB012001F023F9039BE1 -:100A2000213B1F2BE8D801A252F823F0AD0A0008A1 -:100A3000D50A0008690B0008F9090008F90900083F -:100A4000F9090008FB0B0008CB0D0008E50C0008B5 -:100A5000470D00086F0D0008950D0008F909000802 -:100A6000A70D0008F9090008190E00084D0B000831 -:100A7000F90900085D0E0008B90A00084D0B0008CE -:100A8000F9090008470D0008F9090008F9090008EC -:100A9000F9090008F9090008F9090008F90900082E -:100AA000F9090008F9090008690B00080220FFF79E -:100AB00059FE002840F0F981009B022105A8BAF1F7 -:100AC000000F08BF1C4641F21233ADF8143001F09C -:100AD00007F891E74FF47A7000F0E4FF071EEBDBB4 -:100AE0000220FFF73FFE0028E6D0013F052F00F26D -:100AF000DE81DFE807F0030A0D1013360523042119 -:100B000005A8059300F0ECFF17E004215548F9E72C -:100B100004215A48F6E704215948F3E74FF01C082E -:100B2000404608F1040801F00DF80421059005A8DD -:100B300000F0D6FFB8F12C0FF2D101204FF00009E0 -:100B400000FA07F747EA0B0B5FFA8BFB01F01AF983 -:100B500026B10BF00B030B2B08BF0024FFF70AFE96 -:100B60004AE704214748CDE7002EA5D00BF00B0340 -:100B70000B2BA1D10220FFF7F5FD074600289BD0E3 -:100B80000120002600F0DCFF0220FFF73BFE5FFAA9 -:100B900086F8404600F0E4FF0446B0B103994046B1 -:100BA0000136A1F140025142514100F0E9FF002815 -:100BB000EDD1BA46044641F21213022105A83E4681 -:100BC000ADF8143000F08CFF16E725460120FFF742 -:100BD00019FE244B9B68AB4207D9284600F0B2FFB0 -:100BE000013040F067810435F3E70025224BBA4617 -:100BF0003E461D701F4B5D60A8E7002E3FF45CAFC2 -:100C00000BF00B030B2B7FF457AF0220FFF7FAFD1D -:100C1000322000F047FFB0F10008FFF64DAF18F0AA -:100C200003077FF449AF0F4A08EB0503926893422C -:100C30003FF642AFB8F5807F3FF73EAF124BB84565 -:100C4000019323DD4FF47A7000F02CFF0390039A98 -:100C5000002AFFF631AF039A0137019B03F8012BFD -:100C6000EDE700BF00220020F0230020D822002062 -:100C70008D070008F4230020EC220020042200202D -:100C8000082200200C220020F0220020C820FFF7BC -:100C900069FD074600283FF40FAF1F2D11D8C5F19D -:100CA00020020AAB25F0030084494245184428BFBE -:100CB0004246019200F0F4FF019AFF217F4801F0C3 -:100CC00015F84FEAA803C8F387027C492846019328 -:100CD00001F014F8064600283FF46DAF019B05EBC8 -:100CE000830533E70220FFF73DFD00283FF4E4AE23 -:100CF00000F064FF00283FF4DFAE0027B846704BD9 -:100D00009B68BB4218D91F2F11D80A9B01330ED004 -:100D100027F0030312AA134453F8203C05934046DE -:100D2000042205A9043701F041F98046E7E7384677 -:100D300000F008FF0590F2E7CDF81480042105A823 -:100D400000F0CEFE02E70023642104A8049300F023 -:100D5000BDFE00287FF4B0AE0220FFF703FD00289F -:100D60003FF4AAAE049800F01FFF0590E6E70023C9 -:100D7000642104A8049300F0A9FE00287FF49CAE2F -:100D80000220FFF7EFFC00283FF496AE049800F035 -:100D90000DFFEAE70220FFF7E5FC00283FF48CAEE8 -:100DA00000F01CFFE1E70220FFF7DCFC00283FF425 -:100DB00083AE05A9142000F017FF07460421049014 -:100DC00004A800F08DFE3946B9E7322000F06AFE33 -:100DD000071EFFF671AEBB077FF46EAE384A07EB15 -:100DE0000903926893423FF667AE0220FFF7BAFC10 -:100DF00000283FF461AE27F003074F44B9453FF4A4 -:100E0000A5AE484609F1040900F09CFE04210590B6 -:100E100005A800F065FEF1E74FF47A70FFF7A2FC39 -:100E200000283FF449AE00F0C9FE002844D00A9BD8 -:100E300001330BD008220AA9002000F05FFF002830 -:100E40003AD02022FF210AA800F050FFFFF792FCC1 -:100E50001C4805F0FBFA13B0BDE8F08F002E3FF4FC -:100E60002BAE0BF00B030B2B7FF426AE002364217B -:100E700005A8059300F02AFE074600287FF41CAE63 -:100E80000220FFF76FFC804600283FF415AEFFF705 -:100E900071FC41F2883005F0D9FA059800F0BAFFEC -:100EA00046463C4600F06EFFA6E506464EE64FF08D -:100EB000000901E6BA467EE637467CE6F0220020CD -:100EC00000220020A086010070470000704700004B -:100ED000704700002DE9F04100F5803704461646C2 -:100EE0003B7C5BB9C0681030204400F0D9FEE56857 -:100EF0003544B5F5004FE56002D816B1BDE8F08184 -:100F0000DEB905F07F0605F110000021C6F180066C -:100F10002044F6B232462E4400F0E8FEA06804F108 -:100F20001008324600F10060414600F5003005F03F -:100F3000EBFE30B901233B74E0E74FF40046354641 -:100F4000ECE7A26805F11001404632442144A2605A -:100F5000E268521BE26000F0A3FE0220BDE8F0410F -:100F600000F094BE183000F0E9BC000010B5044653 -:100F700007F064FD204610BD10B5044607F05EFD85 -:100F8000204610BDC3B280B2A3F14102052A02D8A7 -:100F9000373800B27047613B052B94BF5738303863 -:100FA000F7E70000F8B504461546084603220C4949 -:100FB00000F080FE014688B908346F1C15F9110055 -:100FC000FFF7E0FF064617F911000131FFF7DAFFDE -:100FD000102940EA061004F8010BEFD1F8BD00BF5C -:100FE000988B00082DE9F04FADF53F7D074641682D -:100FF00001222AA802F05EFE002840F08780064603 -:10100000824681461125DFF80C81DFF80CB101AB77 -:101010004FF4805241462AA802F0A8FF002875D15B -:10102000019AB2F5805F71D8002A65D00446019A12 -:101030009442ECD2282D0FD008DC132D2DD01E2D7C -:1010400039D0112D13D00134A4B2F0E7322D2DD0B8 -:10105000372D2FD02D2DF6D13B68121B08EB040144 -:1010600038461B692D259847BDF80440EBE7121B55 -:10107000022A09D9594608EB040000F01BFE18B9F2 -:1010800002342825A4B2DEE718F804303A2B3DD00C -:101090000A2B1CBFA1461325D5E718F804300A2BEC -:1010A00034D03A2B04BFA2463225CCE718F80430DE -:1010B000202BC8D0264618F804300A2B1AD1AAEBE8 -:1010C000090208EB090102A811254F2A28BF4F2267 -:1010D00007F04EFDA21B08EB060116A84F2A28BFF9 -:1010E0004F2207F045FD3B6816AA02A9DB68384687 -:1010F0009847A8E71E25A6E73B68384604491B69C0 -:10110000984701200DF53F7DBDE8F08F0020F9E7FD -:101110008A8C0008FC2300209C8B000800F1180139 -:1011200010B5044686B00846019100F0F1FB204658 -:10113000FFF758FF60B1019902A800F049FC1022A6 -:1011400004F1080102A807F09DFCB0FA80F0400904 -:1011500006B010BD70B504460025EEB2304600F072 -:10116000FFFC58B100213046013500F009FD08B9F7 -:10117000002070BD022000F089FDEEE72046FFF759 -:1011800031FF0028F4D004F58034207C80F0010089 -:10119000EFE70000F0B5C9B006F016F800F074FEF5 -:1011A00018B90025284649B0F0BD69462A4802F022 -:1011B0009FFF00284BD1294C204602F0C9FF284848 -:1011C00002F0C6FF274802F0C3FF2146224803F081 -:1011D0003BF80028E5D1702007F032FC064610B13C -:1011E000214B44600360336830469B68984705464E -:1011F00000282ED01A4F1948394603F025F8054625 -:101200000028CED1194807F01BFC044638B1184B12 -:101210004760036000F58033C0E902551D74236800 -:1012200020469B689847054628B10E490C4803F0B4 -:101230000BF80028B5D1336830465B6898471CB17D -:10124000236820465B68984700F006FEAAE7002561 -:10125000FAE70446EFE700BFA08B0008B08B000858 -:10126000C78B0008DD8B0008008C0008140001000B -:101270001C8C00082DE9F04FD44A8DB00B68D0F8D3 -:1012800004A001931A440368D14E1A44D1F81C906B -:10129000DFF8B4C3DFF8B4B3D0E90234634003EA43 -:1012A0000A03634013444A6802920AEB7363029C88 -:1012B000C84A2244C468224484688AEA04051D405E -:1012C000654015448A68039203EB3555039CC24A76 -:1012D0002244846822448AEA03042C4084EA0A04F3 -:1012E0001444CA6805EBF4340492164483EA0502F8 -:1012F000224056445A4032440E69059604EBB2220D -:10130000059FB64E3E441E4485EA040313406B40DD -:1013100033444E69069602EB7363069FB04E3E441B -:101320002E4484EA02051D40654035448E690796C7 -:1013300003EB3555079FAB4E3E44264482EA030437 -:101340002C4054403444A84E4E4405EBF43416442B -:1013500083EA050222405A4032440E6A089604EBA2 -:10136000B222089FA14E3E441E4485EA0403134066 -:101370006B4033444E6A099602EB7363099F9C4E9F -:10138000D1F830E03E44D1F83880F3442E4484EA6A -:1013900002051D40654035448E6AA6F5244703EBDF -:1013A00035550A964F3F274482EA03042C405440A7 -:1013B0003C44CF6A0B9705EBF4340B9E8D4F3744BA -:1013C000029E174483EA050222405A403A448A4F5B -:1013D000774404EBB2221F4485EA040313406B40B8 -:1013E0003B444F6BBC4402EB7363654484EA020CDC -:1013F0000CEA030C8CEA040C6544DFF854C2C444C4 -:1014000003EB3555A44482EA03042C405440644461 -:10141000D1F83CC0794905EBF4346144114483EAC6 -:10142000050222405A400A44754904EBB222314475 -:10143000079E194484EA02032B4063400B44714920 -:1014400002EBF36331440B9E0D4482EA0301214019 -:10145000514029446C4D03EBF1513544019E254424 -:1014600083EA010414405C402C44684D01EBB44411 -:101470003544069E154481EA04021A404A402A4433 -:10148000634D04EB323235440A9E1D4484EA020364 -:101490000B4063402B445F4D02EBF3633544059EE4 -:1014A0000D4482EA03012140514029445A4D03EB87 -:1014B000F1516544254483EA010414405C402C4406 -:1014C000564D01EBB4443544099E154481EA0402AB -:1014D0001A404A402A44524D04EB32323544049EAD -:1014E0001D4484EA02030B4063402B444D4D02EB44 -:1014F000F36345440D4482EA0301214051402944ED -:10150000494D03EBF1513544089E2C4483EA010513 -:1015100015405D402C44454D01EBB4443544039ED9 -:101520002A4481EA04051D404D402A44404D04EB05 -:1015300032323D442B4484EA020593440D40654019 -:101540002B443C4D02EBF3633544069E294482EA6A -:101550000305254055402944374D03EBF1514D44D7 -:101560002C4483EA010515405D40254401EBB54557 -:1015700081EA050404EA03024A405A44A6F5B82B5E -:10158000089E05EB3232ABF2BE6B54405B44234401 -:101590002A4C344402EB33730B9E0C4485EA02015F -:1015A00059402144264C344403EB7151029E25449A -:1015B00082EA03044C402544224C444401EB354567 -:1015C000144483EA01026A40224443E078A46AD7C3 -:1015D000EECEBDC156B7C7E8DB702024AF0F7CF557 -:1015E0002AC68747134630A8019546FDD8988069DA -:1015F000AFF7448BBED75C892211906B2108B449A8 -:1016000062251EF640B340C0515A5E26AAC7B6E90D -:101610005D102FD65314440281E6A1D8C8FBD3E74E -:10162000E6CDE121D60737C3870DD5F4ED145A4531 -:1016300005E9E3A9F8A3EFFCD9026F6781F671878A -:1016400022619D6D0C38E5FD937198FD8A4C2A8DC1 -:101650008E4379A6934C344405EB7222059E1C44BC -:1016600081EA0503534023448F4C344402EB337327 -:101670000A9E0C4485EA0201594021448B4C4C449B -:1016800003EB7151254482EA03044C402C44884DFD -:10169000354401EB3444019E154483EA0102624063 -:1016A0002A44844D3D4404EB72221D4481EA040324 -:1016B00053402B44804D354402EB3373049E294440 -:1016C00084EA02055D4029447C4D354403EB7151A9 -:1016D000079E254482EA03044C402C44784D35444F -:1016E00001EB3444099E2A4483EA01056540154410 -:1016F000744A324404EB7525039E134481EA0402C4 -:101700006A401A44704B734405EB32720B4484EA0E -:101710000501514019446D4B634402EB71511C4467 -:1017200085EA02034B401C44694B334401EB3444CB -:10173000019E1D4482EA010363402B44654D04EB86 -:1017400073233544069E154463EA010262402A442D -:10175000614D03EBB2624D4462EA040929445F4DD6 -:1017600089EA0309454449442C445D4D02EBB151DB -:101770003544049E61EA03081D4488EA0208444493 -:1017800001EB744464EA02034B402B44554D04EBD7 -:10179000F323754463EA010E15448EEA040E0EEB42 -:1017A0000502514D03EBB262354462EA040E29444E -:1017B0000A9D8EEA030EA5F580164C4D7144A6F6DF -:1017C000833602EBB151264461EA030454403444A9 -:1017D000029E01EB7444354464EA02061D444E4007 -:1017E0007319089E424D04EBF323354463EA010666 -:1017F0001544664072193F4D03EBB262654462EADC -:10180000040629443C4D5E403144079E02EBB15131 -:10181000354461EA03062C44384D56403D44344477 -:10182000059E1D4401EB744464EA02034B402B44C3 -:10183000334D04EBF32335440B9E154463EA010258 -:1018400062402A442F4D03EBB2623544039E0D449F -:1018500062EA0401594029442B4D02EBB151354451 -:101860002A4E254461EA030454402C44099D01EBAF -:1018700074442E4464EA02051E4485EA01039D195E -:1018800003681A440AEB040303EBF5230260436088 -:1018900083681C44C36819448460C1600DB0BDE80E -:1018A000F08F00BF44EABEA4A9CFDE4B604BBBF66D -:1018B00070BCBFBEC67E9B28FA27A1EA8530EFD454 -:1018C000051D880439D0D4D9E599DBE6F87CA21F40 -:1018D0006556ACC4442229F497FF2A43A72394AB4E -:1018E00039A093FCC3595B6592CC0C8FD15D848584 -:1018F0004F7EA86FE0E62CFE144301A3A111084E11 -:10190000827E53F735F23ABDBBD2D72A91D386EB0C -:10191000094B036003F18833436003F12943A3F5C6 -:101920009613A3F68B638360A3F18833C36000230F -:10193000C0E90433704700BF012345672DE9F84330 -:101940001446026905460E46E300C2F3C50800F1DD -:1019500018079B18036122BF43690133436112F4E6 -:10196000FC7F436903EB5473436114D0C8F1400911 -:1019700007EB08004C4504D22246BDE8F84307F0C7 -:1019800091B8403C4A464E4407F08CF844443946EE -:101990002846FFF76FFCA04606EB0409B8F13F0F9D -:1019A000A9EB08010AD94022384607F07BF83946EE -:1019B0002846A8F14008FFF75DFCEFE7A1096FF0AA -:1019C0003F02384602FB014206EB8111D5E70000D9 -:1019D00070B50B6901F1180506460C46C3F3C50343 -:1019E000EA18501C8022EA54C3F13F02072A1FD88C -:1019F000002100F07BF929462046FFF73BFC382206 -:101A00000021284600F072F9236929462046236503 -:101A100063696365FFF72EFC21461022304607F00C -:101A200041F8204658220021BDE8704000F05EB920 -:101A3000C3F137020021E5E72DE9F84F4FF47A733F -:101A400006460D46002402FB03F7DFF85080DFF85E -:101A5000509098F900305FFA84FA5A1C01D0A342E2 -:101A600010D159F824002A4631460368D3F820B033 -:101A70003B46D847854205D1074B012083F800A09B -:101A8000BDE8F88F0134042CE3D14FF4FA7004F070 -:101A9000DDFC0020F4E700BF4034002010220020CD -:101AA00014220020002307B5024601210DF1070092 -:101AB0008DF80730FFF7C0FF20B19DF8070003B095 -:101AC0005DF804FB4FF0FF30F9E700000A460421FF -:101AD00008B5FFF7B1FF80F00100C0B2404208BD79 -:101AE000074B0A4630B41978064B53F8214001469B -:101AF00023682046DD69044BAC4630BC604700BF1C -:101B00004034002014220020A086010070B50A4E47 -:101B100000240A4D05F096F8308028683388834207 -:101B200008D905F08BF82B6804440133B4F5003F65 -:101B30002B60F2D370BD00BF42340020FC33002084 -:101B400005F05EB900F1006000F5003000687047F4 -:101B500000F10060920000F5003005F0D5B80000FB -:101B6000054B1A68054B1B889B1A834202D9104407 -:101B700005F064B800207047FC3300204234002098 -:101B800038B50446074D29B128682044BDE83840DF -:101B900005F06CB82868204405F056F80028F3D00A -:101BA00038BD00BFFC3300200020704700F1FF501B -:101BB00000F58F10D0F8000870470000064991F832 -:101BC000243033B100230822086A81F82430FFF75B -:101BD000BFBF0120704700BF00340020014B1868D0 -:101BE000704700BF0010005C1B4B0246F0B5186840 -:101BF0001A4BC0F30B06000C1F885C68BE4293F9B9 -:101C0000085003D09F89BE4203D10C335C6893F91E -:101C100008500426124B1F880433874208BF13F96B -:101C2000025C013EF7D1013A013C0B460A44934263 -:101C300007D214F9016F581C2EB1034600F8016C4D -:101C4000F5E7184605E02C2482421C7001D9981C47 -:101C50005D70401AF0BD00BF0010005C242200201F -:101C60004C8C0008022803D1024B4FF080529A613D -:101C7000704700BF00100258022803D1024B4FF4F6 -:101C800080529A61704700BF00100258022804D1A8 -:101C9000024A536983F4805353617047001002581D -:101CA000002310B5934203D0CC5CC4540133F9E750 -:101CB00010BD0000013810B510F9013F3BB191F99A -:101CC00000409C4203D11AB10131013AF4E71AB144 -:101CD00091F90020981A10BD1046FCE70346024611 -:101CE000D01A12F9011B0029FAD1704702440346A9 -:101CF000934202D003F8011BFAE770472DE9F8433D -:101D00001F4D14460746884695F8242052BBDFF83D -:101D100070909CB395F824302BB92022FF214846BF -:101D20002F62FFF7E3FF95F824004146C0F1080257 -:101D300005EB8000A24228BF2246D6B29200FFF7F0 -:101D4000AFFF95F82430A41B17441E449044E4B21E -:101D5000F6B2082E85F82460DBD1FFF72FFF0028AC -:101D6000D7D108E02B6A03EB82038342CFD0FFF781 -:101D700025FF0028CBD10020BDE8F8830120FBE738 -:101D800000340020024B1A78024B1A70704700BFD3 -:101D90004034002010220020F8B5184C184803F0F9 -:101DA000B9FC2146164803F0E1FC24681548D4F834 -:101DB0009020154ED2F80438144D43F00203104F12 -:101DC000C2F8043804F042FB2046114903F0DCFD60 -:101DD000D4F890200424D2F8043823F00203C2F887 -:101DE00004384FF4E133336055F8040BB84202D0A5 -:101DF000314603F0EDFB013CF6D1F8BD54930008E9 -:101E0000504A002040420F002834002014220020B5 -:101E10005C9300080C4B70B50C4D04461E780C4BBF -:101E200055F826209A420DD00A4B00211822184658 -:101E3000FFF75CFF0460014655F82600BDE87040DE -:101E400003F0C6BB70BD00BF403400201422002048 -:101E5000504A00202834002010B5084C01220849BF -:101E6000002001F003FF23783BB1064803F02CFB70 -:101E7000044803F05FFB0023237010BD44340020AE -:101E80005C8C0008A03600201E482DE9F041D0F8F7 -:101E9000503233B901224FF4805100F5147005F02F -:101EA000D5F9194E33780BB1FFF7D6FF0324174F3E -:101EB0004FF00008134D2846144987F8058003F0B9 -:101EC0002BFB284603F054F948B1013C284603F0A7 -:101ED00031FB14F0FF04EED1204634700FE00C49C2 -:101EE00001220C4801F0C2FE014618B1284603F059 -:101EF000EBFAEAE7084800F011F801203070BDE87D -:101F0000F08100BFA0360020443400203C22002095 -:101F10005C8C000848340020608C00080FB400205E -:101F200004B0704700B59BB0EFF3098168226846A2 -:101F3000FFF7B6FEEFF30583014B9B6BFEE700BF97 -:101F400000ED00E008B5FFF7EDFF000000B59BB025 -:101F5000EFF3098168226846FFF7A2FEEFF30583DD -:101F6000014B5B6BFEE700BF00ED00E0FEE7000009 -:101F700000B595B0132101A805F006FA9DF84F3081 -:101F80007BB10023132101A88DF84F3005F0F6F93D -:101F9000054BD3F8002882F30888D3F80438984713 -:101FA000FEE715B05DF804FB0090F01F30B50A4461 -:101FB000084D91420DD011F8013B5840082340F3E1 -:101FC0000004013B2C4013F0FF0384EA5000F6D1DB -:101FD000EFE730BD2083B8ED006870470346006826 -:101FE000596870470B0A017043700B0C090E83701F -:101FF000C1707047110A027003714170110C120E0A -:102000008170C2701A0A42711A0C1B0E8271C37160 -:1020100070470000024400F8011B9042FBD170475A -:10202000024410B510F8013B11F8014B9042A3EBAC -:10203000040301D0002BF5D0184610BDC36A023945 -:10204000023B8B4283BF4389006C01FB03000020ED -:1020500070470000C2F307238A76CB760378032B00 -:1020600001BF120C0A75120A4A75704700F10B0184 -:102070000022D30143EA520310F8012B52FA83F3F2 -:102080008842DAB2F5D110467047000010B54178A9 -:1020900004460020013102464901022A16BFA35C12 -:1020A000032203EBC03302F101021EBF9BB203EB1C -:1020B000500398B29142F0D810BD000002684AB1B6 -:1020C000134613F8011B1F290DD93A29F9D1911C88 -:1020D0008B4202D04FF0FF3070471278302AF9D18E -:1020E000036000207047014B187870479436002039 -:1020F00038B50D46044618B9092000232B6038BDB9 -:102100000368002BF8D01A78002AF5D08188DA8885 -:102110009142F1D1587804F0B3FA10F00100EBD1FC -:102120002368EBE738B50D4640F25231144602F011 -:1021300073F9FF2806D9012C0AD9030A6870022016 -:102140002B7038BD0028FCD024B128700120F8E79E -:102150000020F6E72046F4E72DE9F8430026D0F802 -:10216000008007460C468E76836B3BB398F80030B0 -:10217000042B4BD1D8F8108040273546334698F8C9 -:10218000232096421CD3002B40F0BF80002D00F08E -:10219000BC8000232544AB76637398F80430237326 -:1021A000DB0630D408F13800FFF718FFC4E900015E -:1021B000B8F80C306381B8F80E302381BDE8F8839D -:1021C000B7F5187F80F0A180FA0606F1010608BF76 -:1021D000023738F8070002372BB900F5205292B2C7 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E3020008A9760008E2 +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E302000891850008BD8500085E +:10006000E98500081586000841860008DD4500087E +:1000700005460008314600085D460008894600082C +:10008000B1460008DD460008E3020008E30200086C +:10009000E3020008E3020008E30200086D8600089E +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008598700086D87000862 +:1000E000D1860008E3020008E3020008E3020008EA +:1000F000E3020008E3020008E302000809470008E1 +:10010000E30200084587000895870008E30200081D +:10011000E3020008E3020008E3020008E30200082B +:10012000354700085D47000889470008B5470008C3 +:10013000E1470008E3020008E3020008E3020008C8 +:10014000E3020008E3020008E3020008E3020008FB +:10015000094800083548000861480008E302000823 +:10016000E3020008E3020008E3020008E3020008DB +:10017000E302000881820008E3020008E3020008AD +:10018000E3020008E302000881870008E302000898 +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E30200086D820008E3020008E302000861 +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F07F00EFA61 +:1003500006F06EFB4FF055301F491B4A91423CBFDF +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE707F026FA06F0E6FB4B +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F0C4F9114C124DAC4203DA54F8041B9E +:1003C0008847F9E707F00EBA000600200022002057 +:1003D0000000000808ED00E00000002000060020FA +:1003E000309C000800220020742200207822002087 +:1003F00034670020E0020008E0020008E002000884 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002006F0E4F8FEE706F011 +:100430003DF800DFFEE7000053B94AB9002908BFC4 +:1004400000281CBF4FF0FF314FF0FF3000F074B9AF +:10045000ADF1080C6DE904CE00F006F8DDF804E01B +:10046000DDE9022304B070472DE9F047089D0446FA +:100470008E46002B4DD18A42944669D9B2FA82F257 +:1004800052B101FA02F3C2F1200120FA01F10CFA93 +:1004900002FC41EA030E94404FEA1C48210CBEFBCB +:1004A000F8F61FFA8CF708FB16E341EA034306FB54 +:1004B00007F199420AD91CEB030306F1FF3080F0E3 +:1004C0001F81994240F21C81023E63445B1AA4B230 +:1004D000B3FBF8F008FB103344EA034400FB07F7D2 +:1004E000A7420AD91CEB040400F1FF3380F00A8113 +:1004F000A74240F207816444023840EA0640E41B08 +:1005000000261DB1D4400023C5E900433146BDE8B3 +:10051000F0878B4209D9002D00F0EF800026C5E955 +:10052000000130463146BDE8F087B3FA83F6002E6D +:100530004AD18B4202D3824200F2F980841A61EBE5 +:10054000030301209E46002DE0D0C5E9004EDDE703 +:1005500002B9FFDEB2FA82F2002A40F09280A1EBEB +:100560000C014FEA1C471FFA8CFE0126200CB1FB40 +:10057000F7F307FB131140EA01410EFB03F0884239 +:1005800008D91CEB010103F1FF3802D2884200F2C6 +:10059000CB804346091AA4B2B1FBF7F007FB101158 +:1005A00044EA01440EFB00FEA64508D91CEB0404F6 +:1005B00000F1FF3102D2A64500F2BB800846A4EB51 +:1005C0000E0440EA03409CE7C6F12007B34022FA3C +:1005D00007FC4CEA030C20FA07F401FA06F31C436B +:1005E000F9404FEA1C4900FA06F3B1FBF9F8200C78 +:1005F0001FFA8CFE09FB181140EA014108FB0EF0BE +:10060000884202FA06F20BD91CEB010108F1FF3A0D +:1006100080F08880884240F28580A8F10208614419 +:10062000091AA4B2B1FBF9F009FB101144EA014127 +:1006300000FB0EFE8E4508D91CEB010100F1FF34D2 +:100640006CD28E456AD90238614440EA0840A0FB6A +:100650000294A1EB0E01A142C846A64656D353D040 +:100660005DB1B3EB080261EB0E0101FA07F722FA64 +:1006700006F3F1401F43C5E9007100263146BDE88D +:10068000F087C2F12003D8400CFA02FC21FA03F3F0 +:10069000914001434FEA1C471FFA8CFEB3FBF7F071 +:1006A00007FB10360B0C43EA064300FB0EF69E4296 +:1006B00004FA02F408D91CEB030300F1FF382FD22F +:1006C0009E422DD9023863449B1B89B2B3FBF7F6D7 +:1006D00007FB163341EA034106FB0EF38B4208D9B0 +:1006E0001CEB010106F1FF3816D28B4214D9023EF1 +:1006F0006144C91A46EA004638E72E46284605E70F +:100700000646E3E61846F8E64B45A9D2B9EB0208DF +:1007100064EB0C0E0138A3E74646EAE7204694E76F +:100720004046D1E7D0467BE7023B614432E73046A2 +:1007300009E76444023842E7704700BF38B501F06A +:10074000F3F901F0A3FB06F09DFE054606F0A2FFBB +:100750000446D0B90F4B9D4219D001339D4241F25E +:10076000883504BF01240025002006F095FE0CB159 +:1007700000F078F801F02AFB00F01AFD08B100F053 +:1007800071F8284600F010F9F9E70025ECE7054676 +:10079000EAE700BF010007B008B501F091F9A0F148 +:1007A00020035842584108BD07B541F21203022107 +:1007B00001A8ADF8043001F0A1F903B05DF804FB25 +:1007C00038B5302383F31188174803680BB105F05F +:1007D000F5FF0023154A4FF47A71134805F0E4FF42 +:1007E000002383F31188124C236813B12368013B63 +:1007F0002360636813B16368013B63600D4D2B7820 +:1008000033B963687BB9022001F04AFA322363608E +:100810002B78032B07D163682BB9022001F040FA33 +:100820004FF47A73636038BD78220020C107000856 +:100830009823002090220020084B187003280CD821 +:10084000DFE800F008050208022001F01FBA0220CC +:1008500001F012BA024B00225A6070479022002029 +:1008600098230020F8B5494B494A1C4619680131C4 +:1008700000F08A8004339342F8D16268454B9A4273 +:1008800040F28280444B9B6803F1006303F5003320 +:100890009A4279D2002001F061F90220FFF7CCFFE3 +:1008A0003E4B00219A6C99641A6F19671A6FDA6CC3 +:1008B000D9645A6F59675A6F1A6D19659A6F99679B +:1008C0009B6F374BD3F8802042F00062C3F8802042 +:1008D000D3F8802022F00062C3F88020D3F8802073 +:1008E000D3F8802042F00072C3F88020D3F8802033 +:1008F00022F00072C3F88020D3F8803072B64FF037 +:10090000E023C3F8084DD4E90004BFF34F8FBFF3D1 +:100910006F8F244AC2F88410BFF34F8F536923F4BA +:1009200080335361BFF34F8FD2F8803043F6E076C7 +:10093000C3F3C905C3F34E335B0103EA060C294632 +:100940004CEA81770139C2F87472F9D2203B13F175 +:10095000200FF2D1BFF34F8FBFF36F8FBFF34F8FD5 +:10096000BFF36F8F536923F4003353610023C2F840 +:100970005032BFF34F8FBFF36F8F302383F3118853 +:10098000854680F308882047F8BD00BF00000208B4 +:1009900020000208FFFF0108002200200045025845 +:1009A0000044025800ED00E02DE9F04F93B0B44B45 +:1009B0002022FF2100900AA89D6801F0B1F9B14AF8 +:1009C0001378A3B90121B04811700360302383F379 +:1009D000118803680BB105F0F1FE0023AB4A4FF418 +:1009E0007A71A94805F0E0FE002383F31188009B8B +:1009F00013B1A74B009A1A60A64A1378032B03D0B1 +:100A000000231370A24A53604FF0000A009CD346A3 +:100A10005646D146012001F039F924B19C4B1B68A0 +:100A2000002B00F02682002001F04AF80390039B7F +:100A3000002BF2DB012001F01FF9039B213B1F2B50 +:100A4000E8D801A252F823F0C90A0008F10A000808 +:100A5000850B0008150A0008150A0008150A000889 +:100A6000170C0008E70D0008010D0008630D0008D1 +:100A70008B0D0008B10D0008150A0008C30D000811 +:100A8000150A0008350E0008690B0008150A000851 +:100A9000790E0008D50A0008690B0008150A00083D +:100AA000630D0008150A0008150A0008150A000859 +:100AB000150A0008150A0008150A0008150A00089A +:100AC000150A0008850B00080220FFF765FE0028C4 +:100AD00040F0F981009B022105A8BAF1000F08BF80 +:100AE0001C4641F21233ADF8143001F007F891E7DB +:100AF0004FF47A7000F0E4FF071EEBDB0220FFF7F3 +:100B00004BFE0028E6D0013F052F00F2DE81DFE832 +:100B100007F0030A0D1013360523042105A80593D9 +:100B200000F0ECFF17E004215548F9E704215A488A +:100B3000F6E704215948F3E74FF01C08404608F156 +:100B4000040801F00DF80421059005A800F0D6FF77 +:100B5000B8F12C0FF2D101204FF0000900FA07F78D +:100B600047EA0B0B5FFA8BFB01F026F926B10BF07D +:100B70000B030B2B08BF0024FFF716FE4AE70421E6 +:100B80004748CDE7002EA5D00BF00B030B2BA1D1CE +:100B90000220FFF701FE074600289BD00120002617 +:100BA00000F0DCFF0220FFF747FE1FFA86F8404600 +:100BB00000F0E4FF0446B0B1039940460136A1F1CC +:100BC00040025142514100F0E9FF0028EDD1BA4600 +:100BD000044641F21213022105A83E46ADF8143036 +:100BE00000F08CFF16E725460120FFF725FE244B79 +:100BF0009B68AB4207D9284600F0B2FF013040F0B5 +:100C000067810435F3E70025224BBA463E461D7046 +:100C10001F4B5D60A8E7002E3FF45CAF0BF00B03A9 +:100C20000B2B7FF457AF0220FFF706FE322000F0B7 +:100C300047FFB0F10008FFF64DAF18F003077FF44F +:100C400049AF0F4A08EB0503926893423FF642AF63 +:100C5000B8F5807F3FF73EAF124BB845019323DDD7 +:100C60004FF47A7000F02CFF0390039A002AFFF6ED +:100C700031AF039A0137019B03F8012BEDE700BF69 +:100C8000002200209423002078220020C1070008C1 +:100C90009823002090220020042200200822002017 +:100CA0000C22002094220020C820FFF775FD074683 +:100CB00000283FF40FAF1F2D11D8C5F120020AAB59 +:100CC00025F0030084494245184428BF424601925A +:100CD00001F000F8019AFF217F4801F021F84FEA66 +:100CE000A803C8F387027C492846019301F020F845 +:100CF000064600283FF46DAF019B05EB830533E703 +:100D00000220FFF749FD00283FF4E4AE00F064FF45 +:100D100000283FF4DFAE0027B846704B9B68BB420B +:100D200018D91F2F11D80A9B01330ED027F00303C7 +:100D300012AA134453F8203C05934046042205A907 +:100D4000043701F0F9F88046E7E7384600F008FF7D +:100D50000590F2E7CDF81480042105A800F0CEFE3E +:100D600002E70023642104A8049300F0BDFE0028DC +:100D70007FF4B0AE0220FFF70FFD00283FF4AAAECB +:100D8000049800F01FFF0590E6E70023642104A803 +:100D9000049300F0A9FE00287FF49CAE0220FFF728 +:100DA000FBFC00283FF496AE049800F00DFFEAE744 +:100DB0000220FFF7F1FC00283FF48CAE00F01CFF8E +:100DC000E1E70220FFF7E8FC00283FF483AE05A925 +:100DD000142000F017FF07460421049004A800F037 +:100DE0008DFE3946B9E7322000F06AFE071EFFF695 +:100DF00071AEBB077FF46EAE384A07EB0903926809 +:100E000093423FF667AE0220FFF7C6FC00283FF48E +:100E100061AE27F003074F44B9453FF4A5AE4846FD +:100E200009F1040900F09CFE0421059005A800F0DA +:100E300065FEF1E74FF47A70FFF7AEFC00283FF44F +:100E400049AE00F0C9FE002844D00A9B01330BD004 +:100E500008220AA9002000F06BFF00283AD02022C7 +:100E6000FF210AA800F05CFFFFF79EFC1C4805F07C +:100E7000C7FB13B0BDE8F08F002E3FF42BAE0BF094 +:100E80000B030B2B7FF426AE0023642105A80593EA +:100E900000F02AFE074600287FF41CAE0220FFF770 +:100EA0007BFC804600283FF415AEFFF77DFC41F245 +:100EB000883005F0A5FB059800F0C6FF46463C4685 +:100EC00000F07AFFA6E506464EE64FF0000901E67F +:100ED000BA467EE637467CE69422002000220020B7 +:100EE000A0860100704700007047000070470000B6 +:100EF0002DE9F04100F58037044616463B7C5BB98E +:100F0000C0681030204400F0E5FEE5683544B5F5D2 +:100F1000004FE56002D816B1BDE8F081DEB905F0FA +:100F20007F0605F110000021C6F180062044F6B2CC +:100F300032462E4400F0F4FEA06804F11008324658 +:100F400000F10060414600F5003006F047F830B986 +:100F500001233B74E0E74FF400463546ECE7A26816 +:100F600005F11001404632442144A260E268521B60 +:100F7000E26000F0AFFE0220BDE8F04100F090BE5C +:100F8000183000F0E9BC000010B5044600F0F0FF96 +:100F9000204610BD10B5044600F0EAFF204610BD03 +:100FA000C3B280B2A3F14102052A02D8373800B299 +:100FB0007047613B052B94BF57383038F7E7000086 +:100FC000F8B504461546084603220C4900F08CFE8D +:100FD000014688B908346F1C15F91100FFF7E0FFCE +:100FE000064617F911000131FFF7DAFF102940EA30 +:100FF000061004F8010BEFD1F8BD00BFDC9100082A +:101000002DE9F04FADF53F7D0746416801222AA842 +:1010100002F090FE002840F0878006468246814616 +:101020001125DFF80C81DFF80CB101AB4FF48052D1 +:1010300041462AA802F0DEFF002875D1019AB2F5D8 +:10104000805F71D8002A65D00446019A9442ECD2A0 +:10105000282D0FD008DC132D2DD01E2D39D0112DA9 +:1010600013D00134A4B2F0E7322D2DD0372D2FD07C +:101070002D2DF6D13B68121B08EB040138461B6985 +:101080002D259847BDF80440EBE7121B022A09D929 +:10109000594608EB040000F027FE18B90234282551 +:1010A000A4B2DEE718F804303A2B3DD00A2B1CBF5F +:1010B000A1461325D5E718F804300A2B34D03A2B73 +:1010C00004BFA2463225CCE718F80430202BC8D044 +:1010D000264618F804300A2B1AD1AAEB090208EBAD +:1010E000090102A811254F2A28BF4F2208F062F8F3 +:1010F000A21B08EB060116A84F2A28BF4F2208F0B2 +:1011000059F83B6816AA02A9DB6838469847A8E751 +:101110001E25A6E73B68384604491B69984701200D +:101120000DF53F7DBDE8F08F0020F9E7DE92000865 +:10113000A0230020E091000800F1180110B504463A +:1011400086B00846019100F0F1FB2046FFF758FFFA +:1011500060B1019902A800F049FC102204F10801D5 +:1011600002A807F0E7FFB0FA80F0400906B010BD12 +:1011700070B504460025EEB2304600F0FFFC58B1D1 +:1011800000213046013500F009FD08B9002070BD8E +:10119000022000F085FDEEE72046FFF731FF002832 +:1011A000F4D004F58034207C80F00100EFE70000EB +:1011B000F0B5C9B006F07EF900F0F6FE18B90025CA +:1011C000284649B0F0BD69462A4802F0D5FF0028FC +:1011D0004BD1294C204602F0FFFF284802F0FCFFCB +:1011E000274802F0F9FF2146224803F071F8002851 +:1011F000E5D1702000F0B6FE064610B1214B4460E8 +:101200000360336830469B689847054600282ED017 +:101210001A4F1948394603F05BF805460028CED12D +:10122000194800F09FFE044638B1184B4760036030 +:1012300000F58033C0E902551D74236820469B6881 +:101240009847054628B10E490C4803F041F800289C +:10125000B5D1336830465B6898471CB12368204697 +:101260005B68984700F088FEAAE70025FAE7044685 +:10127000EFE700BFE4910008F49100080B9200082A +:1012800021920008449200081400010060920008B6 +:101290002DE9F04FD44A8DB00B68D0F804A001932B +:1012A0001A440368D14E1A44D1F81C90DFF8B4C335 +:1012B000DFF8B4B3D0E90234634003EA0A036340C1 +:1012C00013444A6802920AEB7363029CC84A2244A0 +:1012D000C468224484688AEA04051D4065401544B8 +:1012E0008A68039203EB3555039CC24A2244846802 +:1012F00022448AEA03042C4084EA0A041444CA689B +:1013000005EBF4340492164483EA05022240564465 +:101310005A4032440E69059604EBB222059FB64E40 +:101320003E441E4485EA040313406B4033444E6937 +:10133000069602EB7363069FB04E3E442E4484EA49 +:1013400002051D40654035448E69079603EB35550F +:10135000079FAB4E3E44264482EA03042C4054408F +:101360003444A84E4E4405EBF434164483EA050297 +:1013700022405A4032440E6A089604EBB222089F7B +:10138000A14E3E441E4485EA040313406B4033449F +:101390004E6A099602EB7363099F9C4ED1F830E0C8 +:1013A0003E44D1F83880F3442E4484EA02051D40BF +:1013B000654035448E6AA6F5244703EB35550A96F9 +:1013C0004F3F274482EA03042C4054403C44CF6AF8 +:1013D0000B9705EBF4340B9E8D4F3744029E174458 +:1013E00083EA050222405A403A448A4F774404EB8C +:1013F000B2221F4485EA040313406B403B444F6B09 +:10140000BC4402EB7363654484EA020C0CEA030CEF +:101410008CEA040C6544DFF854C2C44403EB355530 +:10142000A44482EA03042C4054406444D1F83CC0F4 +:10143000794905EBF4346144114483EA0502224002 +:101440005A400A44754904EBB2223144079E1944BC +:1014500084EA02032B4063400B44714902EBF363BF +:1014600031440B9E0D4482EA03012140514029443E +:101470006C4D03EBF1513544019E254483EA010490 +:1014800014405C402C44684D01EBB4443544069E46 +:10149000154481EA04021A404A402A44634D04EB91 +:1014A000323235440A9E1D4484EA02030B406340F5 +:1014B0002B445F4D02EBF3633544059E0D4482EAF5 +:1014C00003012140514029445A4D03EBF151654439 +:1014D000254483EA010414405C402C44564D01EB42 +:1014E000B4443544099E154481EA04021A404A4036 +:1014F0002A44524D04EB32323544049E1D4484EAA2 +:1015000002030B4063402B444D4D02EBF363454413 +:101510000D4482EA0301214051402944494D03EB27 +:10152000F1513544089E2C4483EA010515405D4085 +:101530002C44454D01EBB4443544039E2A4481EAD2 +:1015400004051D404D402A44404D04EB32323D44D9 +:101550002B4484EA020593440D4065402B443C4DE6 +:1015600002EBF3633544069E294482EA03052540D5 +:1015700055402944374D03EBF1514D442C4483EA47 +:10158000010515405D40254401EBB54581EA0504A0 +:1015900004EA03024A405A44A6F5B82B089E05EB1C +:1015A0003232ABF2BE6B54405B4423442A4C344489 +:1015B00002EB33730B9E0C4485EA0201594021442F +:1015C000264C344403EB7151029E254482EA030405 +:1015D0004C402544224C444401EB3545144483EAF5 +:1015E00001026A40224443E078A46AD7EECEBDC12E +:1015F00056B7C7E8DB702024AF0F7CF52AC68747B3 +:10160000134630A8019546FDD8988069AFF7448B02 +:10161000BED75C892211906B2108B44962251EF661 +:1016200040B340C0515A5E26AAC7B6E95D102FD616 +:101630005314440281E6A1D8C8FBD3E7E6CDE121EB +:10164000D60737C3870DD5F4ED145A4505E9E3A94C +:10165000F8A3EFFCD9026F6781F6718722619D6D57 +:101660000C38E5FD937198FD8A4C2A8D8E4379A63E +:10167000934C344405EB7222059E1C4481EA050319 +:10168000534023448F4C344402EB33730A9E0C4482 +:1016900085EA0201594021448B4C4C4403EB7151C3 +:1016A000254482EA03044C402C44884D354401EB28 +:1016B0003444019E154483EA010262402A44844D69 +:1016C0003D4404EB72221D4481EA040353402B4441 +:1016D000804D354402EB3373049E294484EA0205AD +:1016E0005D4029447C4D354403EB7151079E2544F0 +:1016F00082EA03044C402C44784D354401EB3444D9 +:10170000099E2A4483EA010565401544744A32441F +:1017100004EB7525039E134481EA04026A401A44CF +:10172000704B734405EB32720B4484EA050151405F +:1017300019446D4B634402EB71511C4485EA02036A +:101740004B401C44694B334401EB3444019E1D441F +:1017500082EA010363402B44654D04EB7323354457 +:10176000069E154463EA010262402A44614D03EB80 +:10177000B2624D4462EA040929445F4D89EA0309D3 +:10178000454449442C445D4D02EBB1513544049E1F +:1017900061EA03081D4488EA0208444401EB7444EA +:1017A00064EA02034B402B44554D04EBF32375448C +:1017B00063EA010E15448EEA040E0EEB0502514D4C +:1017C00003EBB262354462EA040E29440A9D8EEAB4 +:1017D000030EA5F580164C4D7144A6F6833602EB38 +:1017E000B151264461EA030454403444029E01EBA3 +:1017F0007444354464EA02061D444E407319089E41 +:10180000424D04EBF323354463EA01061544664078 +:1018100072193F4D03EBB262654462EA0406294443 +:101820003C4D5E403144079E02EBB151354461EAC4 +:1018300003062C44384D56403D443444059E1D4417 +:1018400001EB744464EA02034B402B44334D04EB38 +:10185000F32335440B9E154463EA010262402A4497 +:101860002F4D03EBB2623544039E0D4462EA04013E +:10187000594029442B4D02EBB15135442A4E2544A1 +:1018800061EA030454402C44099D01EB74442E4446 +:1018900064EA02051E4485EA01039D1903681A449F +:1018A0000AEB040303EBF5230260436083681C44E6 +:1018B000C36819448460C1600DB0BDE8F08F00BFFB +:1018C00044EABEA4A9CFDE4B604BBBF670BCBFBEE2 +:1018D000C67E9B28FA27A1EA8530EFD4051D88042F +:1018E00039D0D4D9E599DBE6F87CA21F6556ACC4A3 +:1018F000442229F497FF2A43A72394AB39A093FCF1 +:10190000C3595B6592CC0C8FD15D84854F7EA86FE7 +:10191000E0E62CFE144301A3A111084E827E53F78A +:1019200035F23ABDBBD2D72A91D386EB094B03607F +:1019300003F18833436003F12943A3F59613A3F61B +:101940008B638360A3F18833C3600023C0E9043351 +:10195000704700BF012345672DE9F843144602692B +:1019600005460E46E300C2F3C50800F118079B18B0 +:10197000036122BF43690133436112F4FC7F436971 +:1019800003EB5473436114D0C8F1400907EB08001E +:101990004C4504D22246BDE8F84307F0DBBB403C8F +:1019A0004A464E4407F0D6FB444439462846FFF7E2 +:1019B0006FFCA04606EB0409B8F13F0FA9EB080144 +:1019C0000AD94022384607F0C5FB39462846A8F117 +:1019D0004008FFF75DFCEFE7A1096FF03F023846D2 +:1019E00002FB014206EB8111D5E7000070B50B69DF +:1019F00001F1180506460C46C3F3C503EA18501C4E +:101A00008022EA54C3F13F02072A1FD8002100F0C8 +:101A100087F929462046FFF73BFC3822002128465B +:101A200000F07EF9236929462046236563696365D2 +:101A3000FFF72EFC21461022304607F08BFB204694 +:101A400058220021BDE8704000F06AB9C3F13702A6 +:101A50000021E5E72DE9F84F4FF47A7306460D466D +:101A6000002402FB03F7DFF85080DFF8509098F96C +:101A700000305FFA84FA5A1C01D0A34210D159F801 +:101A800024002A4631460368D3F820B03B46D847A5 +:101A9000854205D1074B012083F800A0BDE8F88FEF +:101AA0000134042CE3D14FF4FA7004F0A9FD0020B6 +:101AB000F4E700BFE43300201022002014220020AD +:101AC000002307B5024601210DF107008DF807300C +:101AD000FFF7C0FF20B19DF8070003B05DF804FBDD +:101AE0004FF0FF30F9E700000A46042108B5FFF780 +:101AF000B1FF80F00100C0B2404208BD074B0A466A +:101B000030B41978064B53F821400146236820462B +:101B1000DD69044BAC4630BC604700BFE4330020B5 +:101B200014220020A086010070B50A4E00240A4D40 +:101B300005F0F8F9308028683388834208D905F029 +:101B4000EDF92B6804440133B4F5003F2B60F2D368 +:101B500070BD00BFE6330020A033002005F0B0BA0E +:101B600000F1006000F500300068704700F100608F +:101B7000920000F5003005F031BA0000054B1A68FC +:101B8000054B1B889B1A834202D9104405F0C6B945 +:101B900000207047A0330020E633002038B504460B +:101BA000074D29B128682044BDE8384005F0CEB97A +:101BB0002868204405F0B8F90028F3D038BD00BFEC +:101BC000A03300200020704700F1FF5000F58F1077 +:101BD000D0F8000870470000064991F8243033B16E +:101BE00000230822086A81F82430FFF7BFBF0120D4 +:101BF000704700BFA4330020014B1868704700BF36 +:101C00000010005C194B01380322084470B51D68B0 +:101C1000174BC5F30B042D0C1E88A6420BD15C6834 +:101C20000A46013C824213460FD214F9016F4EB1AD +:101C300002F8016BF6E7013A03F10803ECD18142A7 +:101C40000B4602D22C2203F8012B0424094A1688E1 +:101C5000AE4204D1984284BF967803F8016B013CF0 +:101C600002F10402F3D1581A70BD00BF0010005CED +:101C700024220020A0920008022803D1024B4FF03A +:101C800080529A61704700BF00100258022803D1A9 +:101C9000024B4FF480529A61704700BF0010025807 +:101CA000022804D1024A536983F480535361704778 +:101CB0000010025870B504464FF47A764CB1412CAE +:101CC000254628BF412506FB05F0641B04F098FC5F +:101CD000F4E770BD002310B5934203D0CC5CC4542C +:101CE0000133F9E710BD0000013810B510F9013FCC +:101CF0003BB191F900409C4203D11AB10131013A44 +:101D0000F4E71AB191F90020981A10BD1046FCE7CB +:101D100003460246D01A12F9011B0029FAD1704776 +:101D200002440346934202D003F8011BFAE77047CE +:101D30002DE9F8431F4D14460746884695F82420A0 +:101D400052BBDFF870909CB395F824302BB9202259 +:101D5000FF2148462F62FFF7E3FF95F82400414634 +:101D6000C0F1080205EB8000A24228BF2246D6B28D +:101D70009200FFF7AFFF95F82430A41B17441E44D0 +:101D80009044E4B2F6B2082E85F82460DBD1FFF768 +:101D900023FF0028D7D108E02B6A03EB820383429C +:101DA000CFD0FFF719FF0028CBD10020BDE8F88382 +:101DB0000120FBE7A4330020024B1A78024B1A7073 +:101DC000704700BFE433002010220020F8B5194C02 +:101DD000194803F01DFF2146174803F045FF24680A +:101DE0004FF47A70154ED4F89020154DD2F804387F +:101DF000114F43F00203C2F80438FFF75BFF20469F +:101E0000104904F03FF8D4F890200424D2F80438A4 +:101E100023F00203C2F804384FF4E133336055F87D +:101E2000040BB84202D0314603F050FE013CF6D11B +:101E3000F8BD00BFA09A000818490020CC3300204C +:101E400014220020A89A00080C4B70B50C4D0446D3 +:101E50001E780C4B55F826209A420DD00A4B0021D3 +:101E600018221846FFF75CFF0460014655F826006B +:101E7000BDE8704003F02ABE70BD00BFE43300200F +:101E80001422002018490020CC330020F0B5A1B066 +:101E900071B600230120002480261A46194602F05C +:101EA0007DFD4FF4D067214A3D25136923BBD2F84D +:101EB00010310BBB036804F1006199600368C3F83B +:101EC0000CD003685E6003681F6001680B6843F014 +:101ED00001030B6001680B6823F01E030B600168AF +:101EE0000B68DB07FCD4037B8034416805FA03F3FD +:101EF000B4F5001F0B60D8D102F086FDB4F5001FC9 +:101F000011D000240A4E0B4D012005F0D9F833887A +:101F1000A34205D928682044013405F017F8F6E7F4 +:101F2000002005F0CDF861B621B0F0BD00200052D0 +:101F3000E6330020A033002030B50A44084D91421A +:101F40000DD011F8013B5840082340F30004013B39 +:101F50002C4013F0FF0384EA5000F6D1EFE730BDC8 +:101F60002083B8ED0121884238BF084605F080B9CA +:101F700008B105F081B9704710B5084C0122084935 +:101F8000002001F0B3FE23783BB1064803F016FDB4 +:101F9000044803F049FD0023237010BDE8330020FE +:101FA000B0920008C83600201D482DE9F041036DAD +:101FB0002BB901224FF48051503005F0BDFA194E73 +:101FC00033780BB1FFF7D8FF0324174F4FF0000809 +:101FD000134D15492846C7F8048003F017FD28461D +:101FE00003F050FB48B1013C284603F01DFD14F0FE +:101FF000FF04EED1204634700FE00C4901220C485A +:1020000001F074FE014618B1284603F0D7FCEAE758 +:10201000084800F011F801203070BDE8F08100BFE1 +:10202000C8360020E83300203C220020B09200088F +:10203000EC330020B49200080FB4002004B07047C5 +:102040000068704703460068596870470B0A0170C2 +:1020500043700B0C090E8370C1707047110A027037 +:1020600003714170110C120E8170C2701A0A427114 +:102070001A0C1B0E8271C37170470000C36A0239CB +:10208000023B8B4283BF4389006C01FB03000020AD +:1020900070470000C2F307238A76CB760378032BC0 +:1020A00001BF120C0A75120A4A75704700F10B0144 +:1020B0000022D30143EA520310F8012B52FA83F3B2 +:1020C0008842DAB2F5D110467047000010B5417869 +:1020D00004460020013102464901022A16BFA35CD2 +:1020E000032203EBC03302F101021EBF9BB203EBDC +:1020F000500398B29142F0D810BD000002684AB176 +:10210000134613F8011B1F290DD93A29F9D1911C47 +:102110008B4202D04FF0FF3070471278302AF9D14D +:10212000036000207047014B187870473836002054 +:1021300038B50D46044618B9092000232B6038BD78 +:102140000368002BF8D01A78002AF5D08188DA8845 +:102150009142F1D1587804F0EFFB10F00100EBD17F +:102160002368EBE738B50D4640F25231144602F0D1 +:10217000B9F9FF2807D9012C0BD9030A022468708A +:102180002B70204638BD30B1002CFAD001242870C5 +:10219000F7E70024F5E70446F3E700002DE9F843EC +:1021A0000026D0F8008005460C468E76836B002B07 +:1021B0004AD098F80030042B4BD13346354640279F +:1021C00020E0B7F5187F80F0C480F90606F101061B +:1021D00008BF0237D05B02372BB900F5205292B20C :1021E000B2F5006F0DD305F11A01C5F1FF0240EA07 -:1021F00003402144FFF796FF002800F08680054445 -:1022000000200346BBE700200146CFE7C36C013343 -:102210005DD1FA6B00232E26551E184615F8011FB6 -:10222000013020290CD0052908BFE521092804D157 -:102230000B2B9EBFE71801337E73E71801337973C8 -:102240000B28EBD1E11800204873A17E00294CD166 -:10225000002B41D06FF00C0604F10D000825361B51 -:10226000331810F8011B002939D02E298BB249D020 -:10227000A3F14101192903D8117B0D4200D020336D -:102280000373EDE7B9F1000F05D100F520539BB2C0 -:10229000B3F5006F0BD305F11A01C5F1FF0240EA57 -:1022A00009402144FFF73EFFA0B10544002002365B -:1022B0008146D8F80C30985B0028E3D1B9F1000FC3 -:1022C0004FF0000318BF00252544AB76A1E7B146C7 -:1022D0003546EEE70546F1E73F23A3760123234485 -:1022E00000219976137B03B96373D37A02F11C0042 -:1022F00023730023FFF770FE20606360D38A63813D -:10230000138B5AE710250B46BAE73F230125A37626 -:102310003FE7000038B50546002435F8020B08B940 -:10232000204638BD02F0ACF86308C2B203EBC433F8 -:1023300012FA83F39AB2C0F3072303EB520303EBC1 -:10234000C2339CB2E9E7000001380A4411F8013BAE -:10235000914200F8013FF9D17047000037B5C378CA -:1023600004461BB90025284603B030BD00F14C01DE -:10237000826C01234078019104F0A8F9054680B9E8 -:10238000A36BE070A06C226BC31A9342EAD2A378CD -:102390000199022BE6D102440123607804F096F9FA -:1023A000E1E70125DFE7000038B5836C05460C4600 -:1023B0008B4210D0FFF7D2FF60B92246012305F10E -:1023C0004C01687804F05EF900281CBF4FF0FF3420 -:1023D0000120AC6438BD0020FCE7000038B50023C4 -:1023E0000446C3704FF0FF338364FFF7DDFF00281E -:1023F0003FD1B4F84A524AF655239D4206D10B22EA -:102400001E4904F14C00FFF70BFEA0B394F84C30CA -:10241000EB2B03D01833DBB2012B23D84AF655231C -:102420009D4206D10822164904F19E00FFF7F8FDEF -:10243000F0B1B4F857305A1E1A4213D1B3F5007FE9 -:1024400010D194F8590068B1431E18400AD194F88D -:102450005C30013B012B05D8B4F85D3013B1B4F802 -:1024600062302BB94AF6552085420CBF022003206A -:1024700038BD0420FCE70120FAE700BF8C8C00087F -:10248000988C000802392DE9F04701F007044FF05D -:10249000010A466C05460AFA04F41746984606EB0C -:1024A0001136C1F3C809E4B2314628460136FFF7B8 -:1024B0007BFF18B10120BDE8F087994605EB0902C2 -:1024C00092F84C30234214BF01210021414513D022 -:1024D0006340013F82F84C3085F803A0EBD06400E4 -:1024E00014F0FF04EAD109F1010301244FF00009BF -:1024F000B3F5007FE1D1D7E70220DCE701290246EE -:10250000F8B50C4640F28C800668F36A8B4240F2C4 -:1025100087803378013B032B00F28280DFE803F0F1 -:102520000229384B04EB5405B16B304601EB5521C1 -:10253000FFF73AFF10B14FF0FF30F8BD6F1CC5F345 -:102540000805B16B3046354401EB572195F84C50E6 -:10255000FFF72AFF0028EED1C7F30807E3073E4440 -:1025600096F84C0045EA00204CBF0009C0F30B0070 -:10257000E3E7B16B304601EB1421FFF715FF0028AC -:10258000D9D1640004F4FF742644B6F84C00D4E7B3 -:10259000B16B304601EBD411FFF706FF0028CAD11A -:1025A000A40006F14C0004F4FE742044FFF714FD6F -:1025B00020F07040C1E7D0E90430D57953EA00013A -:1025C00001D0916801B95DBB9168022DA4EB0101B6 -:1025D0000DD1013B728940F1FF305B0A43EAC053E1 -:1025E000B3FBF2F399421BD81CD0601CA5E7032D66 -:1025F00002D193698B42F8D8D3699BB9B16B30464D -:1026000001EBD411FFF7D0FE002894D1A0004C3686 -:1026100000F4FE703044FFF7DFFC20F000408CE750 -:1026200001208AE76FF0004087E70000F8B50668F0 -:1026300004460D463378042B0CBF4FF080524FF404 -:1026400000128A4201D80220F8BDCA06FBD1826876 -:102650000163D2B9022B13D83389B3EB551FF2D9DA -:10266000F36BA363A36B6263002BECD003EB5523E6 -:102670004C36C5F308050020A3633544E563E3E762 -:10268000F36BC271002BE7D01A4677897F02BD42F7 -:10269000114604D23046FFF7D1FCA063E2E72046A2 -:1026A000FFF72CFF431C024606D00128CBD9F36A62 -:1026B0008342C8D9ED1BEAE70120C5E701292DE9CE -:1026C000F04706460C46174608D9C36A8B4205D91F -:1026D0000378022B62D003D8012B22D0022552E0CE -:1026E000033B012BFAD8816B01EBD411FFF75CFEA1 -:1026F0000546002847D1A40006F14C0304F4FE74FB -:102700001C443378042B07D0204627F07047FFF78E -:1027100063FC00F07040074339462046FFF762FC37 -:102720002FE001EB5108816B01EB5821FFF73CFED4 -:10273000054640BB14F0010406F14C0908F1010AFA -:10274000C8F3080808BFFBB230461FBF19F80830AD -:1027500003F00F023B0103F0F00318BF134309F825 -:1027600008300123B16BF37001EB5A21FFF71CFE17 -:10277000054640B9CAF3080A44B1C7F3071709F878 -:102780000A700123F3702846BDE8F08719F80A3073 -:10279000C7F3032723F00F031F43F0E7816B01EB1F -:1027A0001421FFF701FE05460028ECD1640006F174 -:1027B0004C0304F4FF741F551919C7F307274F7012 -:1027C000DFE70000F8B504460E461746E3690BB98B -:1027D0001846F8BD012BA6EB0305206814BFAA1C00 -:1027E0003A46691CFFF76AFF0028F2D1E369013B12 -:1027F000E361EBE701292DE9F84306460C4617464D -:10280000056802D80220BDE8F883EB6A8B42F9D94B -:102810007AB9A14621463046A046FFF76FFE04462E -:10282000B0B92B78042B02D1002F43D1F7710020CF -:10283000E9E72B78042B02D1C379022BE9D04FF0C2 -:10284000FF3239462846FFF739FF0028E1D0DAE7A2 -:102850000128D7D0421C01D10120D4E72B78042BCA -:1028600019D1EA6AAB69023A93421CD308F101021A -:10287000A2420CD02B78042B08D10023A2EB090232 -:1028800049462846FFF7FEFD0028BCD1A146EB6A69 -:10289000A342BFD8C5E7002241462846FFF70EFFF6 -:1028A0000028DED0AFE70133AB612B7943F00103A1 -:1028B0002B71DBE7F3798BB9B468BC4202D10223F8 -:1028C000F371B4E721463046FFF718FE012899D985 -:1028D000431CC1D001348442EFD0A8E7032BA6D11A -:1028E000B368BB42A3D8B2691344BB429FD3E6E7A7 -:1028F00070B5C3790446032B06D181688369CD186E -:10290000A94203D10023E371002070BD4E1C206852 -:102910003246FFF7D3FE0028F7D13146F0E700003A -:102920002DE9F74306460191FFF718FD04460028FC -:1029300049D106F14C09019930464FF40072FFF776 -:102940007DFB2146B06407464846FFF763FB748968 -:102950006402B4F5006F28BF4FF40064B4F5007F43 -:102960002FD9204603F0EAFE804630B100212246EE -:10297000FFF750FB640A0D4609E06408EEE72346C2 -:102980007A194146707803F0A1FE18B9254473897D -:102990009D42F4D3404603F0D3FE7089401B18BF1C -:1029A000012003B0BDE8F083013573899D42F4D264 -:1029B00001237A194946707803F088FE0028F3D085 -:1029C000EBE70025F1E70120EBE70000F8B504464E -:1029D000FFF7C4FC0546002842D12378032B37D1EA -:1029E0002779012F34D104F14C06552301464FF4C9 -:1029F00000723046FFF70EFB84F84A32AA234122C8 -:102A0000722104F50D7084F84B32522384F84F2064 -:102A100084F84C3084F84D30612384F8301284F807 -:102A20004E3084F8333284F8311284F83222A169AE -:102A3000FFF7D8FA616904F50E70FFF7D3FA626BFD -:102A40003B46314601326078A26403F03FFE2571B7 -:102A500000226078114603F05DFE003818BF0120A7 -:102A6000F8BD000000232DE9F0430B6085B00F4650 -:102A70001546FFF723FB061EC0F2B281804B53F8C8 -:102A80002640002C00F0AE813C6005F0FE05237866 -:102A90006BB1607803F0F4FDC70708D41DB110F0E6 -:102AA000040500D00A25284605B0BDE8F0830023C0 -:102AB000F0B22370607003F0D1FDC10700F1948182 -:102AC0000DB14207EED400212046FFF787FC022813 -:102AD00040F099806E4604F2122304F252213246ED -:102AE00018461033FFF778FA42F8040B8B42F7D1FF -:102AF000002556F8041B00297DD02046FFF76EFC08 -:102B0000012879D80128A26C40F0C08004F1570355 -:102B100004F18C0113F8015B002D7BD18B42F9D1BC -:102B2000B4F8B430B3F5807F74D194F8B830092B81 -:102B300070D104F19400FFF751FA4FF0FF331718EA -:102B400041F10001BB4275EB010363D304F1A00026 -:102B5000FFF742FA94F8BA302063012BA37059D1E1 -:102B600094F8B99003FA09F91FFA89F36381002BED -:102B700050D0444B04F1A800FFF72EFA06469842C5 -:102B800048D8831C626304F1A400E362FFF724FACF -:102B900000EB020804F19C00C4F84080FFF71CFA27 -:102BA00010441FFA89F2A06306FB02F313EB08033B -:102BB00045EB05029F4271EB02032BD32E4604F135 -:102BC000AC00FFF709FAE06365B96389B34221D924 -:102BD000E16B2046FFF732FA81192046FFF7E4FB4C -:102BE00098B90136631993F84C30812B14D02035F5 -:102BF000C5F30805E8E703200135042D7FF479AF1C -:102C0000042807D101E0042801D101254BE7012860 -:102C10007FF678AF0D2546E705F1140004F14C0668 -:102C20003044FFF7D9F901280546F3D9E36A834216 -:102C3000F0D96189821E236C02FB01336364A16BAE -:102C4000204601EBD511FFF7AFFB0028DDD105F0E1 -:102C50007F0006EB8000FFF7BFF9431C03D001356E -:102C6000A842ECD0D6E70425C4E90500064A257041 -:102C700000251388E56101339BB21380E38012E7DE -:102C800098360020FDFFFF7F9C360020B4F85730B7 -:102C9000B3F5007FBED1B4F8626026B904F17000CC -:102CA000FFF79AF9064694F85C302663591EA37024 -:102CB0000129AFD894F859506581002DAAD0691E1A -:102CC0002942A7D1B4F85D8018F00F0FA4F808804E -:102CD000A0D1B4F85F0018B904F16C00FFF77CF9DB -:102CE000B4F85A10002995D006FB03FE01EB181C1E -:102CF000F44460458ED3A0EB0C00A842B0FBF5F382 -:102D000088D33E48834285D84FF6F57083426DD90B -:102D100003259F1C114402EB0C03032DE762626341 -:102D2000A16323644CD1B4F8763053EA08037FF4EE -:102D300071AFBB0004F17800FFF74EF9E06303F2D6 -:102D4000FF13B6EB532FFFF465AF4FF0FF33032DA6 -:102D5000C4E905334FF08003237187D1B4F87C3088 -:102D6000012B83D1511C2046FFF71EFB00287FF466 -:102D70007DAFB4F84A224AF6552320719A427FF477 -:102D800075AF1F4B04F14C00FFF726F998427FF412 -:102D90006DAF03F1FF5304F50C70FFF71DF903F558 -:102DA0000053203398427FF461AF04F50D70FFF7B4 -:102DB00013F9A06104F50E70FFF70EF9606155E795 -:102DC000B8F1000F3FF426AF7144022D4FEA4703DC -:102DD000E1631EBFD91907F0010303EB5103AEE70E -:102DE0000B2560E60C255EE603255CE640F6F575EE -:102DF000AB428CBF022501258BE700BFF5FFFF0F1B -:102E0000525261412DE9F84F07460568884649B995 -:102E10006E69C6B1EB6AB34298BF0126AB69A3B92C -:102E2000002405E0FFF76AFB0128044603D80124CB -:102E30002046BDE8F88F421C00F0D280EB6A834246 -:102E4000F6D84646EAE70126E8E72A78EB6A042A3C -:102E500040F08380A6F1020A023B4FF0010B9A4535 -:102E600028BF4FF0000AD146696C284601EB1931A2 -:102E7000FFF79AFA00283BD109F00703EA6AC9F381 -:102E8000C8010BFA03F3901EDBB26A184C4609F135 -:102E9000010992F84C20814502EA030233BF5B002E -:102EA00000234FF40071DBB228BF9946B2B9023457 -:102EB000631E0333BCD80123214628461A46FFF778 -:102EC000E1FA0228B3D0012800F08A80B8F1000F9F -:102ED00013D10223FB710028A9D130E0CA450AD0E2 -:102EE000002BD2D10131B1F5007FBDD20123CCE757 -:102EF0004FF0FF34DCE70024DAE7FB79022B07D13F -:102F0000731CA342E7D0BB68F31ABB610323FB71B8 -:102F100008F10102FB69A24205D113B10133FB6143 -:102F2000D9E70223FBE70BB90123FB6122464146A7 -:102F30003846FFF747FC00284FD10123FB61EA6ABE -:102F4000AB69023A6C6193429CBF03F1FF33AB6102 -:102F50002B7943F001032B716AE7464514D1741CA9 -:102F60003846A34298BF02242146FFF7C7FA01283A -:102F70003FF45DAF431C33D0E0B16B69012B03D943 -:102F8000EA6A934238BF1E4634460134EB6AA342D4 -:102F900003D8012E7FF644AF022421463846FFF7BE -:102FA000ADFA48B101283FF442AF013018D0B44225 -:102FB000EBD135E7002CE7D04FF0FF322146284611 -:102FC000FFF77CFB48B9B8F1000FB8D02246414664 -:102FD0002846FFF773FB0028B1D001287FF427AF04 -:102FE0004FF0FF3424E700002DE9F843066804465B -:102FF000076B894633782037042B0CBF4FF0805382 -:103000004FF40013BB429CBF00238363836B73B1F7 -:10301000C7F30808B8F1000F3CD10133416B83635B -:1030200039B93389B3EB571F34D80023A363042085 -:103030000AE07389013B13EA57232BD1FFF75EFAAD -:103040000128054602D80220BDE8F883421C01D1C0 -:103050000120F9E7F36A834216D8B9F1000FE4D0F2 -:10306000616B2046FFF7CEFE0546C8B10128EAD0C5 -:10307000431CEDD001463046FFF752FC0028E7D153 -:10308000E37943F00403E371294630466563FEF7B4 -:10309000D5FFA0634C36002027634644E663D3E7A0 -:1030A0000720D1E72DE9F04105460068A96B0669C4 -:1030B000FFF77AF9044620B9E96B0B78852B03D02A -:1030C00002242046BDE8F08120223046FFF73CF97B -:1030D000777801377F01A7F16003B3F5007FEFD860 -:1030E00021462846FFF780FF04280446E8D0002840 -:1030F000E7D1A96B2868FFF757F904460028E0D10B -:10310000E96B0B78C02BDBD12022B018FFF71CF93C -:1031100096F823300F222C33B3FBF2F3B7EB431FA7 -:10312000CED34FF0400800212846FFF75DFF04286A -:103130000446C5D00028C4D1A96B2868FFF734F92C -:1031400004460028BDD1E96B0B78C12BB8D1B8F586 -:10315000187F04D2202206EB0800FFF7F5F808F1EB -:1031600020084745DFD8B8F5187FAAD83046FEF7C3 -:103170008DFF73888342A4D0A2E700000B68002271 -:1031800010B5036004460B6A83604B6AC261C37169 -:1031900023F0FF03896AC0E90432C164FFF746FAED -:1031A00020B92046BDE81040FFF77CBF10BD0000ED -:1031B000F8B50E46002104460768FFF737FA98B9BC -:1031C0000546A16B3846FFF7EFF868B93A78E36B2C -:1031D000042A1B780CD11B060ED50546012120467A -:1031E000FFF702FF0028ECD0042808BF072006E004 -:1031F000E52B01D0002BF0D10135B542EED1F8BD61 -:1032000003682DE9F0411E6905464FF0010830467C -:10321000FEF73CFFB070000A7778F0702846E96C42 -:10322000FFF704FA04462CB1022C28BF0224E0B2B6 -:10323000BDE8F081A96B2868FFF7B6F804460028BE -:10324000F2D120223146E86BFFF77EF82B6883F835 -:103250000380002FE8D021462846FFF7C5FE203620 -:103260000446013FDFE70000C16C4B1C2DE9F04133 -:1032700004460568066B1FD1E5274FF00108A16BD6 -:103280002846FFF791F898B92A78E36B042A09BF1A -:103290001A781F7002F07F021A7085F80380236B82 -:1032A000B3420DD200212046FFF79EFE0028E6D053 -:1032B000042808BF022003E0FFF7B8F90028DBD09C -:1032C000BDE8F0812DE9F8434FF0FF080646076896 -:1032D000042445464FF6FF79B16B11B9002C73D029 -:1032E00063E03846FFF760F8044600285DD1F06BD4 -:1032F0000378002B6ED03A78042A11D1852B4DD15A -:10330000336B3046F364FFF7CDFE044600284CD102 -:103310003B691B7903F03F03B3712046BDE8F88396 -:10332000C27AE52B02F03F02B27143D02E2B41D07E -:1033300022F0200108293DD00F2A40D1590637D567 -:1033400003F0BF05336B90F80D80F364437B434576 -:1033500030D1428B72BB03780D21FC6823F040030F -:10336000DFF874E0013B4B4301211EF801CB30F83C -:103370000CC009B3FF2B1DD824F813C061460133DC -:1033800001320D2AF1D10278520605D521B1FF2B69 -:1033900010D8002224F81320013DEDB20021304660 -:1033A000FFF722FE0446002896D00023B363B4E75B -:1033B000AB42CBD0FF25F1E7CC45E1D0FAE72DB900 -:1033C000FEF754FE404501D10024A6E74FF0FF333D -:1033D000F364A2E70424E8E7348D00082DE9F04FF8 -:1033E000002187B00446D0F80090FFF71FF980460F -:1033F00070B999F80030042B33D1D9F80C00FEF7DE -:1034000089FF07462046FFF75DFF054620B180464D -:10341000404607B0BDE8F08FD9F810309A8CBA4218 -:10342000F0D193F823B040265D4506D1D9F80C3091 -:1034300033F81530002BE5D1EAE7F106D9F8103062 -:1034400008BF0236985B01F01BF8D9F80C308246B1 -:1034500033F8150001F014F88245D3D10236013556 -:10346000E2E74FF0FF0A4FF0FF3B5546C4F84CB07F -:10347000A16B4846FEF798FF00285CD1E66B3778D1 -:10348000002F77D0F27AE52F02F03F03A37103D02B -:10349000120704D50F2B04D0C4F84CB04FE00F2B0B -:1034A00054D194F84B3058063FD4790645D5236B58 -:1034B00007F0BF0796F80DA0E364737B53453ED138 -:1034C000738B002B3BD135780121D9F80C3005F0F6 -:1034D0003F0501930D23013D5D43284B13F8012B5C -:1034E000B25A71B3FF2D059329D81046049200F00B -:1034F000C7FF6B1C03900293019B33F8150000F08B -:10350000BFFF039981421AD1049A029D1146059B7F -:103510001B4A9342E2D133785A0604D519B1019B74 -:1035200033F815305BB97D1EEDB200212046FFF760 -:103530005BFD00289CD080466AE7BD42BDD0FF25D8 -:10354000F3E74FF6FF708242E2D0F8E72DB930463C -:10355000FEF78CFD50453FF45BAF94F84B30DB0732 -:103560009AD40B2204F140013046FEF759FD0028A1 -:1035700092D14DE74FF004084AE700BF348D0008B0 -:10358000418D00082DE9F04F90F84B5099B004465A -:1035900015F0A00540F061810668F26832F8153038 -:1035A000002B4AD13378042B40F086800F230E3550 -:1035B0002046B5FBF3F5A91CFFF7FAFD814600286C -:1035C00076D1236B0135A3EB4515E3795A07E56402 -:1035D00035D523F004032046E371FFF789F950BB8A -:1035E0004FF0FF32616B2046FFF7ECF818BBA36881 -:1035F0002BB3214604A8FFF7C1FDE0B970894FF451 -:103600000071D4E90423E0FB01233069C4E90423F9 -:103610003830FEF7EFFC3069D4E904232830FEF798 -:10362000E9FCE379326904A843F0010382F8213010 -:10363000FFF7E6FD18B181463AE00135AEE7D6E97D -:1036400003548523002140222046FEF7E3FC01229B -:103650002370C0230E464FF0C10C84F820308E46F4 -:10366000402304EB02085F1C04F803C0F0B20233ED -:1036700004F807E022B135F811200AB10131C9B2CE -:10368000170AE25408F803700233DF06F2D135F866 -:1036900011700136002FE6D1831C84F823102846D0 -:1036A0006370FEF737FE84F82400000A84F82500D2 -:1036B000484619B0BDE8F08F04F140070C2204A879 -:1036C0003946FEF741FE9DF81B30DB0740F1CF8005 -:1036D00040234FF0010ADFF8F88184F84B300B22C9 -:1036E00004A93846D6F80C90FEF72EFEBAF1050F65 -:1036F00054D9A9F10201534631F8022F002A3FD1D3 -:103700000DF10F00072203F00F0C0CF130013929E5 -:1037100088BF0CF13701013A00F801194FEA131183 -:1037200001D00F2B3CD818AB7E21134403F8581C52 -:1037300039460023934205D011F8010B03F1010C27 -:1037400020282FD104F13F00072A03F1010397BF7E -:1037500018A920218918013298BF11F8581C072B8D -:10376000C154F1D92046FFF739FE8146002877D1B0 -:103770000AF1010ABAF1640FB1D14FF0070997E7D6 -:10378000102002F0010C52080CEB430313F4803FAD -:1037900018BF83EA08030138F3D1ADE75346AFE71A -:1037A0000B46B0E76346C5E7216B2046A1EB451108 -:1037B000FEF73CFF814600287FF47AAF4FF6FF7892 -:1037C0003846FEF753FC0190A16B3046FEF7ECFD46 -:1037D000814600287FF46CAFE36BE9B2019A4FF0A9 -:1037E0000D0CD6F80CE05A734FF00F02DFF8E4A08E -:1037F000DA724A1E18730CFB02F284469876D87669 -:1038000040451AF8019B0CF1010C18BF3EF812005C -:1038100003EB090B18BF013203F809004FEA102926 -:10382000002808BF4046BCF10D0F8BF80190E7D18E -:10383000404502D03EF812200AB941F0400119700B -:10384000012300212046F370FFF7CEFB81460028BC -:103850007FF42EAF013DB7D11EE04FF0060927E7F8 -:1038600004287FF425AF9DF81B3084F84B309DF879 -:103870001B3020469B0745BF0C350D210125B5FBAC -:10388000F1F548BF01352946FFF792FC8146002833 -:103890007FF40EAF013D87D1A16B3046FEF784FD6A -:1038A000814600287FF404AF01462022E06BFEF73A -:1038B000B1FB0B223946E06BFEF746FD94F84B3026 -:1038C000E26B03F0180313730123F370F0E600BFFB -:1038D00021100100348D000810B504460A4634302A -:1038E000FEF77AFB886004F13800FEF777FBC2E947 -:1038F000040194F8213003F00203D3710023D36153 -:1039000010BD000003284B8B04BF8A8A43EA0243A0 -:10391000184670472DE9F04F0B7899B00446884659 -:103920002F2BD0F800B001D05C2B09D14246137880 -:10393000904601322F2BFAD05C2BF8D0002301E007 -:10394000DBF81C30A3600023E3619BF80030042BFC -:103950001ED1A368E3B1DBF82030214604A823621E -:10396000DBF824306362DBF82830A362FFF706FC43 -:103970000346002859D1DBF8102002F13800FEF789 -:103980002BFBC4E9040392F8213003F00203E37136 -:1039900098F800301F2B00F223818023002120465D -:1039A00084F84B3019B0BDE8F04FFEF73FBEFF2E54 -:1039B00000F038812AF81600013615E142461378E6 -:1039C000904601322F2BFAD05C2BF8D00025012E27 -:1039D00030D1BAF800302E2B32D1002304F140024E -:1039E0002AF816309E428CBF2E21202101330B2B4A -:1039F00002F8011BF6D145F02005204684F84B5013 -:103A0000FFF7ECFC94F84B30002800F0D08004283D -:103A10000BD1990603F0040240F1C580002A00F0A2 -:103A2000DF808023002084F84B3019B0BDE8F08F90 -:103A30000425CCE7022E03D1BAF802302E2BC8D0D1 -:103A4000AAF102028EBB00222AF81620002E00F0F6 -:103A5000E9803AF81210134601322029F9D00BB947 -:103A60002E2901D145F00305AAF1020131F81620F3 -:103A70002E2A01D0013EF9D14FF000090B2220215E -:103A800004F14000FEF7C6FA4F460822591C3AF8E6 -:103A900013000191F0B1202803D02E280DD1B1429E -:103AA00010D045F00305019BF0E732F81630202BCB -:103AB00001D02E2BC7D1013EC4E7914505D2019B11 -:103AC000B34235D10B2A2CD101E00B2A23D145F08A -:103AD00003050B2294F84030E52B04BF052384F83E -:103AE0004030082A04BFBF00FFB207F00C030C2BC4 -:103AF00003D007F00303032B01D145F00205AB0708 -:103B00003FF57BAFFE0748BF45F01005780748BF7B -:103B100045F0080571E7019BB34202D045F003056B -:103B2000D8D8BF000B224FF008090196FFB2BAE7C0 -:103B30007F2812D945F0020340F2523103920293DA -:103B400000F06AFC10F0800FDDE9023210D000F0C6 -:103B50007F004349085C1D4630B1424911F8013BE2 -:103B6000002B6DD08342F9D145F003055F2010E0B2 -:103B7000FF28F0D9511E894503D345F0030591462E -:103B800091E704EB0901050A09F1010981F84050A8 -:103B90001D4604EB090309F1010983F8400082E79F -:103BA00047F00207F5E7002A08BF05203DE75A075E -:103BB0003FF53BAFA379DB0640D59BF80000042816 -:103BC00032D1A3682146E27923622369DBF8100031 -:103BD00023F0FF0313436362E36CA362FFF77CFEF1 -:103BE00023680026D3F80CA018F8010B00283FF436 -:103BF0001FAF40F2523100F02FFC98B11F287FF622 -:103C000017AF2F283FF4DAAE5C283FF4D7AE7F28F9 -:103C10003FF6CDAE144A12F8013B002B3FF4C7AE7D -:103C20008342F8D1062000E7216B0BF14C03C1F36E -:103C300008011944FFF766FEA060D1E70520F4E60D -:103C4000A0F141039BB2192BAAD9A0F161039BB249 -:103C5000192B9EBF203847F0010780B299E700BFBB -:103C6000B48C0008AD8C0008A48C00081FB5CDE909 -:103C7000001003A814460391FEF720FA002815DB74 -:103C80000B4A52F820300BB100211970019B0BB187 -:103C90000021197042F820302CB1002201A9684699 -:103CA000FEF7E0FE0446204604B010BD0B24FAE700 -:103CB000983600202DE9F04798B0904605460191CE -:103CC000002800F04F8102F03F0603A901A8324608 -:103CD000FEF7C8FE002840F04381039B4FF48C6040 -:103CE000049302F02BFD0746002800F03D81039B62 -:103CF00000F500720199D86004A81A61FFF70AFE66 -:103D0000044620B99DF95B30002BB8BF062418F09B -:103D10001C0F00F0C980002C4BD0042C3FD104A80C -:103D2000FFF730FC0446002839D146F00806039B13 -:103D30001A78042A7FD1186929462B60FFF7CCFD39 -:103D4000039B00211E2218690230FEF763F9039BD2 -:103D50001A2218692630FEF75DF9039B20211A69A3 -:103D600011711C6903F050F9014601220834204604 -:103D7000FEF738F9039B04A81B6983F82120FFF79D -:103D80003FFA044658B9A96801B302462846FEF72F -:103D900031FDAB68039A0446013B5361B4B1384628 -:103DA00002F0CEFC0CB100232B60204618B0BDE819 -:103DB000F0879DF8163013F0110F40F0818018F055 -:103DC000040F40F0C78018F0080FB0D1039A3107F4 -:103DD0001399936C48BF46F04006E964AB641078D1 -:103DE00004286FD1069B9DF817102B62089B106961 -:103DF00023F0FF030B4329466B62179BAB62FFF76F -:103E00006BFD039B0024002205F150082B60214626 -:103E1000DB88404685F83060AB80002385F8314070 -:103E20006C64C5E90E234FF40072FEF7F3F8B20696 -:103E300053D40024B3E703F0E7F801460090139849 -:103E40000E30FEF7CFF8139800991630FEF7CAF837 -:103E5000039C13992078FFF755FD2023002280460C -:103E6000CB7220461399FEF7F5F8139B002201212F -:103E70001A775A779A77DA77039BD970B8F1000FDF -:103E8000A4D0414604A8D3F84890FEF7B3FC0446FA -:103E9000002884D149460398FEF786FA039B04461E -:103EA00008F1FF30586179E7002C7FF478AF9DF876 -:103EB0001630DC0650D418F0020F87D0D80785D50D -:103EC00007246CE7FFF71EFD0023A86001F11C002A -:103ED000FEF782F86B61286193E7D5E9046956EA39 -:103EE0000903A6D0039BA968B3F80AA04FEA4A2A9F -:103EF000C5E90E69B24574EB09031BD3002429649C -:103F0000002C7FF44CAFC6F30803002B91D0039C28 -:103F10002046FEF793F808B3760A0123414646EAA5 -:103F2000C95682196A64607802F0ACFB041E18BF9F -:103F3000012434E72846FEF7E1FAB6EB0A0601460B -:103F400069F10009012803D9431CD3D10124D6E724 -:103F50000224D4E7082422E7042420E702241EE7F1 -:103F6000044620E7092420E711241EE72DE9F04F3D -:103F7000994685B00023884603A90446C9F8003055 -:103F80001646FEF7B5F8054680BB94F831506DBB78 -:103F900094F8303013F00103009300F0A68004F190 -:103FA000500AD4E90432D4E90E011B1A62EB010273 -:103FB000B34272F1000238BF1E46BEB1D4E90E1002 -:103FC000C1F30803002B40F08280039B5A894B0AFF -:103FD000013A43EAC0531A401BD151EA000309D108 -:103FE000A06801280DD8022584F83150284605B074 -:103FF000BDE8F08F216C20460192FEF77FFA019A0E -:10400000EFE7431C04D10123009D84F83130EDE734 -:104010002064DDF80CB0216C5846FEF70FF800283C -:10402000E1D0B6F5007F02EB000731D3BBF80A10F0 -:1040300002EB5620730A88429BF8010088BF8B1A56 -:104040003A464146019302F01DFB0028DBD194F96A -:104050003020019B002A0BDA606CC01B984207D20B -:104060004FF40072514608EB4020FEF76DF9019BBA -:104070005F02D9F80030F61BB8443B44C9F8003061 -:10408000D4E90E32DB1942F10002C4E90E3294E7A2 -:10409000626CBA421AD094F93030002B0DDA012349 -:1040A00051469BF8010002F011FB0028ABD194F8B7 -:1040B000303003F07F0384F83030039801233A4610 -:1040C0005146407802F0DEFA00289CD16764A16B6B -:1040D0004046C1F30801C1F500775144B74228BFFB -:1040E00037463A46FEF730F9C3E707257EE700007A -:1040F00070B596B00E460022019002A901A8FEF705 -:10410000B1FC0446E0B94FF48C6002F017FB0546A1 -:10411000D8B1029B00F500720199D86002A81A611B -:10412000FFF7F8FB044640B99DF95330002B0ADB3A -:104130001EB1314602A8FEF70FF8284602F000FB38 -:10414000204616B070BD0624F7E71124F8E70000FA -:1041500070B5B8B00222019003A901A8FEF782FC55 -:10416000044608BB039B4FF48C60109302F0E6FA00 -:104170000546002866D0039B00F500720199D860BF -:1041800010A81A61FFF7C6FB044650B99DF88B30A2 -:10419000980655D4190653D49DF84630DA0706D54B -:1041A0000724284602F0CCFA204638B070BD039BA5 -:1041B00004931878042814D104A91869FFF78CFB1C -:1041C000069E9DF84630DB0610D410A8FFF74CF889 -:1041D00004460028E5D156BB0398FEF7F7FB0446DA -:1041E000DFE71F99FFF78EFB0646EAE7039BDA69D4 -:1041F000B242D5D024930021269624A81B78042B04 -:1042000001BFDDE90823CDE928239DF817308DF89B -:104210009730FEF70BFA04460028C2D124A8FFF716 -:1042200051F804460028BBD00428BAD1CDE7024695 -:10423000314604A8FEF7DEFA04460028B1D1CBE7E8 -:104240000624AEE71124AFE7F0B5BDB0CDE900100C -:104250006846FDF733FF022203A901A8FEF702FC1E -:104260000446002838D1039B4FF48C60149302F06D -:1042700065FA0546002800F0CD80039B00F500722A -:104280000199D86014A81A61FFF744FB044600BBEB -:104290009DF89B3013F0A00F40F0B880039B1A7874 -:1042A000042A58D11969402204A8FEF74DF850227B -:1042B00028A80DEB0201FEF747F8009928A8FFF7A0 -:1042C00029FB0446002843D12A9A169B9A4206D01D -:1042D0000824284602F034FA20463DB0F0BD349A56 -:1042E000209B9A42F4D128A8FFF74CF904460028F5 -:1042F000EFD1039B04A940221869848C477890F879 -:104300002360FEF721F8039B28A81B695F70039BBD -:104310001A6982F823601A6982F82440240A82F814 -:1043200025401A691379D9065CBF43F02003137145 -:10433000FEF766FF04460028CBD114A8FEF794FFD1 -:1043400004460028C5D10398FEF740FB0446C0E7A9 -:104350000428BED1C7E72022239904A8FDF7F4FF63 -:10436000502228A80DEB0201FDF7EEFF009928A8C6 -:10437000FFF7D0FA0446002844D12A9A169B9A42A5 -:10438000A6D1349A209B9A42A2D128A8FFF7FAF826 -:10439000044600289DD1379C13220DF11D010127F1 -:1043A00004F10D00FDF7D0FF9DF81B30039EDA06E7 -:1043B00058BF43F02003E372F770E37ADB06BCD505 -:1043C000169A2A9B9A42B8D021463078FFF79AFA7B -:1043D00001463046FDF732FE0146C8B13046FDF7D2 -:1043E000E3FF044600287FF474AF039890F86D3023 -:1043F0002E2BA2D12A9A00F16C01FDF72BFE039B14 -:10440000DF709AE704287FF464AFBEE7062460E714 -:1044100002245EE711245FE77F2810B501D880B23F -:1044200010BDB0F5803F13D240F2523399420FD104 -:104430000849002231F8024B93B2844203D103F1C0 -:104440008000C0B2ECE70132802AF3D11346F6E7D0 -:104450000020E5E7F48F00087F280DD940F25233A1 -:10446000994208D1FF2806D800F10040034B80385C -:1044700033F8100070470020704700BFF48F000829 -:10448000B0F5803FF0B522D21F4A83B21F49B0F584 -:10449000805F28BF0A46141D34F8042C2146AAB1B7 -:1044A000934213D334F8025C2E0AEFB252FA85F528 -:1044B000A84222DA082E09D8DFE806F0050A101211 -:1044C0001416181A1C00801A34F810301846F0BD63 -:1044D000981A00F001001B1A9BB2F7E7103BFBE7AC -:1044E000203BF9E7303BF7E71A3BF5E70833F3E702 -:1044F000503BF1E7A3F5E353EEE70434002ECBD1B4 -:1045000001EB4702C7E700BF448D0008388F000861 -:1045100001F001038A0748BF43F002034A0748BF7E -:1045200043F008030A0748BF43F00403CA0648BF24 -:1045300043F010038A06426B48BF43F02003134345 -:1045400043637047094BC26A994228BF1946D0F8A5 -:104550004C328B4210B5507906D95A1E4C0002EBF2 -:104560004103B3FBF4F3184410BD00BF20BCBE00F0 -:1045700010B5202383F311880024064B06482146FA -:10458000DC6301F07DFF84F31188BDE8104002F088 -:1045900039BF00BF00700052DC36002010B5094C56 -:1045A000204600F0ADFF084B00220849636431202B -:1045B000C4E90F23064BC4E992130921BDE810405A -:1045C00000F022BCA0360020005A620200700052A7 -:1045D00000B4C404C36A0BB90F4BC3620379012B47 -:1045E00011D10E4B98420ED10D4BD3F8D42042F48A -:1045F0008032C3F8D420D3F8FC2042F48032C3F8D0 -:10460000FC20D3F8FC30D0F8483200221A605A60FF -:10461000DA625A62704700BFF4900008A0360020AA -:10462000004402580379012B18D0D0F848320022F8 -:104630001A605A60DA625A62094B98420ED1094BED -:10464000D3F8D42022F48032C3F8D420D3F8FC204D -:1046500022F48032C3F8FC20D3F8FC30704700BF4E -:10466000A03600200044025810B5D0F8484207494F -:10467000FFF768FF6060236842F2107043F00303A5 -:104680002360BDE8104001F0E1BE00BF801A0600C3 -:1046900038B5D0F8485201296C6808BF054924F0A4 -:1046A000FF0418BF0449FFF74DFF044344F480544E -:1046B0006C6038BD80F0FA0240787D01D0F8483255 -:1046C00000225A601A607047D0F8482201295368C6 -:1046D00023F4404304D0022905D001B95360704748 -:1046E00043F48043FAE743F40043F7E7D0F8483255 -:1046F00041F480519A60D9605A6B1206FCD5802231 -:104700009A63704710B541F48851D0F84842A260CE -:10471000E160616B11F04502FBD0A26311F004026D -:1047200003D0FFF7F5FE012010BD61691046196046 -:10473000FAE7000010B541F48851D0F84842A26071 -:10474000E160616B11F04502FBD0A26311F005023C -:1047500003D0FFF7DDFE012010BD6169104619602E -:10476000FAE700002DE9F041044628200F461646DE -:1047700001F06CFED4F84802C56A00F1580115F04A -:1047800002053FD0826AD4F8500202F077FD10B9DA -:104790000120BDE8F081202383F311884FF0FF3121 -:1047A000D4F848024FF49D738163C363012303650A -:1047B000C36A43F00103C36204F13C0001F052FEFE -:1047C000D4F848220023136583F31188D4F84832C3 -:1047D000D4F85002996D9A6A02F078FDD4F8483204 -:1047E0005A6BD205D4D54FF0FF32012F9A634FF0A8 -:1047F0000002DA6231D9334620460C21BDE8F0418F -:10480000FFF798BF4FF0FF384FF49D73C0F8388022 -:10481000C363826AD4F8500202F066FD0028B7D064 -:10482000202383F311880122D4F84832414604F151 -:104830003C001A65DA6A42F00102DA6201F012FE07 -:10484000D4F848321D6585F31188D4F84832D4F87D -:104850005002996D02F074FDC0E7104699E7000020 -:1048600073B5D0F84842002501924FF0FF320E4652 -:10487000616B2565A263E562FFF74AFE012E07D949 -:10488000019B2A460C2102B0BDE87040FFF752BFE1 -:1048900002B070BD10B541F49851D0F84842A26002 -:1048A000E160616B11F04502FBD0A26311F03F02A1 -:1048B00003D0FFF72DFE012010BD216A10461960BC -:1048C000E1695960A16999606169D960F4E7000004 -:1048D0007FB516460193026C0D46D0F84832044667 -:1048E0005A6200F0D3FD019938B1204603AA012194 -:1048F000FFF7B6FF012004B070BDD4F84802089A53 -:10490000C36A43F40053C3624FF0FF33836306234B -:1049100086628565C36203AB2046FFF70BFF002864 -:10492000E3D1064B039A1340002BDED103AA0121E9 -:104930002046FFF717FF0028DDD0D6E708E0FFFD8F -:10494000F7B517461D46026C0446D0F848320E46AD -:104950005A6200F09BFD00BBD4F84832DA6A42F498 -:104960000052DA624FF0FF329A636A029A62922230 -:104970009F65DA62236BDB0601AB58BF7602012D1F -:1049800032460CD912212046FFF7D4FE48B120460A -:1049900001AA2946FFF764FF012003B0F0BD1121F1 -:1049A000F1E7064B019A1340002BF0D101AA2946EA -:1049B0002046FFF7D7FE0028EFD0E8E708E0FFFD2C -:1049C000F7B517461D46426C0446D0F848320E46ED -:1049D0005A6200F05BFDE8B9D4F84832DA6A42F472 -:1049E0000052DA624FF0FF329A636A029A62236BD6 -:1049F000DB0601AB58BF7602012D32460CD91921D6 -:104A00002046FFF797FE48B1204601AA2946FFF746 -:104A100027FF012003B0F0BD1821F1E7084B019AF0 -:104A20001340002BF0D1D4F848329022294620467A -:104A30009F65DA6201AAFFF795FE0028EAD0E3E756 -:104A400008E0FFFD12F0030F2DE9F04107460C4688 -:104A500015461E461CD0C1EBC1520E44DFF838800B -:104A600005EB4225B44202D10020BDE8F0810123CC -:104A7000094A21463846FFF763FF0028F5D105EBC8 -:104A800044204FF4007241460134FDF709F9E9E78B -:104A9000BDE8F041FFF754BFF438002012F0030FD7 -:104AA0002DE9F04107460C4615461E461CD0C1EBC9 -:104AB000C1520E44DFF8388005EB4225B44202D1E2 -:104AC0000020BDE8F0814FF4007205EB4421404620 -:104AD000FDF7E6F80123424621463846FFF770FF0E -:104AE0000028EED10134E9E7BDE8F041FFF768BFE7 -:104AF000F4380020002070470268436811430160C9 -:104B000003B1184770470000024A136843F0C0031E -:104B10001360704700440040024A136843F0C0032A -:104B20001360704700480040024A136843F0C00316 -:104B3000136070470078004037B5274C274D20465A -:104B400000F03AFD04F11400009400234FF40072C9 -:104B5000234900F0C9F94FF40072224904F13800EA -:104B60000094214B00F042FA204BC4E91735204C49 -:104B7000204600F021FD04F11400009400234FF4BE -:104B800000721C4900F0B0F94FF400721A4904F1A8 -:104B900038000094194B00F029FA194BC4E9173575 -:104BA000184C204600F008FD04F1140000234FF4D7 -:104BB00000721549009400F097F9144B4FF40072FD -:104BC000134904F13800009400F010FA114BC4E9C5 -:104BD000173503B030BD00BFF43A002000E1F50501 -:104BE000383C002038420020094B000800440040B7 -:104BF000603B0020383E002038440020194B00085C -:104C000000480040CC3B002038400020294B0008E1 -:104C10003846002000780040037C30B5334C002932 -:104C200018BF0C46012B18D1314B98420FD1314B94 -:104C3000D3F8E82042F40032C3F8E820D3F810217A -:104C400042F40032C3F81021D3F8103105E02A4BAA -:104C500098422FD0294B984238D02268036EC16DFC -:104C600003EB52038466B3FBF2F36268150442BFA0 -:104C700023F0070503F0070343EA4503CB60A3686D -:104C800043F040034B60E36843F001038B6042F460 -:104C9000967343F001030B604FF0FF330B62510535 -:104CA00005D512F010221DD0B2F1805F1CD080F823 -:104CB000643030BD0F4BD3F8E82042F48022C3F8B3 -:104CC000E820D3F8102142F48022BBE7094BD3F847 -:104CD000E82042F08042C3F8E820D3F8102142F0E7 -:104CE0008042AFE77F23E2E73F23E0E7FC90000844 -:104CF000F43A002000440258603B0020CC3B0020E6 -:104D00002DE9F047C66D05463768F469210734621E -:104D100019D014F0080118BF8021E20748BF41F004 -:104D20002001A3074FF0200348BF41F04001600776 -:104D300048BF41F4807183F31188281DFFF7DCFE22 -:104D4000002383F31188E2050AD5202383F3118819 -:104D50004FF40071281DFFF7CFFE002383F3118865 -:104D60004FF020094FF0000A14F0200838D13B061C -:104D700016D54FF0200905F1380A200610D589F321 -:104D80001188504600F066F9002836DA0821281DFF -:104D9000FFF7B2FE27F080033360002383F311880E -:104DA000790614D5620612D5202383F31188D5E93C -:104DB00013239A4208D12B6C33B127F040071021FE -:104DC000281DFFF799FE3760002383F31188E3065F -:104DD00018D5AA6E1369ABB15069BDE8F047184702 -:104DE00089F31188736A284695F86410194000F019 -:104DF000FDFB8AF31188F469B6E7B06288F3118885 -:104E0000F469BAE7BDE8F087090100F160430122C7 -:104E100003F56143C9B283F8001300F01F039A4001 -:104E200043099B0003F1604303F56143C3F880210C -:104E30001A607047F8B51546826804460B46AA42C8 -:104E400000D28568A1692669761AB5420BD2184648 -:104E50002A46FCF725FFA3692B44A3612846A368D3 -:104E60005B1BA360F8BD0CD9AF1B18463246FCF79C -:104E700017FF3A46E1683044FCF712FFE3683B4411 -:104E8000EBE718462A46FCF70BFFE368E5E700006E -:104E900083689342F7B50446154600D28568D4E985 -:104EA0000460361AB5420BD22A46FCF7F9FE636954 -:104EB0002B4463612846A3685B1BA36003B0F0BD6D -:104EC0000DD93246AF1B0191FCF7EAFE01993A4633 -:104ED000E0683144FCF7E4FEE3683B44E9E72A4636 -:104EE000FCF7DEFEE368E4E710B50A440024C36182 -:104EF000029B8460C16002610362C0E90000C0E9F6 -:104F0000051110BD08B5D0E90532934201D1826880 -:104F100082B98268013282605A1C42611970002194 -:104F2000D0E904329A4224BFC368436101F0C2FA57 -:104F3000002008BD4FF0FF30FBE7000070B52023D4 -:104F400004460E4683F31188A568A5B1A368A2693B -:104F5000013BA360531CA36115782269934224BFCF -:104F6000E368A361E3690BB120469847002383F30C -:104F70001188284607E03146204601F08BFA0028C8 -:104F8000E2DA85F3118870BD2DE9F74F04460E462D -:104F900017469846D0F81C904FF0200A8AF31188E3 -:104FA0004FF0000B154665B12A4631462046FFF703 -:104FB00041FF034660B94146204601F06BFA0028E4 -:104FC000F1D0002383F31188781B03B0BDE8F08F84 -:104FD000B9F1000F03D001902046C847019B8BF325 -:104FE0001188ED1A1E448AF31188DCE7C160C361A1 -:104FF000009B82600362C0E905111144C0E9000012 -:1050000001617047F8B504460D461646202383F328 -:105010001188A768A7B1A368013BA36063695A1C04 -:1050200062611D70D4E904329A4224BFE36863616F -:10503000E3690BB120469847002080F3118807E010 -:105040003146204601F026FA0028E2DA87F311887B -:10505000F8BD0000D0E9052310B59A4201D182685D -:105060007AB982680021013282605A1C82611C7800 -:1050700003699A4224BFC368836101F01BFA20468A -:1050800010BD4FF0FF30FBE72DE9F74F04460E4609 -:1050900017469846D0F81C904FF0200A8AF31188E2 -:1050A0004FF0000B154665B12A4631462046FFF702 -:1050B000EFFE034660B94146204601F0EBF90028B7 -:1050C000F1D0002383F31188781B03B0BDE8F08F83 -:1050D000B9F1000F03D001902046C847019B8BF324 -:1050E0001188ED1A1E448AF31188DCE70379052B39 -:1050F00005BF836A002001204B6004BF4FF400739A -:105100000B60704770B55D1E866A04460D44B5425B -:1051100005D9436B43F080034363012070BD06252E -:105120000571FFF78FFC05232371F7E770B55D1E4E -:10513000866A04460D44B54205D9436B43F08003AB -:105140004363012070BD07250571FFF7A7FC052308 -:105150002371F7E738B505790446052D05D10823F5 -:105160000371FFF7C7FC257138BD0120FCE7000083 -:105170002DE9F041032384B0044602AF0371FFF729 -:1051800073FA002220461146FFF7B0FA4FF4D572A9 -:105190003B1D08212046FFF7CDFA0246B8B901238E -:1051A00023637B68C3F30323012B09D13B1D372104 -:1051B0002046FFF7BFFA18B9AB4B7A681340ABB182 -:1051C00020460125FFF77AFA0223237140E13B1DB7 -:1051D000002237212046FFF7ADFA28B9A24A7B68A2 -:1051E0001A40002A00F0A98002232363236B03F0F6 -:1051F0000F03022B40F0AB8064259C4E42F21070EE -:1052000001F024F93B1D324601212046FFF77AFACE -:105210000028D5D17B68002B80F295805A0003D5F9 -:10522000236B43F010032363002204F108030221DF -:105230002046FFF72FFB02460028C1D104F13803B6 -:1052400003212046FFF776FA0028B9D104F11805AA -:10525000A26B092120462B46FFF71CFB0028AFD18B -:105260003B46A26B07212046FFF764FA064600285A -:10527000A6D1236B03F00F03022B40F093807E2214 -:105280007F21284603F0E8FA012840F28B8004F1E0 -:1052900048084FF47A7001F0D9F808234FF40072EF -:1052A000414620460096FFF713FB002888D1404670 -:1052B00003F020FB236BA06203F00F03022B77D1D6 -:1052C0003B1D6B4A06212046FFF734FA00286DD1BA -:1052D00065497B681940B1FA81F149092046FFF719 -:1052E000D7F93B464FF4007210212046FFF722FA0F -:1052F000054600287FF464AF5B4E3B6833427FF481 -:105300005FAF236B13F00E0F03F00F027BD0022A66 -:105310007FF456AFE36A1979012900F09E800229D3 -:1053200000F09E80002900F09180DFF85481204633 -:10533000FFF7CAF93B1D42467DE011462046226335 -:10534000FFF7D4F952E7013D7FF458AF38E7494DF4 -:105350006426494ADFF81081012B18BF15463B1D12 -:10536000002237212046FFF7E5F900287FF428AF17 -:105370007B6813EA080F7FF423AF3B1D2A462921DF -:105380002046FFF7BFF900287FF41AAF7B68002B97 -:10539000FFF644AF013E3FF413AF42F2107001F04C -:1053A00055F8DCE7284603F079FA83E7002195E712 -:1053B000E84690B07E227F21284602AE03F04CFAE8 -:1053C00010B90021C54689E7002340223146204616 -:1053D00000930623FFF77CFA0028F2D1B3895BBA69 -:1053E0009B07EED5254B40223146204600930623ED -:1053F000FFF76EFA0028E4D1317C01F00F010F397C -:1054000018BF0121DEE7E36A1979F9B101297FF4B8 -:10541000D7AE2046FFF758F93B1DA26B3721204637 -:10542000FFF788F900287FF4CBAE7B6833427FF426 -:10543000C7AE3B1D022206212046FFF77BF900285C -:105440007FF4BEAE7B6833427FF4BAAE052323718E -:1054500028460837BD46BDE8F081DFF8288066E7BA -:10546000DFF8248063E700BF08E0FFFD0080FFC095 -:105470000001B9030080FF5000001080F1FFFF80A1 -:105480000000B7030001B7030002B70337B50446B5 -:105490000C4D01ABA26B0D212046FFF74BF978B9FB -:1054A000019B2B420BD1C3F34323042B08D0053BB4 -:1054B000022B04D84FF47A7000F0C8FFE9E701200E -:1054C00003B030BD08E0FFFD70B52023054683F32F -:1054D000118803790024022B03D184F3118820461C -:1054E00070BD0423037184F311880226FFF7CEFFF9 -:1054F00004462846FFF7E2F82E71F0E7FFF74EB8B2 -:10550000044B03600123037100234363C0E90A33A2 -:10551000704700BF1491000810B52023044683F3A0 -:105520001188C162FFF756F802232371002383F329 -:10553000118810BD10B52023044683F31188FFF7AE -:1055400071F800230122E362227183F3118810BDF8 -:10555000026843681143016003B1184770470000B7 -:105560001430FFF711BD00004FF0FF331430FFF788 -:105570000BBD00003830FFF787BD00004FF0FF3350 -:105580003830FFF781BD00001430FFF7D7BC0000B2 -:105590004FF0FF311430FFF7D1BC00003830FFF777 -:1055A00031BD00004FF0FF323830FFF72BBD000057 -:1055B00000207047FFF7C0BA044B0360002343602C -:1055C000C0E9023301230374704700BF389100081B -:1055D00010B52023044683F31188FFF71DFB022337 -:1055E0002374002383F3118810BD000038B5C3690C -:1055F00004460D461BB904210844FFF7A9FF2946BC -:1056000004F11400FFF77EFC002806DA201D4FF499 -:105610008061BDE83840FFF79BBF38BD0268436832 -:105620001143016003B118477047000013B5406B88 -:1056300000F58054D4F8A4381A681178042914D1DC -:10564000017C022911D11979012312898B4013425F -:105650000BD101A94C3003F02DF8D4F8A448024630 -:10566000019B2179206800F0DFF902B010BD000035 -:10567000143002F0AFBF00004FF0FF33143002F0DF -:10568000A9BF00004C3003F081B800004FF0FF3399 -:105690004C3003F07BB80000143002F07DBF0000F6 -:1056A0004FF0FF31143002F077BF00004C3003F0B0 -:1056B0004DB800004FF0FF324C3003F047B8000007 -:1056C0000020704710B500F58054D4F8A4381A684B -:1056D0001178042917D1017C022914D159790123A9 -:1056E00052898B4013420ED1143002F00FFF024654 -:1056F00048B1D4F8A4484FF4407361792068BDE8FC -:10570000104000F07FB910BD406BFFF7DBBF000019 -:10571000704700007FB5124B012504260446036044 -:105720000023057400F1840243602946C0E9023376 -:105730000C4B0290143001934FF44073009602F02A -:10574000C1FE094B04F69442294604F14C00029430 -:10575000CDE900634FF4407302F088FF04B070BDE0 -:1057600060910008095700082D5600080A68202398 -:1057700083F311880B790B3342F823004B791333F1 -:1057800042F823008B7913B10B3342F8230000F564 -:105790008053C3F8A41802230374002383F31188F1 -:1057A0007047000038B5037F044613B190F85430B9 -:1057B000ABB90125201D0221FFF730FF04F11400D1 -:1057C0006FF00101257700F081FE04F14C0084F8B0 -:1057D00054506FF00101BDE8384000F077BE38BD8D -:1057E00010B5012104460430FFF718FF002323778A -:1057F00084F8543010BD000038B50446002514303C -:1058000002F078FE04F14C00257702F047FF201DDE -:1058100084F854500121FFF701FF2046BDE83840CD -:10582000FFF750BF90F8803003F06003202B06D1C3 -:1058300090F881200023212A03D81F2A06D80020AF -:105840007047222AFBD1C0E91D3303E0034A4267B7 -:1058500007228267C3670120704700BF44220020EF -:1058600037B500F58055D5F8A4381A6811780429A1 -:105870001AD1017C022917D11979012312898B4091 -:10588000134211D100F14C04204602F0C7FF58B179 -:1058900001A9204602F00EFFD5F8A4480246019B5C -:1058A0002179206800F0C0F803B030BD01F10B038E -:1058B000F0B550F8236085B004460D46FEB12023B4 -:1058C00083F3118804EB8507301D0821FFF7A6FE3E -:1058D000FB6806F14C005B691B681BB1019002F08C -:1058E000F7FE019803A902F0E5FE024648B1039BCA -:1058F0002946204600F098F8002383F3118805B06C -:10590000F0BDFB685A691268002AF5D01B8A013B7A -:105910001340F1D104F18002EAE70000133138B5F9 -:1059200050F82140ECB1202383F3118804F5805313 -:10593000D3F8A4281368527903EB8203DB689B69D0 -:105940005D6845B104216018FFF768FE294604F13F -:10595000140002F0E5FD2046FFF7B4FE002383F3B8 -:10596000118838BD7047000001F046BE0123402277 -:10597000002110B5044600F8303BFCF7B7F90023CE -:10598000C4E9013310BD000010B52023044683F3A1 -:1059900011882422416000210C30FCF7A7F9204631 -:1059A00001F04CFE02232370002383F3118810BD05 -:1059B00070B500EB8103054650690E461446DA6067 -:1059C00018B110220021FCF791F9A06918B110223A -:1059D0000021FCF78BF931462846BDE8704001F004 -:1059E0003FBF000083682022002103F0011310B59F -:1059F000044683601030FCF779F92046BDE810407A -:105A000001F0BABFF0B4012500EB810447898D4055 -:105A1000E4683D43A469458123600023A26063607C -:105A2000F0BC01F0D7BF0000F0B4012500EB810409 -:105A300007898D40E4683D43646905812360002344 -:105A4000A2606360F0BC02F04DB8000070B50223A4 -:105A500000250446242203702946C0F888500C30E3 -:105A600040F8045CFCF742F9204684F8705001F0DD -:105A70008BFE63681B6823B129462046BDE8704051 -:105A8000184770BD037880F88C3005230370436895 -:105A90001B6810B504460BB1042198470023A3608E -:105AA00010BD000090F88C20436802701B680BB199 -:105AB000052118477047000070B590F87030044613 -:105AC00013B1002380F8703004F18002204601F009 -:105AD00077FF63689B68B3B994F8803013F0600572 -:105AE00035D00021204602F021FA0021204602F0A4 -:105AF00011FA63681B6813B10621204698470623F4 -:105B000084F8703070BD204698470028E4D0B4F87F -:105B10008630A26F9A4288BFA36794F98030A56F40 -:105B2000002B4FF0200380F20381002D00F0F28063 -:105B3000092284F8702083F3118800212046D4E9DB -:105B40001D23FFF771FF002383F31188DAE794F830 -:105B5000812003F07F0343EA022340F202329342A2 -:105B600000F0C58021D8B3F5807F48D00DD8012B37 -:105B70003FD0022B00F09380002BB2D104F18802B9 -:105B800062670222A267E367C1E7B3F5817F00F095 -:105B90009B80B3F5407FA4D194F88230012BA0D133 -:105BA000B4F8883043F0020332E0B3F5006F4DD013 -:105BB00017D8B3F5A06F31D0A3F5C063012B90D8EF -:105BC0006368204694F882205E6894F88310B4F8E5 -:105BD0008430B047002884D0436863670368A367B4 -:105BE0001AE0B3F5106F36D040F6024293427FF4CC -:105BF00078AF5C4B63670223A3670023C3E794F885 -:105C00008230012B7FF46DAFB4F8883023F00203AB -:105C1000A4F88830C4E91D55E56778E7B4F880300A -:105C2000B3F5A06F0ED194F88230204684F88A3004 -:105C300001F008FE63681B6813B1012120469847F4 -:105C4000032323700023C4E91D339CE704F18B0375 -:105C500063670123C3E72378042B10D1202383F348 -:105C600011882046FFF7BEFE85F311880321636883 -:105C700084F88B5021701B680BB12046984794F82C -:105C80008230002BDED084F88B30042323706368CD -:105C90001B68002BD6D0022120469847D2E794F803 -:105CA000843020461D0603F00F010AD501F07AFE6C -:105CB000012804D002287FF414AF2B4B9AE72B4B1A -:105CC00098E701F061FEF3E794F88230002B7FF44F -:105CD00008AF94F8843013F00F01B3D01A062046B1 -:105CE00002D502F03BF9ADE702F02CF9AAE794F8EF -:105CF0008230002B7FF4F5AE94F8843013F00F015E -:105D0000A0D01B06204602D502F010F99AE702F057 -:105D100001F997E7142284F8702083F311882B4649 -:105D20002A4629462046FFF76DFE85F31188E9E6ED -:105D30005DB1152284F8702083F31188002120467C -:105D4000D4E91D23FFF75EFEFDE60B2284F87020E8 -:105D500083F311882B462A4629462046FFF764FE26 -:105D6000E3E700BF90910008889100088C9100083B -:105D700038B590F870300446002B3ED0063BDAB2BE -:105D80000F2A34D80F2B32D8DFE803F0373131082F -:105D9000223231313131313131313737856FB0F81D -:105DA00086309D4214D2C3681B8AB5FBF3F203FB15 -:105DB00012556DB9202383F311882B462A462946B4 -:105DC000FFF732FE85F311880A2384F870300EE065 -:105DD000142384F87030202383F311880023204695 -:105DE0001A461946FFF70EFE002383F3118838BDCB -:105DF000C36F03B198470023E7E70021204602F074 -:105E000095F80021204602F085F863681B6813B1FD -:105E10000621204698470623D7E7000010B590F8E2 -:105E200070300446142B29D017D8062B05D001D882 -:105E30001BB110BD093B022BFBD80021204602F00C -:105E400075F80021204602F065F863681B6813B1FD -:105E5000062120469847062319E0152BE9D10B238C -:105E600080F87030202383F3118800231A461946E6 -:105E7000FFF7DAFD002383F31188DAE7C3689B6933 -:105E80005B68002BD5D1C36F03B19847002384F81A -:105E90007030CEE70448054B03600023C0E90133AE -:105EA0000C3000F0DFB800BF384800208D890008B2 -:105EB000CB1D083A23F00703591A521A10B4D2081E -:105EC0000024C0E9004384600C301C605A605DF817 -:105ED000044B00F0C7B800002DE9F74F364FCD1D39 -:105EE0008846002818BF0746082A4FEAD50538BF5C -:105EF000082207F10C003C1D9146019000F0F2F8D9 -:105F0000019809F10701C9F1000E2246246864B91D -:105F100000F0F2F83B68CBB308224946E800984706 -:105F2000044698B340E9027830E004EB010CD4F861 -:105F300004A00CEA0E0C0AF10106ACF1080304EB14 -:105F4000C6069E42E1D9A6EB0C0CB5EBEC0F4FEA6E -:105F5000EC0BDAD89C421DD204F10802AB45A3EB4E -:105F600002024FEAE202626009D9691CED4303EBC9 -:105F7000C1025D445560256843F8315022601C46DB -:105F8000C3F8048044F8087B00F0B6F8204603B05C -:105F9000BDE8F08FAA45216802D111602346EEE7E3 -:105FA000013504EBC50344F8351003F10801761AF6 -:105FB000F6105E601360F1E73848002073B50446C0 -:105FC000A0F1080550F8080C54F8043C061D0C30EC -:105FD00007330190DB0844F8043C00F083F83346B3 -:105FE0000198B3421A6801D09D4228D90AB195425E -:105FF00025D244F8082C54F8042C1D60013254F8C2 -:10600000081C05EBC206B14206D14E68324444F882 -:10601000042C0A6844F8082C5E68711C03EBC1016B -:106020008D4207D154F8042C013232445A6054F89E -:10603000082C1A6002B0BDE8704000F05DB813464D -:10604000CFE700000B4610B51B68994203D09C684F -:1060500082689442F8D25A680360426010605860C7 -:1060600010BD00000023C0E9000083600361704799 -:1060700038B504461A4B80689D6948B3A84212D1CE -:1060800023690133236138BD836090F820307BB1F0 -:10609000062B13D1416AD0E9003213605A60FFF732 -:1060A000D1FF436A9868AB6882689A42ECD305E0F6 -:1060B000D0E9003213605A6000F05AF828462146B1 -:1060C000FFF7C0FF6C620620BDE8384000F092B8D0 -:1060D0002369A56001332361EB6AE360EC62D2E7D8 -:1060E0005848002008B5202383F31188FFF7C0FF2C -:1060F000002383F3118808BD174B10B5996920233D -:1061000083F311880269013A0261B2B90468C36875 -:106110008442CB621ED00A6B9BB901238A60036163 -:1061200003681A6802605060DA6A8360C260D862ED -:10613000184600F01DF800F0C9F8002383F3118819 -:1061400010BD1C68A34203D0A468A24238BF2246F7 -:10615000DB68E1E7A260F0E758480020034B00222B -:10616000C3E900339A60C3E90433704758480020FC -:106170000023826880F82030054B1B6899689142A3 -:10618000FBD25A680360426010605860704700BFDD -:106190005848002008B5202383F3118890F8203058 -:1061A000032B05D0042B0DD02BB983F3118808BD28 -:1061B000436A00221A604FF0FF334362FFF7D8FFB3 -:1061C0000023F2E7D0E9003213605A60F3E70000E1 -:1061D0000023826880F82030054B1B689968914243 -:1061E000FBD85A680360426010605860704700BF77 -:1061F00058480020064B996981F820001868026809 -:1062000053601A609861012380F82030FAF764BA6D -:10621000584800204B1C30B5044687B00A4D10D0BA -:10622000AB6901A8094A00F06DF92046FFF7E2FFCB -:10623000049B13B101A800F0A1F9AB69586A07B03B -:1062400030BDFFF7D7FFF8E75848002095610008F8 -:1062500038B50C4D04464162AB6981689A68914239 -:1062600003D8BDE83840FFF783BF1846FFF7B0FFFB -:1062700001230146AC61204684F82030BDE8384057 -:10628000FAF72ABA58480020044B1A689B699068AC -:106290009B68984294BF0020012070475848002016 -:1062A00010B5094C2368A0691A6854602260012265 -:1062B000A36183F82020FFF78BFF0146A069BDE8AA -:1062C0001040FAF709BA00BF5848002008B5FFF798 -:1062D000DBFF18B1BDE80840FFF7E2BF08BD0000D2 -:1062E000FFF7DEBFFEE7000010B50F4CFFF736FFEB -:1062F00000F0FAF802F02CFBFFF7CCFD80220B49EE -:10630000204600F03DF8012344F8180C002480F8E2 -:106310002030C46101F04EF884F3118862B604485D -:10632000BDE8104000F05CB888480020A494000844 -:106330009C91000800F05CB9EFF3118020B9EFF3F5 -:106340000583202282F311887047000010B530B910 -:10635000EFF30584C4F3080414B180F3118810BD71 -:10636000FFF7B4FF84F31188F9E70000034A51688E -:1063700053685B1A9842FBD8704700BF001000E0DA -:106380008260026300228161C262022202840122D1 -:1063900080F82220044A516902614161086150611C -:1063A00000F128028262704758480020D0E901239A -:1063B000016843F81C2CA3F19C0243F82C2C0269C1 -:1063C00043F85C2C426943F8582C044A43F83C2CAF -:1063D000C268A3F13800FFF7D3BF00BFF106000881 -:1063E00010B5202383F31188FFF7E0FF0021044656 -:1063F000FFF72EFF002383F31188204610BD000015 -:1064000038B50E4B9C6904F128056062A06AA84269 -:106410000FD194F822303BB994F821309B0702BF8A -:10642000D4E9043213615A610F20BDE83840FFF708 -:10643000E1BE0368A362FFF79BFEE7E75848002030 -:10644000202383F31188FFF7DBBF000008B5014666 -:10645000202383F311880820FFF7DCFE002383F359 -:10646000118808BD054B9B6921B103605862032068 -:10647000FFF7D0BE4FF0FF30704700BF58480020F4 -:1064800003682BB10022026018465962FFF770BE04 -:106490007047000049B1064B42689B6918605A601A -:1064A000136043600420FFF7B5BE4FF0FF30704724 -:1064B000584800200368984206D01A68026050606D -:1064C00018465962FFF754BE7047000038B50446BD -:1064D0000D462068844200D138BD036823605C60AB -:1064E0004562FFF745FEF4E7054B4FF0FF3103F13E -:1064F0001C02C3E907220022C3E90912704700BF4A -:106500005848002070B51C4E05460C46C0E90323D0 -:1065100002F018FA334653F81C2F9A420DD1B0629C -:106520000A2C2CBF00190A302A60C5E90124C6E9EB -:106530000755BDE8704002F0EFB9B16A431AE3189D -:1065400038BF1C469368A34202D9081902F0F4F937 -:10655000F3699A6894420CD85A68AC602B606A6000 -:1065600015609A685D60121B9A604FF0FF3373628A -:1065700070BDA41A1B68ECE75848002038B51B4CC6 -:10658000E36998420DD08168D0E9003213605A6007 -:106590000022C2609A680A449A604FF0FF33636237 -:1065A00038BD03682246002142F81C3F93425A60DE -:1065B000C16003D1BDE8384002F0B8B99A6881687B -:1065C000A56A0A449A6002F0BDF9E369411B9A6822 -:1065D0008A42E5D9AB181D1AA06A092D98BF01F1AE -:1065E0000A02BDE83840104402F0A6B9584800201D -:1065F0002DE9F041184C002704F11C06E56902F072 -:10660000A1F9A36AAA68C11A8A4215D81344D5F819 -:106610000C80A362D5E9003213605A60E369EF6031 -:10662000B34201D102F082F987F311882869C0478B -:10663000202383F31188E1E7E169B14209D01344D3 -:106640001B1ABDE8F0410A2B2CBFC0180A3002F01B -:1066500073B9BDE8F08100BF5848002010B558B9A3 -:1066600006480479053C18BF012400F035F908B14B -:1066700044F00404204610BD0124FBE7A0360020AE -:10668000FFF7ECBF2DE9F8430F461646994604463E -:10669000B0B9DFF8348098F80450052D05D00324F4 -:1066A0000BE0013D15F0FF050CD04B463A46314654 -:1066B0004046FEF727FD0028F3D12046BDE8F883C9 -:1066C0000424FAE70124F8E7A03600202DE9F84376 -:1066D0000F46164699460446B0B9DFF8348098F85C -:1066E0000450052D05D003240BE0013D15F0FF05F6 -:1066F0000CD04B463A4631464046FEF717FD00287F -:10670000F3D12046BDE8F8830424FAE70124F8E732 -:10671000A036002070B9012905D0032907D000292F -:1067200018BF04207047044B9B6A136070474FF4F6 -:106730008073FAE704207047A036002000F0F2BB17 -:1067400000F02CBC00207047FEE7000070470000FE -:106750004FF0FF30704700004B6843608B688360E8 -:10676000CB68C3600B6943614B6903628B69436209 -:106770000B6803607047000008B53C4B40F2FF71A6 -:106780003B48D3F888200A43C3F88820D3F88820F0 -:1067900022F4FF6222F00702C3F88820D3F8882091 -:1067A000D3F8E0200A43C3F8E020D3F808210A43D5 -:1067B000C3F808212F4AD3F808311146FFF7CCFF60 -:1067C00000F5806002F11C01FFF7C6FF00F5806054 -:1067D00002F13801FFF7C0FF00F5806002F15401BB -:1067E000FFF7BAFF00F5806002F17001FFF7B4FF18 -:1067F00000F5806002F18C01FFF7AEFF00F58060CC -:1068000002F1A801FFF7A8FF00F5806002F1C401C2 -:10681000FFF7A2FF00F5806002F1E001FFF79CFFA7 -:1068200000F5806002F1FC01FFF796FF02F58C7124 -:1068300000F58060FFF790FF01F014FC0E4BD3F8D9 -:10684000902242F00102C3F89022D3F8942242F041 -:106850000102C3F894220522C3F898204FF0605239 -:10686000C3F89C20054AC3F8A02008BD0044025884 -:1068700000000258B491000800ED00E01F0008037A -:1068800008B501F00BFEFFF72FFD104BD3F8DC200D -:1068900042F04002C3F8DC20D3F8042122F0400289 -:1068A000C3F80421D3F80431094B1A6842F00802F6 -:1068B0001A601A6842F004021A6000F049FD00F004 -:1068C00035FBBDE8084000F0B5B800BF00440258F1 -:1068D00000180248012070470020704770470000F0 -:1068E00002290CD0032904D00129074818BF002031 -:1068F0007047032A05D8054800EBC20070470448DA -:1069000070470020704700BFB89300085422002051 -:106910006C93000870B59AB005460846144601A964 -:1069200000F0C2F801A8FBF7D9F9431C0022C6B257 -:106930005B001046C5E9003423700323023404F8D9 -:10694000013C01ABD1B202348E4201D81AB070BD05 -:1069500013F8011B013204F8010C04F8021CF1E7E2 -:1069600008B5202383F311880348FEF779FF00233D -:1069700083F3118808BD00BF504A002090F8803092 -:1069800003F01F02012A07D190F881200B2A03D1BE -:106990000023C0E91D3315E003F06003202B08D16C -:1069A000B0F884302BB990F88120212A03D81F2A0F -:1069B00004D8FEF737BF222AEBD0FAE7034A426732 -:1069C00007228267C3670120704700BF4B22002067 -:1069D00007B5052917D8DFE801F0191603191920A2 -:1069E000202383F31188104A01210190FEF7E0FF74 -:1069F000019802210D4AFEF7DBFF0D48FEF7FCFE71 -:106A0000002383F3118803B05DF804FB202383F394 -:106A100011880748FEF7C6FEF2E7202383F31188AA -:106A20000348FEF7DDFEEBE70C9300083093000807 -:106A3000504A002038B50C4D0C4C2A460C4904F144 -:106A40000800FFF767FF05F1CA0204F110000949C9 -:106A5000FFF760FF05F5CA7204F118000649BDE8AA -:106A60003840FFF757BF00BF2863002054220020A2 -:106A7000E8920008F29200080193000870B50446FD -:106A800008460D46FBF72AF9C6B2204601340378C2 -:106A90000BB9184670BD32462946FBF70BF90028A2 -:106AA000F3D10120F6E700002DE9F04705460C463A -:106AB000FBF714F92B49C6B22846FFF7DFFF08B1F0 -:106AC0000E36F6B228492846FFF7D8FF08B110362F -:106AD000F6B2632E0BD8DFF88C80DFF88C90234F52 -:106AE000DFF894A02E7846B92670BDE8F0872946D5 -:106AF0002046BDE8F04702F033B8252E2ED10722FC -:106B000041462846FBF7D6F870B9194B224603F1E7 -:106B1000140153F8040B8B4242F8040BF9D11B7893 -:106B2000073515341370DDE7082249462846FBF780 -:106B3000C1F898B9A21C0F4B197802320909C95D36 -:106B400002F8041C13F8011B01F00F015345C95D45 -:106B500002F8031CF0D118340835C3E7013504F8F6 -:106B6000016BBFE7D893000801930008F693000873 -:106B7000E093000800E8F11F0CE8F11FBFF34F8F0E -:106B8000044B1A695107FCD1D3F810215207F8D1F0 -:106B9000704700BF0020005208B50D4B1B78ABB901 -:106BA000FFF7ECFF0B4BDA68D10704D50A4A5A60AD -:106BB00002F188325A60D3F80C21D20706D5064A72 -:106BC000C3F8042102F18832C3F8042108BD00BFD4 -:106BD00086650020002000522301674508B5114B4F -:106BE0001B78F3B9104B1A69510703D5DA6842F0E4 -:106BF0004002DA60D3F81021520705D5D3F80C21F2 -:106C000042F04002C3F80C21FFF7B8FF064BDA68E8 -:106C100042F00102DA60D3F80C2142F00102C3F81D -:106C20000C2108BD86650020002000520F289ABF65 -:106C300000F5806040040020704700004FF40030F1 -:106C400070470000102070470F2808B50BD8FFF7D9 -:106C5000EDFF00F500330268013204D104308342B5 -:106C6000F9D1012008BD0020FCE700000F2870B515 -:106C7000054645D8FFF760FB224CFFF77FFF06462D -:106C8000FFF78AFF4FF0FF33072D6361C4F814311B -:106C900020D82361FFF772FF2B0243F02403E36047 -:106CA000E36843F08003E36023695A07FCD4284675 -:106CB000FFF764FF4FF40031FFF7B8FF00F0A2FACE -:106CC0003046FFF78BFFFFF741FB2846BDE87040D9 -:106CD000FFF7BABFC4F81031FFF750FFA5F1080362 -:106CE0001B0243F02403C4F80C31D4F80C3143F0F8 -:106CF0008003C4F80C31D4F810315B07FBD4D6E71D -:106D0000002070BD002000522DE9F84F40EA020338 -:106D100005460C461746D80602D00020BDE8F88F7D -:106D200027F01F07DFF8D4B0FFF736FF2744BC4237 -:106D300003D10120FFF752FFF0E720222946204629 -:106D400001F0A0FE10B920352034F0E72B4605F104 -:106D500020021E68711CE0D104339A42F9D1FFF77A -:106D6000EBFA05F17843234AB3F5801F224B28BF85 -:106D70009A4603F1040338BF9046A2F1080228BFE7 -:106D80009846A3F108033ABF9146DA469946FFF7C1 -:106D9000F5FEC8F80060A5EB040CD9F8002004F15A -:106DA0001C0142F00202C9F80020221FDAF800603C -:106DB00016F00506FAD152F8043F8A424CF8023028 -:106DC000F4D1BFF34F8FFFF7D9FE4FF0FF32C8F871 -:106DD0000020D9F8002022F00202C9F80020FFF7B5 -:106DE000B5FA20222146284601F04CFE0028AAD000 -:106DF00030469FE71420005210210052102000520C -:106E000010B5084C237828B11BB9FFF7C5FE012344 -:106E1000237010BD002BFCD02070BDE81040FFF7A0 -:106E2000DDBE00BF866500202DE9F74F0E46054602 -:106E3000002863D011F0050762D139B9082229462C -:106E40003046FFF749F80446002847D108224FF0A2 -:106E50000109DFF8C08006F00403DFF8BCA006EAF1 -:106E6000090BBBF1000F27D0D8F81410C80723D4A2 -:106E700009F1010908F10C08B9F1060FF1D18FB938 -:106E8000224E2946F0190092FFF726F8044628BB47 -:106E90002037009AA02FF4D12946FFF71DF80446A9 -:106EA000E0B9009A29461A48FFF716F8044600BBD5 -:106EB000204603B0BDE8F08FA3B1D8F8141011F04C -:106EC000040FD5D029460AEB4910CDE90023FFF77E -:106ED00003F80446DDE900230028C9D02A46002132 -:106EE000204608E0B107EDD5D8F8141011F0020FD4 -:106EF000E7E72A460021FAF7F9FED9E70446D7E783 -:106F00001F35202225F01F05A1E700BFC86500201E -:106F10008865002008940008A86500200021FFF77C -:106F200083BF00000121FFF77FBF000070B5144D43 -:106F30000124144E40F2FF3200210120FAF7D6FE60 -:106F400006EB441001342A6955F80C1FFEF7B0FF18 -:106F5000062CF5D137254FF4C0542046FFF7E2FF49 -:106F6000014628B122460848BDE87040FEF7A0BFA0 -:106F7000C4EBC404013D4FEAD404EED170BD00BFA0 -:106F800008940008A8650020886500200421FFF708 -:106F90004BBF00004843FFF7C1BF000008B1FFF737 -:106FA0000DB8704770B5104E82B0FFF7C5F90546B1 -:106FB00001F0C8FC326803469042336037BF0B4A89 -:106FC0000A495168146836BF0131D1E90041516066 -:106FD0000419284641F100010191FFF7B7F9204655 -:106FE000019902B070BD00BF686600207066002085 -:106FF00008B5FFF7D7FF034AD2E90032C01842EBC9 -:10700000010108BD78660020434BD3E900232DE938 -:10701000F34113437CD0FFF7EBFF404A00230027E6 -:10702000F9F73EF906460D463D4A0023F9F738F9CF -:107030000023144630462946394AF9F731F94FF40E -:1070400061613C23ADF80170B4FBF1F5B4FBF3F6DC -:1070500001FB154103FB16464624B1FBF3F1314B0E -:10706000F6B28DF8004098423CD84FF0640C4FF4D3 -:10707000C87EA30704F26C7225D1B2FBFCF30CFBB3 -:10708000132313BBB2FBFEF30EFB1322B2FA82F3FF -:107090005B0903F26D18621C8045D2B217D90FB19B -:1070A0008DF800400022204C4FF00C0C17460CFBD2 -:1070B0000343D4B2013213F804C084450CD8A0EBCA -:1070C0000C000127F5E70023E3E70123E1E7A0EB4C -:1070D000080014460127CCE70FB18DF80140431C8E -:1070E0008DF802309DF80100431C9DF800005038D7 -:1070F000400640EA43509DF8023040EA034040EA2F -:10710000560040EAC52040EA411002B0BDE8F081D7 -:107110004FF40410F9E700BF7866002040420F00EA -:107120008051010090230B00509400080244074B4B -:10713000D2B210B5904200D110BD441C00B253F839 -:10714000200041F8040BE0B2F4E700BF50400058C3 -:107150000E4B30B51C6F240405D41C6F1C671C6FCC -:1071600044F400441C670A4C02442368D2B243F43E -:1071700080732360074B904200D130BD441C51F80E -:10718000045B00B243F82050E0B2F4E70044025838 -:10719000004802585040005807B5012201A90020BC -:1071A000FFF7C4FF019803B05DF804FB13B5044674 -:1071B000FFF7F2FFA04205D0012201A900200194AF -:1071C000FFF7C6FF02B010BD10B56424013C4FF4B8 -:1071D0007A70FFF73BF914F0FF04F7D1084B4FF03A -:1071E000807214249A6103F5805308229A61013C4D -:1071F0004FF47A70FFF72AF914F0FF04F7D110BDAD -:10720000000002580144BFF34F8F064B884204D35D -:10721000BFF34F8FBFF36F8F7047C3F85C0220300E -:10722000F4E700BF00ED00E00144BFF34F8F064BD1 -:10723000884204D3BFF34F8FBFF36F8F7047C3F8FB -:1072400070022030F4E700BF00ED00E070B50546A5 -:1072500016460C4601201021FFF79CFE286046735D -:107260003CB1204636B1FFF791FE2B68186000B1A3 -:107270009C6070BDFFF756FEF7E7000070B50E4644 -:107280001546044600B30B6843608368934210D2EE -:1072900013B10068FFF782FE637B28462BB1FFF72E -:1072A00075FE206020B9A06070BDFFF73BFEF8E7D7 -:1072B000A560206805F11F01306021F01F01FFF774 -:1072C000A1FF01202073EFE70120EDE710B5044690 -:1072D00040B10068884205D1606808B1FAF7E0FC67 -:1072E0000023237310BD000070B50E4615460446FA -:1072F00020B38368934210D213B10068FFF74EFEAB -:10730000637B28462BB1FFF741FE206020B9A060C7 -:1073100070BDFFF707FEF8E7A560316819B12A468E -:107320002068FAF7BDFC206805F11F01306021F0EC -:107330001F01FFF779FF01202073E9E70120E7E74C -:1073400020B103688B4204BF002303737047000021 -:10735000034B1A681AB9034AD2F8D0241A6070474E -:10736000806600200040025808B5FFF7F1FF024B8D -:107370001868C0F3806008BD80660020CAB201466C -:107380000120FFF7E5BE0000CAB201460120FFF769 -:10739000CDBE0000EFF30983054968334A6B22F044 -:1073A00001024A6383F30988002383F3118870473D -:1073B00000EF00E0202080F3118862B60D4B0E4AEA -:1073C000D96821F4E0610904090C0A430B49DA6029 -:1073D000D3F8FC2042F08072C3F8FC20084AC2F8BF -:1073E000B01F116841F0010111601022DA7783F8B3 -:1073F0002200704700ED00E00003FA0555CEACC551 -:10740000001000E0202310B583F311880E4B5B6859 -:1074100013F4006314D0F1EE103AEFF309844FF047 -:107420008073683CE361094BDB6B236684F3098856 -:10743000FEF72AFF10B1064BA36110BD054BFBE719 -:1074400083F31188F9E700BF00ED00E000EF00E0F2 -:10745000030700080607000870B5BFF34F8FBFF39E -:107460006F8F1A4A0021C2F85012BFF34F8FBFF33B -:107470006F8F536943F400335361BFF34F8FBFF3F2 -:107480006F8FC2F88410BFF34F8FD2F8803043F66D -:10749000E074C3F3C900C3F34E335B0103EA04068F -:1074A000014646EA81750139C2F86052F9D2203BA3 -:1074B00013F1200FF2D1BFF34F8F536943F48033A0 -:1074C0005361BFF34F8FBFF36F8F70BD00ED00E0CE -:1074D000FEE700000A4B0B480B4A90420BD30B4BC4 -:1074E000C11EDA1C121A22F003028B4238BF00229E -:1074F0000021FAF7FBBB53F8041B40F8041BECE730 -:10750000A09500086468002064680020646800207A -:107510007047000070B5D0E9244300224FF0FF35DA -:107520009E6804EB42135101D3F80009002805DAE4 -:10753000D3F8000940F08040C3F80009D3F8000BED -:10754000002805DAD3F8000B40F08040C3F8000BA8 -:10755000013263189642C3F80859C3F8085BE0D2B9 -:107560004FF00113C4F81C3870BD000000EB81031C -:10757000D3F80CC02DE9F043DCF814204E1CD0F8F1 -:107580009050D2F800E005EB063605EB4118506844 -:1075900070450AD30122D5F8343802FA01F123EA02 -:1075A0000101C5F83418BDE8F083AEEB0003BCF868 -:1075B0001040A34228BF2346D8F81849A4B2B3EB21 -:1075C000840FF0D89468A4F1040959F8047F376057 -:1075D000A4EB09071F44042FF7D81C44034494600C -:1075E0005360D4E7890141F02001016103699B06E2 -:1075F000FCD41220FEF7BABE10B50A4C2046FEF7A6 -:10760000B5F9094BC4F89030084BC4F89430084CD5 -:107610002046FEF7ABF9074BC4F89030064BC4F890 -:10762000943010BD84660020000008408C9400084F -:1076300020670020000004409894000870B503788B -:107640000546012B5DD1494BD0F89040984259D165 -:10765000474B0E216520D3F8D82042F00062C3F8D2 -:10766000D820D3F8002142F00062C3F80021D3F8FB -:107670000021D3F8802042F00062C3F88020D3F8C4 -:10768000802022F00062C3F88020D3F88030FDF71C -:10769000BBFB384BE360384BC4F800380023D5F807 -:1076A0009060C4F8003EC02323604FF40413A3632A -:1076B0003369002BFCDA01230C203361FEF756FE00 -:1076C0003369DB07FCD41220FEF750FE3369002B30 -:1076D000FCDA00262846A660FFF71CFF6B68C4F89A -:1076E0001068DB68C4F81468C4F81C68002B3AD131 -:1076F000224BA3614FF0FF336361A36843F00103A2 -:10770000A36070BD1E4B9842C8D1194B0E214D206D -:10771000D3F8D82042F00072C3F8D820D3F8002163 -:1077200042F00072C3F80021D3F80021D3F8802082 -:1077300042F00072C3F88020D3F8802022F000725B -:10774000C3F88020D3F88020D3F8D82022F08062BC -:10775000C3F8D820D3F8002122F08062C3F80021BA -:10776000D3F8003193E7074BC3E700BF84660020DE -:10777000004402584014004003002002003C30C086 -:1077800020670020083C30C0F8B5D0F8904005468E -:1077900000214FF000662046FFF724FFD5F8941033 -:1077A00000234FF001128F684FF0FF30C4F83438D7 -:1077B000C4F81C2804EB431201339F42C2F800694D -:1077C000C2F8006BC2F80809C2F8080BF2D20B68C5 -:1077D000D5F89020C5F898306362102313611669BC -:1077E00016F01006FBD11220FEF7C0FDD4F80038C9 -:1077F00023F4FE63C4F80038A36943F4402343F044 -:107800001003A3610923C4F81038C4F814380B4BD3 -:10781000EB604FF0C043C4F8103B094BC4F8003B89 -:10782000C4F81069C4F80039D5F8983003F1100293 -:1078300043F48013C5F89820A362F8BD689400084B -:1078400040800010D0F8902090F88A10D2F80038CC -:1078500023F4FE6343EA0113C2F8003870470000C6 -:107860002DE9F84300EB8103D0F890500C46804698 -:10787000DA680FFA81F94801166806F00306731EEC -:10788000022B05EB41134FF0000194BFB604384EB4 -:10789000C3F8101B4FF0010104F1100398BF06F16B -:1078A000805601FA03F3916998BF06F50046002956 -:1078B0003AD0578A04F15801374349016F50D5F83F -:1078C0001C180B430021C5F81C382B180127C3F8DE -:1078D0001019A7405369611E9BB3138A928B9B08B2 -:1078E000012A88BF5343D8F89820981842EA0343E6 -:1078F00001F140022146C8F89800284605EB8202B3 -:107900005360FFF76FFE08EB8900C3681B8A43EAE8 -:10791000845348341E4364012E51D5F81C381F434C -:10792000C5F81C78BDE8F88305EB4917D7F8001BAC -:1079300021F40041C7F8001BD5F81C1821EA030305 -:10794000C0E704F13F030B4A2846214605EB8303B9 -:107950005A60FFF747FE05EB4910D0F8003923F4D1 -:107960000043C0F80039D5F81C3823EA0707D7E7E9 -:107970000080001000040002D0F894201268C0F8C3 -:107980009820FFF7C7BD00005831D0F8903049016A -:107990005B5813F4004004D013F4001F0CBF022006 -:1079A000012070474831D0F8903049015B5813F4FA -:1079B000004004D013F4001F0CBF022001207047C8 -:1079C00000EB8101CB68196A0B6813604B68536048 -:1079D0007047000000EB810330B5DD68AA691368C9 -:1079E000D36019B9402B84BF402313606B8A14689D -:1079F000D0F890201C4402EB4110013C09B2B4FBCA -:107A0000F3F46343033323F0030343EAC44343F033 -:107A1000C043C0F8103B2B6803F00303012B0ED1C9 -:107A2000D2F8083802EB411013F4807FD0F8003B05 -:107A300014BF43F0805343F00053C0F8003B02EB07 -:107A40004112D2F8003B43F00443C2F8003B30BD82 -:107A50002DE9F041D0F8906005460C4606EB411345 -:107A6000D3F8087B3A07C3F8087B08D5D6F8143852 -:107A70001B0704D500EB8103DB685B689847FA07B6 -:107A80001FD5D6F81438DB071BD505EB8403D9685E -:107A9000CCB98B69488A5A68B2FBF0F600FB162213 -:107AA0008AB91868DA6890420DD2121AC3E9002424 -:107AB000202383F3118821462846FFF78BFF84F3A8 -:107AC0001188BDE8F081012303FA04F26B8923EAEF -:107AD00002036B81CB68002BF3D021462846BDE81A -:107AE000F041184700EB81034A0170B5DD68D0F81A -:107AF00090306C692668E66056BB1A444FF400204B -:107B0000C2F810092A6802F00302012A0AB20ED153 -:107B1000D3F8080803EB421410F4807FD4F800096E -:107B200014BF40F0805040F00050C4F8000903EB4F -:107B30004212D2F8000940F00440C2F800090122C4 -:107B4000D3F8340802FA01F10143C3F8341870BDC8 -:107B500019B9402E84BF4020206020681A442E8A24 -:107B60008419013CB4FBF6F440EAC44040F00050F4 -:107B7000C6E700002DE9F041D0F8906004460D46BC -:107B800006EB4113D3F80879C3F80879FB071CD535 -:107B9000D6F81038DA0718D500EB8103D3F80CC0FB -:107BA000DCF81430D3F800E0DA6896451BD2A2EB7B -:107BB0000E024FF000081A60C3F80480202383F3FC -:107BC0001188FFF78FFF88F311883B0618D5012332 -:107BD000D6F83428AB40134212D029462046BDE8DF -:107BE000F041FFF7C3BC012303FA01F2038923EA42 -:107BF00002030381DCF80830002BE6D09847E4E765 -:107C0000BDE8F0812DE9F84FD0F8905004466E6938 -:107C1000AB691E4016F480586E6103D0BDE8F84F82 -:107C2000FDF714BF002E12DAD5F8003E9F0705D0ED -:107C3000D5F8003E23F00303C5F8003ED5F804381C -:107C4000204623F00103C5F80438FDF72BFF30056B -:107C500005D52046FFF75EFC2046FDF713FFB10473 -:107C60000CD5D5F8083813F0060FEB6823F47053E1 -:107C70000CBF43F4105343F4A053EB60320704D518 -:107C80006368DB680BB120469847F30200F1BA80C5 -:107C9000B70226D5D4F8909000274FF0010A09EBDF -:107CA0004712D2F8003B03F44023B3F5802F11D1E3 -:107CB000D2F8003B002B0DDA62890AFA07F322EAB8 -:107CC0000303638104EB8703DB68DB6813B1394688 -:107CD000204698470137D4F89430FFB29B689F4202 -:107CE000DDD9F00619D5D4F89000026AC2F30A175C -:107CF00002F00F0302F4F012B2F5802F00F0CC80F6 -:107D0000B2F5402F09D104EB8303002200F5805027 -:107D1000DB681B6A974240F0B2803003D5F81858F0 -:107D200035D5E90303D500212046FFF791FEAA03CC -:107D300003D501212046FFF78BFE6B0303D50221FB -:107D40002046FFF785FE2F0303D503212046FFF7CA -:107D50007FFEE80203D504212046FFF779FEA90241 -:107D600003D505212046FFF773FE6A0203D50621DD -:107D70002046FFF76DFE2B0203D507212046FFF7B3 -:107D800067FEEF0103D508212046FFF761FE70036F -:107D900040F1A980E90703D500212046FFF7EAFE5C -:107DA000AA0703D501212046FFF7E4FE6B0703D5A0 -:107DB00002212046FFF7DEFE2F0703D503212046D0 -:107DC000FFF7D8FEEE0603D504212046FFF7D2FECA -:107DD000A80603D505212046FFF7CCFE690603D58A -:107DE00006212046FFF7C6FE2A0603D507212046B6 -:107DF000FFF7C0FEEB0576D520460821BDE8F84F19 -:107E0000FFF7B8BED4F8909000274FF0010AD4F8DD -:107E100094305FFA87FB9B689B453FF639AF09EBCF -:107E20004B13D3F8002902F44022B2F5802F24D15D -:107E3000D3F80029002A20DAD3F8002942F0904232 -:107E4000C3F80029D3F80029002AFBDB5946D4F8EF -:107E50009000FFF7C7FB22890AFA0BF322EA03031B -:107E6000238104EB8B03DB689B6813B159462046E2 -:107E7000984759462046FFF779FB0137C7E7910736 -:107E800001D1D0F80080072A02F101029CBF03F85B -:107E9000018B4FEA18283DE704EB830300F580507F -:107EA000DA68D2F818C0DCF80820DCE9001CA1EB85 -:107EB0000C0C00218F4208D1DB689B699A683A4418 -:107EC0009A605A683A445A6027E711F0030F01D1CB -:107ED000D0F800808C4501F1010184BF02F8018BCC -:107EE0004FEA1828E6E7BDE8F88F000008B5034818 -:107EF000FFF788FEBDE80840FFF784BA84660020DB -:107F000008B50348FFF77EFEBDE80840FFF77ABAE0 -:107F100020670020D0F8903003EB4111D1F8003BEE -:107F200043F40013C1F8003B70470000D0F89030D4 -:107F300003EB4111D1F8003943F40013C1F80039C3 -:107F400070470000D0F8903003EB4111D1F8003BAE -:107F500023F40013C1F8003B70470000D0F89030C4 -:107F600003EB4111D1F8003923F40013C1F80039B3 -:107F7000704700003A4B4FF0FF31D3F8802062F099 -:107F80000042C3F88020D3F8802002F00042C3F8FA -:107F90008020D3F88020D3F88420C3F88410D3F84D -:107FA00084200022C3F88420D3F88400D86F40F0E6 -:107FB000FF4040F4FF0040F43F5040F03F00D867DE -:107FC000D86F20F0FF4020F4FF0020F43F5020F055 -:107FD0003F00D867D86FD3F888006FEA40506FEA47 -:107FE0005050C3F88800D3F88800C0F30A00C3F8E3 -:107FF0008800D3F88800D3F89000C3F89010D3F825 -:108000009000C3F89020D3F89000D3F89400C3F800 -:108010009410D3F89400C3F89420D3F89400D3F8C4 -:108020009800C3F89810D3F89800C3F89820D3F8B4 -:108030009800D3F88C00C3F88C10D3F88C00C3F8E8 -:108040008C20D3F88C00D3F89C00C3F89C10D3F894 -:108050009C10C3F89C20D3F89C3000F0E7B900BF17 -:1080600000440258614B0122C3F80821604BD3F849 -:10807000F42042F00202C3F8F420D3F81C2142F0AD -:108080000202C3F81C210422D3F81C31594BDA60D8 -:108090005A689104FCD5584A1A6001229A60574ADE -:1080A000DA6000221A614FF440429A61514B9A699A -:1080B0009204FCD51A6842F480721A604C4B1A6F15 -:1080C00012F4407F04D04FF480321A6700221A67FE -:1080D0001A6842F001021A60454B1A685007FCD535 -:1080E00000221A611A6912F03802FBD101211960CD -:1080F0004FF0804159605A67414ADA62414A1A6139 -:108100001A6842F480321A60394B1A689103FCD520 -:108110001A6842F480521A601A689204FCD53A4AEE -:108120003A499A6200225A6319633949DA639963BA -:108130005A64384A1A64384ADA621A6842F0A85215 -:108140001A602B4B1A6802F02852B2F1285FF9D15D -:1081500048229A614FF48862DA6140221A622F4AFB -:10816000DA644FF080521A652D4A5A652D4A9A6595 -:1081700032232D4A1360136803F00F03022BFAD148 -:108180001B4B1A6942F003021A611A6902F03802A5 -:10819000182AFAD1D3F8DC2042F00052C3F8DC20D0 -:1081A000D3F8042142F00052C3F80421D3F804218B -:1081B000D3F8DC2042F08042C3F8DC20D3F804215D -:1081C00042F08042C3F80421D3F80421D3F8DC2024 -:1081D00042F00042C3F8DC20D3F8042142F0004210 -:1081E000C3F80421D3F80431704700BF0080005168 -:1081F000004402580048025800C000F0040000018A -:108200000000FF010088900832206000630209012D -:108210001D02040047040508FD0BFF01200000209B -:108220000010E00000010100002000524FF0B042B9 -:1082300008B5D2F8883003F00103C2F8883023B1C2 -:10824000044A13680BB150689847BDE80840FFF72F -:10825000D9B800BFDC6700204FF0B04208B5D2F8B3 -:10826000883003F00203C2F8883023B1044A9368CF -:108270000BB1D0689847BDE80840FFF7C3B800BF0E -:10828000DC6700204FF0B04208B5D2F8883003F028 -:108290000403C2F8883023B1044A13690BB1506952 -:1082A0009847BDE80840FFF7ADB800BFDC67002085 -:1082B0004FF0B04208B5D2F8883003F00803C2F896 -:1082C000883023B1044A93690BB1D0699847BDE85F -:1082D0000840FFF797B800BFDC6700204FF0B042BE -:1082E00008B5D2F8883003F01003C2F8883023B103 -:1082F000044A136A0BB1506A9847BDE80840FFF77B -:1083000081B800BFDC6700204FF0B04310B5D3F850 -:10831000884004F47872C3F88820A30604D5124A72 -:10832000936A0BB1D06A9847600604D50E4A136B66 -:108330000BB1506B9847210604D50B4A936B0BB1D8 -:10834000D06B9847E20504D5074A136C0BB1506C0B -:108350009847A30504D5044A936C0BB1D06C984799 -:10836000BDE81040FFF74EB8DC6700204FF0B04387 -:1083700010B5D3F8884004F47C42C3F88820620525 -:1083800004D5164A136D0BB1506D9847230504D5DB -:10839000124A936D0BB1D06D9847E00404D50F4A93 -:1083A000136E0BB1506E9847A10404D50B4A936E1F -:1083B0000BB1D06E9847620404D5084A136F0BB115 -:1083C000506F9847230404D5044A936F0BB1D06FC4 -:1083D0009847BDE81040FFF715B800BFDC670020E4 -:1083E00008B50348FCF78CFCBDE80840FFF70AB865 -:1083F000F43A002008B50348FCF782FCBDE80840C9 -:10840000FFF700B8603B002008B50348FCF778FC94 -:10841000BDE80840FEF7F6BFCC3B002008B500F0F1 -:10842000F7FABDE80840FEF7EDBF0000062108B5E9 -:108430000846FCF7E9FC06210720FCF7E5FC0621CD -:108440000820FCF7E1FC06210920FCF7DDFC0621F1 -:108450000A20FCF7D9FC06211720FCF7D5FC0621E1 -:108460002820FCF7D1FC09217A20FCF7CDFC09215A -:108470003120FCF7C9FC07213220FCF7C5FC0C2198 -:108480002620FCF7C1FC0C212720FCF7BDFC0C21A9 -:108490005220BDE80840FCF7B7BC000008B5FFF764 -:1084A00069FD00F07DFAFDF785F8FDF727F8FDF787 -:1084B0005BFAFDF72DF9FEF711FABDE8084000F070 -:1084C00029BA000030B50433039C0172002104FB7B -:1084D0000325C160C0E90653049B0363059BC0E903 -:1084E0000000C0E90422C0E90842C0E90A11436360 -:1084F00030BD00000022416AC260C0E90411C0E939 -:108500000A226FF00101FDF7E1BF0000D0E904325B -:10851000934201D1C2680AB9181D70470020704704 -:10852000036919600021C2680132C260C269134444 -:1085300082699342036124BF436A0361FDF7BABFB6 -:1085400038B504460D46E3683BB162690020131D4F -:108550001268A3621344E36207E0237A33B9294621 -:108560002046FDF797FF0028EDDA38BD6FF00100D7 -:10857000FBE70000C368C269013BC3604369134461 -:1085800082699342436124BF436A4361002383624B -:10859000036B03B11847704770B52023044683F37B -:1085A0001188866A3EB9FFF7CBFF054618B186F3FE -:1085B0001188284670BDA36AE26A13F8015B9342F2 -:1085C000A36202D32046FFF7D5FF002383F311886F -:1085D000EFE700002DE9F84F04460E46174698468F -:1085E0004FF0200989F311880025AA46D4F828B055 -:1085F000BBF1000F09D141462046FFF7A1FF20B192 -:108600008BF311882846BDE8F88FD4E90A12A7EB4E -:10861000050B521A934528BF9346BBF1400F1BD957 -:10862000334601F1400251F8040B914243F8040B28 -:10863000F9D1A36A403640354033A362D4E90A2316 -:108640009A4202D32046FFF795FF8AF31188BD4274 -:10865000D8D289F31188C9E730465A46F9F720FB8A -:10866000A36A5E445D445B44A362E7E710B5029CE5 -:108670000433017204FB0321C460C0E90613002324 -:10868000C0E90A33039B0363049BC0E90000C0E90F -:108690000422C0E90842436310BD0000026A6FF083 -:1086A0000101C260426AC0E904220022C0E90A2234 -:1086B000FDF70CBFD0E904239A4201D1C26822B968 -:1086C000184650F8043B0B607047002070470000CC -:1086D000C3680021C2690133C360436913448269DE -:1086E0009342436124BF436A4361FDF7E3BE000048 -:1086F00038B504460D46E3683BB1236900201A1DD6 -:10870000A262E2691344E36207E0237A33B929469F -:108710002046FDF7BFFE0028EDDA38BD6FF00100FE -:10872000FBE7000003691960C268013AC260C269D0 -:10873000134482699342036124BF436A03610023A7 -:108740008362036B03B118477047000070B52023A4 -:108750000D460446114683F31188866A2EB9FFF749 -:10876000C7FF10B186F3118870BDA36A1D70A36A9C -:10877000E26A01339342A36204D3E16920460439DB -:10878000FFF7D0FF002080F31188EDE72DE9F84FC7 -:1087900004460D46904699464FF0200A8AF3118808 -:1087A0000026B346A76A4FB949462046FFF7A0FF07 -:1087B00020B187F311883046BDE8F88FD4E90A0765 -:1087C0003A1AA8EB0607974228BF1746402F1BD935 -:1087D00005F1400355F8042B9D4240F8042BF9D1D4 -:1087E000A36A40364033A362D4E90A239A4204D3F1 -:1087F000E16920460439FFF795FF8BF31188464560 -:10880000D9D28AF31188CDE729463A46F9F748FAD2 -:10881000A36A3D443E443B44A362E5E7D0E9042318 -:108820009A4217D1C3689BB1836A8BB1043B9B1AF0 -:108830000ED01360C368013BC360C3691A448369E7 -:108840009A42026124BF436A0361002383620123C9 -:10885000184670470023FBE701F01F03F0B502F054 -:108860001F0456095A1C0123B6EB511F50F826501D -:1088700003FA02F34FEA511703F1FF333DBF50F8FB -:108880002720C4F12000134003EA05003BBF03FA90 -:1088900000F225FA04F0E0401043F0BD70B57E22EE -:1088A0007F210546FFF7D8FF18B1012819D0002015 -:1088B00070BD3E2249212846FFF7CEFF2F220446F5 -:1088C00031212846FFF7C8FF064601345022023600 -:1088D00053212846B440FFF7BFFF093804FA00F0DF -:1088E000E6E7302245212846FFF7B6FF0130800237 -:1088F000DEE7000090F8D63090F8D7201B0403EB99 -:10890000026390F8D42090F8D500134403EB0020C4 -:108910007047000000F052B8034B002258631A6100 -:108920000222DA60704700BF000C0040014B0022B9 -:10893000DA607047000C0040014B5863704700BF7D -:10894000000C0040014B586A704700BF000C00400B -:10895000024B034A1A60034A5A607047D4670020EA -:108960006868002000000220074B494210B55C688F -:10897000201A08401968821A914203D8944201D300 -:108980005A6010BD0020FCE7D467002008B5202302 -:1089900083F31188FFF7E8FF002383F3118808BDF4 -:1089A0000023054A19460133102BC2E9001102F1D8 -:1089B0000802F8D1704700BFDC670020114BD3F8E4 -:1089C000E82042F00802C3F8E820D3F8102142F072 -:1089D0000802C3F810210C4AD3F81031D36B43F0CE -:1089E0000803D363C722094B9A624FF0FF32DA6261 -:1089F00000229A615A63DA605A6001225A611A6051 -:108A0000704700BF004402580010005C000C00409A -:108A1000094A08B51169D3680B40D9B29B076FEAC0 -:108A20000101116107D5202383F31188FDF782FC32 -:108A3000002383F3118808BD000C0040FEF7AEBA96 -:108A4000012838BF012010B504462046FEF766FA1B -:108A500030B900F007F808B900F00CF88047F4E7E7 -:108A600010BD0000024B1868BFF35B8F704700BF5A -:108A70005C68002008B5062000F056F80120FDF7DC -:108A800063FE000010B501390244904201D100207C -:108A900005E0037811F8014FA34201D0181B10BD67 -:108AA0000130F2E7884210B501EB020402D984429A -:108AB000234607D8431EA14208D011F8012B03F822 -:108AC000012FF8E7024401468A4200D110BD13F895 -:108AD000014D02F8014DF7E71F2938B504460D4650 -:108AE00004D9162303604FF0FF3038BD426C12B139 -:108AF00052F821304BB9204600F030F82A460146A2 -:108B00002046BDE8384000F017B8012B0AD0591CA8 -:108B100003D1162303600120E7E7002442F8254033 -:108B2000284698470020E0E7024B01461868FFF707 -:108B3000D3BF00BF7422002038B5074D0023044680 -:108B4000084611462B60FDF703FE431C02D12B683B -:108B500003B1236038BD00BF60680020FDF7F2BD9F -:108B6000034611F8012B03F8012B002AF9D17047B5 -:108B700010B50139034632B111F8014F03F8014B2A -:108B8000013A002CF7D11A440021934200D110BDC4 -:108B900003F8011BF9E700004D4435002D2D0A00B4 -:108BA0002F6172647570696C6F742E6162696E00FA -:108BB0002F6172647570696C6F742D766572696669 -:108BC000792E6162696E002F6172647570696C6FD5 -:108BD000742D666C6173682E6162696E002F61721C -:108BE000647570696C6F742D666C61736865642E52 -:108BF0006162696E000000000000000000000000DB -:108C0000D10E00086D0F00081D110008A50F000807 -:108C1000650F00080000000000000000CD0E0008F5 -:108C2000790F000855110008C90E0008D50E00087C -:108C300053544D333248373F3F3F0053544D333246 -:108C4000483734332F3735330000000001105A0005 -:108C50000310590001205800032056002F00000087 -:108C60005375636365737366756C6C79206D6F758E -:108C70006E746564205344436172642028736C6F82 -:108C800077646F776E3D2575290A0000EB76904575 -:108C900058464154202020004641543332202020A1 -:108CA00000000000222A3A3C3E3F7C7F002B2C3BF8 -:108CB0003D5B5D0043554541414141434545454983 -:108CC000494941414592924F4F4F5555594F554F44 -:108CD0009C4F9E9F41494F55A5A5A6A7A8A9AAAB01 -:108CE000ACADAEAFB0B1B2B3B4414141B8B9BABBAB -:108CF000BCBDBEBFC0C1C2C3C4C54141C8C9CACB47 -:108D0000CCCDCECFD1D145454549494949D9DADB0A -:108D1000DCDD49DF4FE14F4F4F4FE6E8E855555551 -:108D20005959EEEFF0F1F2F3F4F5F6F7F8F9FAFB32 -:108D3000FCFDFEFF01030507090E10121416181C96 -:108D40001E00000061001A03E0001703F80007038B -:108D5000FF000100780100013001320106013901F4 -:108D600010014A012E017901060180014D004302E4 -:108D700081018201820184018401860187018701CA -:108D800089018A018B018B018D018E018F01900178 -:108D90009101910193019401F601960197019801C7 -:108DA00098013D029B019C019D0120029F01A001B1 -:108DB000A001A201A201A401A401A601A701A7018B -:108DC000A901AA01AB01AC01AC01AE01AF01AF0139 -:108DD000B101B201B301B301B501B501B701B801E9 -:108DE000B801BA01BB01BC01BC01BE01F701C00161 -:108DF000C101C201C301C401C501C401C701C80149 -:108E0000C701CA01CB01CA01CD011001DD0101007A -:108E10008E01DE011201F3010300F101F401F401FE -:108E2000F8012801220212013A020900652C3B02D6 -:108E30003B023D02662C3F024002410241024602D3 -:108E40000A015302400081018601550289018A010D -:108E500058028F015A0290015C025D025E025F02BD -:108E60009301610262029401640265026602670274 -:108E7000970196016A02622C6C026D026E029C01DF -:108E8000700271029D01730274029F0176027702E3 -:108E9000780279027A027B027C02642C7E027F02D5 -:108EA000A60181028202A90184028502860287024C -:108EB000AE014402B101B20145028D028E028F0261 -:108EC00090029102B7017B030300FD03FE03FF0341 -:108ED000AC0304008603880389038A03B1031103EA -:108EE000C2030200A303A303C4030803CC030300CB -:108EF0008C038E038F03D8031801F2030A00F903D1 -:108F0000F303F403F503F603F703F703F903FA0396 -:108F1000FA033004200350041007600422018A047D -:108F20003601C1040E01CF040100C004D004440185 -:108F300061052604000000007D1D0100632C001E59 -:108F40009601A01E5A01001F0806101F0606201FCA -:108F50000806301F0806401F0606511F0700591F4C -:108F6000521F5B1F541F5D1F561F5F1F601F0806A7 -:108F7000701F0E00BA1FBB1FC81FC91FCA1FCB1FFF -:108F8000DA1FDB1FF81FF91FEA1FEB1FFA1FFB1F79 -:108F9000801F0806901F0806A01F0806B01F0400C7 -:108FA000B81FB91FB21FBC1FCC1F0100C31FD01FA9 -:108FB0000206E01F0206E51F0100EC1FF31F01007F -:108FC000FC1F4E210100322170211002842101007A -:108FD0008321D0241A05302C2F04602C0201672C29 -:108FE0000601752C0201802C6401002D260841FF2A -:108FF0001A030000C700FC00E900E200E400E00002 -:10900000E500E700EA00EB00E800EF00EE00EC000E -:10901000C400C500C900E600C600F400F600F20076 -:10902000FB00F900FF00D600DC00F800A300D80028 -:10903000D7009201E100ED00F300FA00F100D10049 -:10904000AA00BA00BF00AE00AC00BD00BC00A10089 -:10905000AB00BB0091259225932502252425C10054 -:10906000C200C000A9006325512557255D25A20037 -:10907000A5001025142534252C251C2500253C256C -:10908000E300C3005A25542569256625602550252F -:109090006C25A400F000D000CA00CB00C80031014C -:1090A000CD00CE00CF0018250C2588258425A600EC -:1090B000CC008025D300DF00D400D200F500D5001D -:1090C000B500FE00DE00DA00DB00D900FD00DD00A7 -:1090D000AF00B400AD00B1001720BE00B600A7007D -:1090E000F700B800B000A800B700B900B300B200A4 -:1090F000A025A00000000000010000000096000074 -:10910000000000000000000000000000000000005F -:109110000000000000000000D5680008D9680008C1 -:1091200071510008C9540008055100082D5100086C -:1091300055510008ED500008000000007D55000862 -:1091400069550008A5550008915500089D5500086F -:10915000895500087555000861550008B15500088B -:10916000000000008D56000879560008B55600082A -:10917000A1560008AD56000899560008855600080B -:1091800071560008C15600080000000001000000F0 -:109190000000000069646C65000000009491000804 -:1091A000C0480020504A002001000000E56200088D -:1091B000000000000000812A00000000AAAAAAAA5C -:1091C00000000024FFFE00000000000000A00A00D4 -:1091D0000001000000000000AAAAAAAA00000000E6 -:1091E000FFFF000000000000000000001400AA566D -:1091F00000000000AAAAAAAA14005554FFFF00000C -:1092000000000000CCCC0C0020681A000000000018 -:10921000AAAA8AAA10541500FFFF0000000C7007CC -:10922000770000004081020100100000AAAAAAAA4B -:1092300000410100F7FF000000000070070000007F -:109240000000000000000000AAAAAAAA0000000076 -:10925000FFFF000000000000000000000000000010 -:1092600000000000AAAAAAAA00000000FFFF000058 -:1092700000000000000000000000000000000000EE -:10928000AAAAAAAA00000000FFFF00000000000038 -:10929000000000000000000000000000AAAAAAAA26 -:1092A00000000000FFFF00000000000000000000C0 -:1092B0000000000000000000AAAAAAAA0000000006 -:1092C000FFFF0000000000000000000000000000A0 -:1092D00000000000AAAAAAAA00000000FFFF0000E8 -:1092E00000000000000000004375626550696C6F6B -:1092F0007400437562654F72616E67652B2D424C39 -:10930000002553455249414C250000000200000051 -:1093100000000000AD5800081D5900084000400042 -:10932000F862002008630020020000000000000036 -:109330000300000000000000655900080000000064 -:109340001000000018630020000000000100000071 -:10935000000000008466002001010200D1690008BD -:10936000E16800087D6900086169000843000000A9 -:109370007493000809024300020100C0320904008E -:109380000001020201000524001001052401000172 -:10939000042402020524060001070582030800FFD9 -:1093A00009040100020A0000000705010240000054 -:1093B000070581024000000012000000C093000871 -:1093C0001201100102000040AE2D581000020102EF -:1093D000030100000403090425424F4152442500C3 -:1093E000437562654F72616E6765506C75732D626F -:1093F0006473686F7400303132333435363738393E -:1094000041424344454600000000002000000200A5 -:109410000200000000000030000004000000000016 -:109420000000002400000800040000000004000008 -:1094300000FC00000200000000000430008000007A -:1094400000000000000000380000010001000000E2 -:109450001F1C1F1E1F1E1F1F1E1F1E1F1F1D1F1E26 -:109460001F1E1F1F1E1F1E1F00000000B95A0008EC -:10947000715D00081D5E000840004000BC670020D0 -:10948000BC67002001000000CC67002080000000C5 -:10949000400100000800000000010000000400007E -:1094A000080000006D61696E001643300404340842 -:1094B0000C1014181C20212200000000146EFF7FE5 -:1094C0000100000000000000270400000000000070 -:1094D00000001E0000000000FF000000504A0020B5 -:1094E000F43A0020603B0020CC3B0020000000004C -:1094F000308C00083F000000500400003B8C000846 -:109500003F00000000000000010000000096000085 -:1095100000000800960000000008000004000000A1 -:10952000D4930008000000000000000000000000CC -:109530000000000000000000000000007822002071 -:10954000000000000000000000000000000000001B -:10955000000000000000000000000000000000000B -:1095600000000000000000000000000000000000FB -:1095700000000000000000000000000000000000EB -:1095800000000000000000000000000000000000DB -:1095900000000000000000000000000000000000CB +:1021F00003402144FFF7B6FF002800F0AA80054401 +:1022000000200346D8F8102092F82310B142D8D805 +:10221000002B40F09E80002D00F09B800023254481 +:10222000AB766373D8F81020137903F03701DB061F +:1022300021730BD402F13800FFF704FFC4E9000159 +:1022400093896381D3892381BDE8F8830020014607 +:10225000F4E7C36C01335ED1EA6B00232E26551ED2 +:10226000184615F8011F013020290CD0052908BF98 +:10227000E521092804D10B2B9EBFE71801337E739B +:10228000E718013379730B28EBD1E118002048736C +:10229000A17E00294BD1002B40D06FF00C0604F139 +:1022A0000D000825361B331810F8011B002938D003 +:1022B0002E298BB24AD0A3F14101192903D8117BF1 +:1022C0000D4200D020330373EDE7B9F1000F05D1C3 +:1022D00000F520539BB2B3F5006F0BD307F11A0141 +:1022E000C7F1FF0240EA09402144FFF73BFF48B134 +:1022F0000744002002368146D8F80C30985B00284D +:10230000E3D13846B9F1000F4FF0000218BF0020AA +:1023100023189A76A0E7B1463746EDE73F23A37628 +:102320000123234400219976137B03B96373D37A85 +:1023300002F11C0003F03F0323730023FFF780FE2C +:1023400020606360D38A6381138B7CE710250B4682 +:10235000B9E73F230125A37660E7000038B50546BD +:10236000002435F8020B08B9204638BD02F0EEF81B +:102370006308C2B203EBC43312FA83F39AB2C0F318 +:10238000072303EB520303EBC2339CB2E9E70000DF +:1023900037B5C37804461BB90025284603B030BDC5 +:1023A00000F14C01826C01234078019104F0EAFABB +:1023B000054680B9A36BE070A06C226BC31A9342F0 +:1023C000EAD2A3780199022BE6D102440123607876 +:1023D00004F0D8FAE1E70125DFE7000038B5836CA7 +:1023E00005460C468B4210D0FFF7D2FF60B922465B +:1023F000012305F14C01687804F0A0FA00281CBF05 +:102400004FF0FF340120AC6438BD0020FCE7000031 +:1024100038B500230446C3704FF0FF338364FFF7E1 +:10242000DDFF00284BD1B4F84A524AF655239D42AD +:1024300007D10B22254904F14C0006F07BFE002851 +:102440003FD094F84C30EB2B03D01833DBB2012B88 +:102450002ED84AF655239D4206D108221C4904F184 +:102460009E0006F067FE48B3B4F85730B3F5007F1E +:102470001ED194F85930DBB15A1E1A4218D1B4F863 +:102480005A30ABB194F85C30013B012B10D8B4F852 +:102490005D306BB1B4F85F307F2B06D804F16C006F +:1024A000FFF7CEFDB0F5803F02D3B4F8623053B9E8 +:1024B0004AF6552085420CBF0220032038BD042077 +:1024C000FCE70120FAE70020F8E700BFE0920008EF +:1024D000EC92000802392DE9F04701F007044FF0B3 +:1024E000010A466C05460AFA04F41746984606EBBC +:1024F0001136C1F3C809E4B2314628460136FFF768 +:102500006DFF18B10120BDE8F087994605EB09027F +:1025100092F84C30234214BF01210021414513D0D1 +:102520006340013F82F84C3085F803A0EBD0640093 +:1025300014F0FF04EAD109F1010301244FF000096E +:10254000B3F5007FE1D1D7E70220DCE7012902469D +:10255000F8B50C4640F28C800668F36A8B4240F274 +:1025600087803378013B032B00F28280DFE803F0A1 +:102570000229384B04EB5405B16B304601EB552171 +:10258000FFF72CFF10B14FF0FF30F8BD6F1CC5F303 +:102590000805B16B3046354401EB572195F84C5096 +:1025A000FFF71CFF0028EED1C7F30807E3073E44FE +:1025B00096F84C0045EA00204CBF0009C0F30B0020 +:1025C000E3E7B16B304601EB1421FFF707FF00286A +:1025D000D9D1640004F4FF742644B6F84C00D4E763 +:1025E000B16B304601EBD411FFF7F8FE0028CAD1D9 +:1025F000A40006F14C0004F4FE742044FFF720FD13 +:1026000020F07040C1E7D0E90430D57953EA0001E9 +:1026100001D0916801B95DBB9168022DA4EB010165 +:102620000DD1013B728940F1FF305B0A43EAC05390 +:10263000B3FBF2F399421BD81CD0601CA5E7032D15 +:1026400002D193698B42F8D8D3699BB9B16B3046FC +:1026500001EBD411FFF7C2FE002894D1A0004C3644 +:1026600000F4FE703044FFF7EBFC20F000408CE7F4 +:1026700001208AE76FF0004087E70000F8B50668A0 +:1026800004460D463378042B0CBF4FF080524FF4B4 +:1026900000128A4201D80220F8BDCA06FBD1826826 +:1026A0000163D2B9022B13D83389B3EB551FF2D98A +:1026B000F36BA363A36B6263002BECD003EB552396 +:1026C0004C36C5F308050020A3633544E563E3E712 +:1026D000F36BC271002BE7D01A4677897F02BD42A7 +:1026E000114604D23046FFF7C9FCA063E2E720465A +:1026F000FFF72CFF431C024606D00128CBD9F36A12 +:102700008342C8D9ED1BEAE70120C5E701292DE97D +:10271000F04706460C46174608D9C36A8B4205D9CE +:102720000378022B62D003D8012B22D0022552E07D +:10273000033B012BFAD8816B01EBD411FFF74EFE5E +:102740000546002847D1A40006F14C0304F4FE74AA +:102750001C443378042B07D0204627F07047FFF73E +:102760006FFC00F07040074339462046FFF76EFCCF +:102770002FE001EB5108816B01EB5821FFF72EFE92 +:10278000054640BB14F0010406F14C0908F1010AAA +:10279000C8F3080808BFFBB230461FBF19F808305D +:1027A00003F00F023B0103F0F00318BF134309F8D5 +:1027B00008300123B16BF37001EB5A21FFF70EFED5 +:1027C000054640B9CAF3080A44B1C7F3071709F828 +:1027D0000A700123F3702846BDE8F08719F80A3023 +:1027E000C7F3032723F00F031F43F0E7816B01EBCF +:1027F0001421FFF7F3FD05460028ECD1640006F133 +:102800004C0304F4FF741F551919C7F307274F70C1 +:10281000DFE70000F8B504460E461746E3690BB93A +:102820001846F8BD012BA6EB0305206814BFAA1CAF +:102830003A46691CFFF76AFF0028F2D1E369013BC1 +:10284000E361EBE701292DE9F84306460C461746FC +:10285000056802D80220BDE8F883EB6A8B42F9D9FB +:102860007AB9A14621463046A046FFF76FFE0446DE +:10287000B0B92B78042B02D1002F43D1F77100207F +:10288000E9E72B78042B02D1C379022BE9D04FF072 +:10289000FF3239462846FFF739FF0028E1D0DAE752 +:1028A0000128D7D0421C01D10120D4E72B78042B7A +:1028B00019D1EA6AAB69023A93421CD308F10102CA +:1028C000A2420CD02B78042B08D10023A2EB0902E2 +:1028D00049462846FFF7FEFD0028BCD1A146EB6A19 +:1028E000A342BFD8C5E7002241462846FFF70EFFA6 +:1028F0000028DED0AFE70133AB612B7943F0010351 +:102900002B71DBE7F3798BB9B468BC4202D10223A7 +:10291000F371B4E721463046FFF718FE012899D934 +:10292000431CC1D001348442EFD0A8E7032BA6D1C9 +:10293000B368BB42A3D8B2691344BB429FD3E6E756 +:1029400070B5C3790446032B06D181688369CD181D +:10295000A94203D10023E371002070BD4E1C206802 +:102960003246FFF7D3FE0028F7D13146F0E70000EA +:102970002DE9F74305460191FFF70AFD04460028BB +:1029800049D105F14C09019928464FF40072FFF72F +:1029900075FB2146A86407464846FFF7C1F96C89D4 +:1029A0006402B4F5004F28BF4FF40044B4F5007F33 +:1029B0002FD9204604F064FC804630B12246002125 +:1029C000640A0026FFF7ACF909E06408EEE7234645 +:1029D000BA194146687803F0D5FF18B926446B89C7 +:1029E0009E42F4D3404604F05BFC6889801B18BF0C +:1029F000012003B0BDE8F08301366B899E42F4D21A +:102A00000123BA194946687803F0BCFF0028F3D0C7 +:102A1000EBE70026F1E70120EBE70000F8B50446FC +:102A2000FFF7B6FC0546002842D12378032B37D1A7 +:102A30002779012F34D104F14C0601464FF400727E +:102A40003046FFF76DF955234122722184F84A324E +:102A5000AA2304F50D7084F84F2084F84B325223DA +:102A600084F8301284F84C3084F84D30612384F8B7 +:102A7000311284F84E3084F83332A16984F832225E +:102A8000FFF7E4FA616904F50E70FFF7DFFA626B95 +:102A90003B46314601326078A26403F073FF257132 +:102AA00000226078114603F091FF003818BF012022 +:102AB000F8BD000000232DE9F0430B6085B00F4600 +:102AC0001546FFF71BFB061EC0F2B281804B53F880 +:102AD0002640002C00F0AE813C6005F0FE05237816 +:102AE0006BB1607803F028FFC70708D41DB110F060 +:102AF000040500D00A25284605B0BDE8F083002370 +:102B0000F0B22370607003F003FFC10700F19481FD +:102B10000DB14207EED400212046FFF779FC0228D0 +:102B200040F099806E4604F2122304F2522132469C +:102B300018461033FFF784FA42F8040B8B42F7D1A2 +:102B4000002556F8041B00297DD02046FFF760FCC5 +:102B5000012879D80128A26C40F0C08004F1570305 +:102B600004F18C0113F8015B002D7BD18B42F9D16C +:102B7000B4F8B430B3F5807F74D194F8B830092B31 +:102B800070D104F19400FFF75DFA4FF0FF3317188E +:102B900041F10001BB4275EB010363D304F1A000D6 +:102BA000FFF74EFA94F8BA302063012BA37059D185 +:102BB00094F8B99003FA09F91FFA89F36381002B9D +:102BC00050D0444B04F1A800FFF73AFA0646984269 +:102BD00048D8831C626304F1A400E362FFF730FA73 +:102BE00000EB020804F19C00C4F84080FFF728FACB +:102BF00010441FFA89F2A06306FB02F313EB0803EB +:102C000045EB05029F4271EB02032BD32E4604F1E4 +:102C1000AC00FFF715FAE06365B96389B34221D9C7 +:102C2000E16B2046FFF72AFA81192046FFF7D6FB11 +:102C300098B90136631993F84C30812B14D02035A4 +:102C4000C5F30805E8E703200135042D7FF479AFCB +:102C5000042807D101E0042801D101254BE7012810 +:102C60007FF678AF0D2546E705F1140004F14C0618 +:102C70003044FFF7E5F901280546F3D9E36A8342BA +:102C8000F0D96189821E236C02FB01336364A16B5E +:102C9000204601EBD511FFF7A1FB0028DDD105F09F +:102CA0007F0006EB8000FFF7CBF9431C03D0013512 +:102CB000A842ECD0D6E70425C4E90500064A2570F1 +:102CC00000251388E56101339BB21380E38012E78E +:102CD0003C360020FDFFFF7F40360020B4F857301F +:102CE000B3F5007FBED1B4F8626026B904F170007C +:102CF000FFF7A6F9064694F85C302663591EA370C8 +:102D00000129AFD894F859506581002DAAD0691EC9 +:102D10002942A7D1B4F85D8018F00F0FA4F80880FD +:102D2000A0D1B4F85F0018B904F16C00FFF788F97E +:102D3000B4F85A10002995D006FB03FE01EB181CCD +:102D4000F44460458ED3A0EB0C00A842B0FBF5F331 +:102D500088D33E48834285D84FF6F57083426DD9BB +:102D600003259F1C114402EB0C03032DE7626263F1 +:102D7000A16323644CD1B4F8763053EA08037FF49E +:102D800071AFBB0004F17800FFF75AF9E06303F27A +:102D9000FF13B6EB532FFFF465AF4FF0FF33032D56 +:102DA000C4E905334FF08003237187D1B4F87C3038 +:102DB000012B83D1511C2046FFF710FB00287FF424 +:102DC0007DAFB4F84A224AF6552320719A427FF427 +:102DD00075AF1F4B04F14C00FFF732F998427FF4B6 +:102DE0006DAF03F1FF5304F50C70FFF729F903F5FC +:102DF0000053203398427FF461AF04F50D70FFF764 +:102E00001FF9A06104F50E70FFF71AF9606155E72C +:102E1000B8F1000F3FF426AF7144022D4FEA47038B +:102E2000E1631EBFD91907F0010303EB5103AEE7BD +:102E30000B2560E60C255EE603255CE640F6F5759D +:102E4000AB428CBF022501258BE700BFF5FFFF0FCA +:102E5000525261412DE9F84F07460568884649B945 +:102E60006E69C6B1EB6AB34298BF0126AB69A3B9DC +:102E7000002405E0FFF76AFB0128044603D801247B +:102E80002046BDE8F88F421C00F0D280EB6A8342F6 +:102E9000F6D84646EAE70126E8E72A78EB6A042AEC +:102EA00040F08380A6F1020A023B4FF0010B9A45E5 +:102EB00028BF4FF0000AD146696C284601EB193152 +:102EC000FFF78CFA00283BD109F00703EA6AC9F33F +:102ED000C8010BFA03F3901EDBB26A184C4609F1E5 +:102EE000010992F84C20814502EA030233BF5B00DE +:102EF00000234FF40071DBB228BF9946B2B9023407 +:102F0000631E0333BCD80123214628461A46FFF727 +:102F1000E1FA0228B3D0012800F08A80B8F1000F4E +:102F200013D10223FB710028A9D130E0CA450AD091 +:102F3000002BD2D10131B1F5007FBDD20123CCE706 +:102F40004FF0FF34DCE70024DAE7FB79022B07D1EE +:102F5000731CA342E7D0BB68F31ABB610323FB7168 +:102F600008F10102FB69A24205D113B10133FB61F3 +:102F7000D9E70223FBE70BB90123FB612246414657 +:102F80003846FFF747FC00284FD10123FB61EA6A6E +:102F9000AB69023A6C6193429CBF03F1FF33AB61B2 +:102FA0002B7943F001032B716AE7464514D1741C59 +:102FB0003846A34298BF02242146FFF7C7FA0128EA +:102FC0003FF45DAF431C33D0E0B16B69012B03D9F3 +:102FD000EA6A934238BF1E4634460134EB6AA34284 +:102FE00003D8012E7FF644AF022421463846FFF76E +:102FF000ADFA48B101283FF442AF013018D0B442D5 +:10300000EBD135E7002CE7D04FF0FF3221462846C0 +:10301000FFF77CFB48B9B8F1000FB8D02246414613 +:103020002846FFF773FB0028B1D001287FF427AFB3 +:103030004FF0FF3424E700002DE9F843066804460A +:10304000076B894633782037042B0CBF4FF0805331 +:103050004FF40013BB429CBF00238363836B73B1A7 +:10306000C7F30808B8F1000F3CD10133416B83630B +:1030700039B93389B3EB571F34D80023A363042035 +:103080000AE07389013B13EA57232BD1FFF75EFA5D +:103090000128054602D80220BDE8F883421C01D170 +:1030A0000120F9E7F36A834216D8B9F1000FE4D0A2 +:1030B000616B2046FFF7CEFE0546C8B10128EAD075 +:1030C000431CEDD001463046FFF752FC0028E7D103 +:1030D000E37943F00403E371294630466563FEF764 +:1030E000CDFFA0634C36002027634644E663D3E758 +:1030F0000720D1E7F8B50E46002104460768FFF720 +:10310000BDFA98B90546A16B3846FFF767F968B96B +:103110003A78E36B042A1B780CD11B060ED50546C2 +:1031200001212046FFF788FF0028ECD0042808BFC3 +:10313000072006E0E52B01D0002BF0D10135B54288 +:10314000EED1F8BDC16C4B1C2DE9F0410446056879 +:10315000066B1FD1E5274FF00108A16B2846FFF74A +:103160003DF998B92A78E36B042A09BF1A781F70D1 +:1031700002F07F021A7085F80380236BB3420DD2F0 +:1031800000212046FFF758FF0028E6D0042808BF9A +:10319000022003E0FFF772FA0028DBD0BDE8F081DF +:1031A0002DE9F04105460068A96B0669FFF716F99D +:1031B000044620B9EB6B1A78852A03D002242046F6 +:1031C000BDE8F081324603F1200153F8040B8B4235 +:1031D00042F8040BF9D1777801377F01A7F160033A +:1031E000B3F5007FEAD800212846FFF725FF042821 +:1031F0000446E3D00028E2D1A96B2868FFF7EEF877 +:1032000004460028DBD1EB6B1A78C02AD6D106F130 +:10321000200203F1200153F8040B8B4242F8040B07 +:10322000F9D196F823300F222C33B3FBF2F3B7EB2E +:10323000431FC3D34FF0400800212846FFF7FCFE90 +:1032400004280446BAD00028B9D1A96B2868FFF732 +:10325000C5F804460028B2D1EB6B1A78C12AADD16B +:10326000B8F5187F09D206EB080203F1200153F8E4 +:10327000040B8B4242F8040BF9D108F120084745B2 +:10328000DAD8B8F5187F9AD83046FEF71FFF738852 +:10329000834294D092E700000B68002210B50360CF +:1032A00004460B6A83604B6AC261C37123F0FF035B +:1032B000896AC0E90432C164FFF7E0F920B9204609 +:1032C000BDE81040FFF76CBF10BD0000F8B5036803 +:1032D000054601271C692046FEF7F8FEA070000A8B +:1032E0006678E0702846E96CFFF7C8F920B102283B +:1032F00028BF0220C0B2F8BDA96B2868FFF76EF89E +:103300000028F4D1EB6B04F1200254F8041B944222 +:1033100043F8041BF9D12B68DF70002EE7D00021A1 +:103320002846013EFFF788FEE0E700002DE9F8435C +:103330004FF0FF0806460768042445464FF6FF791C +:10334000B16B11B9002C73D063E03846FFF746F833 +:10335000044600285DD1F06B0378002B6ED03A78DC +:10336000042A11D1852B4DD1336B3046F364FFF71E +:1033700017FF044600284CD13B691B7903F03F033B +:10338000B3712046BDE8F883C27AE52B02F03F0214 +:10339000B27143D02E2B41D022F0200108293DD01C +:1033A0000F2A40D1590637D503F0BF05336B90F88B +:1033B0000D80F364437B434530D1428B72BB03786D +:1033C0000D21FC6823F04003DFF874E0013B4B4320 +:1033D00001211EF801CB30F80CC009B3FF2B1DD81A +:1033E00024F813C06146013301320D2AF1D102786D +:1033F000520605D521B1FF2B10D8002224F8132046 +:10340000013DEDB200213046FFF716FE04460028CC +:1034100096D00023B363B4E7AB42CBD0FF25F1E7EE +:10342000CC45E1D0FAE72DB9FEF740FE404501D189 +:103430000024A6E74FF0FF33F364A2E70424E8E793 +:10344000889300082DE9F04F002187B00446D0F89A +:103450000090FFF713F9804670B999F80030042BFB +:1034600033D1D9F80C00FEF779FF07462046FFF765 +:103470005DFF054620B18046404607B0BDE8F08FAD +:10348000D9F810309A8CBA42F0D193F823B0402684 +:103490005D4506D1D9F80C3033F81530002BE5D155 +:1034A000EAE7F106D9F8103008BF0236985B01F060 +:1034B0004DF8D9F80C30824633F8150001F046F883 +:1034C0008245D3D102360135E2E74FF0FF0A4FF0D3 +:1034D000FF3B5546C4F84CB0A16B4846FEF77EFF53 +:1034E00000285CD1E66B3778002F77D0F27AE52F91 +:1034F00002F03F03A37103D0120704D50F2B04D0B1 +:10350000C4F84CB04FE00F2B54D194F84B30580610 +:103510003FD4790645D5236B07F0BF0796F80DA079 +:10352000E364737B53453ED1738B002B3BD13578DD +:103530000121D9F80C3005F03F0501930D23013D21 +:103540005D43284B13F8012BB25A71B3FF2D05933D +:1035500029D81046049200F0F9FF6B1C03900293E7 +:10356000019B33F8150000F0F1FF039981421AD155 +:10357000049A029D1146059B1B4A9342E2D133787F +:103580005A0604D519B1019B33F815305BB97D1E7D +:10359000EDB200212046FFF74FFD00289CD0804669 +:1035A0006AE7BD42BDD0FF25F3E74FF6FF708242C8 +:1035B000E2D0F8E72DB93046FEF778FD50453FF4EC +:1035C0005BAF94F84B30DB079AD40B2204F1400137 +:1035D000304605F0AFFD002892D14DE74FF00408CA +:1035E0004AE700BF88930008959300082DE9F04F43 +:1035F00090F84BB099B004461BF0A00540F06881EC +:103600000668F26832F81530002B4AD13378042B63 +:1036100040F087800F230E352046B5FBF3F5A91C3B +:10362000FFF768FD8146002877D1236B0135A3EBB6 +:103630004515E3795A07E56435D523F004032046A0 +:10364000E371FFF77DF950BB4FF0FF32616B20460D +:10365000FFF7E0F818BBA3682BB3214604A8FFF7D7 +:103660001BFEE0B970894FF40071D4E90423E0FB3C +:1036700001233069C4E904233830FEF7EFFC3069D8 +:10368000D4E904232830FEF7E9FCE379326904A881 +:1036900043F0010382F82130FFF718FE18B181468C +:1036A0003BE00135AEE7D6E9035440220021204635 +:1036B000FEF736FB8523012140222370C0234FF003 +:1036C000C10C04EB010884F8203000231E469E46FE +:1036D000571C04F802C0F0B2023204F807E021B12E +:1036E00035F8131009B10133DBB20F0AA15408F801 +:1036F00002700232D706F2D135F813700136002F6E +:10370000E6D184F82330831C28466370FEF726FE3A +:1037100084F82400000A84F82500484619B0BDE862 +:10372000F08F04F140070DF1100A1BF0010F97E82C +:1037300007008AE8070000F0D38040234FF001081B +:1037400084F84B30BC46F368B8F1050F9AE80700DF +:10375000ACE803002CF8022B4FEA12428CF8002050 +:1037600059D9981E424630F8021F002942D10DF166 +:103770000F0C072102F00F0E914612090EF13000D6 +:10378000392888BF0EF1370001390CF8010902D041 +:10379000B9F10F0FEED818AB7E205A1802F8580C6A +:1037A00038460022914206D010F801CB02F1010EFA +:1037B000BCF1200F31D104F13F0C072902F10102C5 +:1037C00097BF18AB20205818013198BF10F8580C3B +:1037D000072A0CF80200F0D92046FFF733FE814695 +:1037E000002878D108F10108B8F1640FAAD14FF090 +:1037F000070992E74FF0100C01F0010E49080EEB9B +:103800004202D30344BF82F4883282F02102BCF129 +:10381000010CF1D1A7E74246A9E77246C2E7216B46 +:103820002046A1EB4511FEF729FF814600287FF4D1 +:1038300074AF4FF6FF783846FEF738FC0190A16B65 +:103840003046FEF7CBFD814600287FF466AFE36B80 +:10385000E9B2019A4FF00D0CD6F80CE05A734FF014 +:103860000F02DFF8E0A0DA724A1E18730CFB02F2B6 +:1038700084469876D87640451AF8019B0CF1010CE5 +:1038800018BF3EF8120003EB090B18BF013203F812 +:1038900009004FEA1029002808BF4046BCF10D0F6F +:1038A0008BF80190E7D1404502D03EF812200AB9CA +:1038B00041F040011970012300212046F370FFF709 +:1038C000BBFB814600287FF428AF013DB7D11BE048 +:1038D0004FF0060921E704287FF41FAF84F84BB0AE +:1038E0001BF0020F20461BBF0C350D210125B5FB37 +:1038F000F1F518BF01352946FFF7FCFB814600288A +:103900007FF40BAF013D8AD1A16B3046FEF766FD17 +:10391000814600287FF401AF01462022E06BFEF7CC +:10392000FFF9E36B03CF18605960BA7839889A724F +:10393000198194F84B30E26B03F0180313730123E1 +:10394000F370EAE68893000810B504460A4634305E +:10395000FEF776FB886004F13800FEF773FBC2E9DE +:10396000040194F8213003F00203D3710023D361E2 +:1039700010BD000003284B8B04BF8A8A43EA024330 +:10398000184670472DE9F04F0B7899B004468946E8 +:103990002F2BD0F800B001D05C2B09D14A46137808 +:1039A000914601322F2BFAD05C2BF8D0002301E096 +:1039B000DBF81C30A3600023E3619BF80030042B8C +:1039C0001ED1A368E3B1DBF82030214604A82362AE +:1039D000DBF824306362DBF82830A362FFF75CFC7D +:1039E0000346002854D1DBF8102002F13800FEF71E +:1039F00027FBC4E9040392F8213003F00203E371CA +:103A000099F800301F2B00F23581802300212046D9 +:103A100084F84B3019B0BDE8F04FFEF72FBE494691 +:103A20000B78894601312F2BFAD05C2BF8D01F2B55 +:103A30008CBF00250425012F2FD113882E2B31D1C7 +:103A4000002322F8173004F140029F428CBF2E2140 +:103A5000202101330B2B02F8011BF6D145F0200584 +:103A6000204684F84B50FFF7EDFC94F84B300028CB +:103A700000F0E78004280BD1990603F0040240F11E +:103A8000DC80002A00F0F6808023002084F84B3090 +:103A900019B0BDE8F08F0425CDE7022F02D153887D +:103AA0002E2BCAD0911E87BB002322F81730002F7F +:103AB00000F0118132F81300194601332028F9D0A3 +:103AC00009B92E2801D145F00305901E30F81730B2 +:103AD0002E2B01D0013FF9D14FF020334FF0000AD7 +:103AE0006364D0462364C4F847300823481C32F886 +:103AF00011600090F6B1202E03D02E2E0DD1B842C9 +:103B000010D045F003050099F0E731F81730202B6D +:103B100001D02E2BC8D1013FC5E79A4505D20099A7 +:103B2000B9423BD10B2B30D101E00B2B27D145F013 +:103B300003050B2394F84020E52A04BF052284F8EE +:103B40004020082B04BF4FEA88085FFA88F808F085 +:103B50000C030C2B03D008F00303032B01D145F019 +:103B60000205A8073FF57CAF18F0010F18BF45F01C +:103B7000100518F0040F18BF45F0080570E700990C +:103B8000B94202D045F00305D4D84FEA88080B2388 +:103B90004FF0080A00975FFA88F8B4E77F2E15D92E +:103BA000304640F25231CDE9022345F00203019341 +:103BB00000F098FC10F0800F0646DDE9022316D0D5 +:103BC00000F07F0646498E5D019D46B3314645486B +:103BD000CDE9012305F0D8FADDE90123F8B9A6F112 +:103BE000410189B219291ED848F0020810E0FF28C7 +:103BF000EAD9591E8A4503D345F003059A4682E760 +:103C000004EB0A01000A0AF1010A019D81F8400053 +:103C100004EB0A010AF1010A81F8406073E745F0FC +:103C200003055F26F4E7A6F1610189B219299EBF59 +:103C3000203E48F00108B6B2EAE7002A08BF052096 +:103C400026E75A073FF524AFA379DB0645D59BF855 +:103C50000000042835D1A3682146E2792362236954 +:103C6000DBF8100023F0FF0313436362E36CA362ED +:103C7000FFF76AFE23680027DA6819F8010B0028AD +:103C80003FF409AF40F25231009200F04BFC054680 +:103C900008B31F28009A7FF6FEAE2F283FF4BFAE70 +:103CA0005C283FF4BCAE7F2805D801460E4805F0DD +:103CB0006BFA009A78B9FF2F0DD022F81750013710 +:103CC000DBE7216B0BF14C03C1F308011944FFF74B +:103CD00051FEA060CEE70620DAE60520D8E600BF58 +:103CE0000893000801930008F89200081FB5CDE979 +:103CF000001003A814460391FEF700FA002815DB14 +:103D00000B4A52F820300BB100211970019B0BB106 +:103D10000021197042F820302CB1002201A9684618 +:103D2000FEF7C8FE0446204604B010BD0B24FAE797 +:103D30003C3600202DE9F04798B0904605460191A9 +:103D4000002800F0528102F03F0603A901A8324684 +:103D5000FEF7B0FE002840F04681039B4FF48C60D4 +:103D6000049303F08DFA0746002800F04081039B7E +:103D700000F500720199D86004A81A61FFF702FEED +:103D8000044620B99DF95B30002BB8BF062418F01B +:103D90001C0F00F0CD80002C4CD0042C40D104A886 +:103DA000FFF724FC044600283AD146F00806039B9E +:103DB0001A78042A40F08380186929462B60FFF79F +:103DC000C3FD039B1E22002118690230FDF7A8FFE6 +:103DD000039C00211A2220692630FDF7A1FF2369E8 +:103DE00020221A71246903F085FA01460122083461 +:103DF0002046FEF72BF9039B04A81B6983F82120BA +:103E0000FFF764FA044658B9A96801B30246284688 +:103E1000FEF718FDAB68039A0446013B5361B4B149 +:103E2000384603F03DFA0CB100232B60204618B051 +:103E3000BDE8F0879DF8163013F0110F40F0848034 +:103E400018F0040F40F0C98018F0080FAFD1039AA2 +:103E500031071399936C48BF46F04006E964AB64A0 +:103E60001078042872D1069B9DF817102B62089BCE +:103E7000106923F0FF030B4329466B62179BAB626B +:103E8000FFF762FDDDF80CA00024002205F15008C8 +:103E9000BAF8063021464046C5F800A0AB800023A2 +:103EA00085F8306085F831406C64C5E90E234FF425 +:103EB0000072FDF735FFB20653D40024B0E703F0DB +:103EC00019FA0146009013980E30FEF7BFF81398C8 +:103ED00000991630FEF7BAF8039C13992078FFF783 +:103EE00049FD202300228046CB7220461399FEF71D +:103EF000D1F8139B002201211A775A779A77DA7743 +:103F0000039BD970B8F1000FA1D0414604A8D3F8A3 +:103F10004890FEF797FC0446002881D14946039853 +:103F2000FEF75CFA039B044608F1FF30586176E720 +:103F3000002C7FF475AF9DF81630DC064FD418F0D6 +:103F4000020F84D0D80782D5072469E7FFF712FD56 +:103F50000023A86001F11C00FEF772F86B61286174 +:103F600090E7D5E9046956EA0903A6D0BAF80AA091 +:103F7000A9684FEA4A2AC5E90E69B24574EB0903FC +:103F80001BD300242964002C7FF44AAFC6F3080336 +:103F9000002B92D0039C2046FEF770F808B3760AF7 +:103FA0000123414646EAC95682196A64607802F0E4 +:103FB000C5FC041E18BF012432E72846FEF7C6FAE6 +:103FC000B6EB0A06014669F10009012803D9431C32 +:103FD000D3D10124D6E70224D4E7082420E704241F +:103FE0001EE702241CE704461EE709241EE71124ED +:103FF0001CE700002DE9F04F994685B00023884664 +:1040000003A90446C9F800301646FEF791F80546A4 +:1040100080BB94F831506DBB94F8303013F001033D +:10402000009300F0A68004F1500AD4E90432D4E9E8 +:104030000E011B1A62EB0102B34272F1000238BF9B +:104040001E46BEB1D4E90E10C1F30803002B40F0A8 +:104050008280039B5A894B0A013A43EAC0531A40B3 +:104060001BD151EA000309D1A06801280DD802250F +:1040700084F83150284605B0BDE8F08F216C204609 +:104080000192FEF763FA019AEFE7431C04D1012382 +:10409000009D84F83130EDE72064DDF80CB0216C30 +:1040A0005846FDF7EBFF0028E1D0B6F5007F02EBA4 +:1040B000000731D3BBF80A1002EB5620730A88427E +:1040C0009BF8010088BF8B1A3A464146019302F0E3 +:1040D00035FC0028DBD194F93020019B002A0BDA53 +:1040E000606CC01B984207D24FF40072514608EB37 +:1040F0004020FDF7EFFD019B5F02D9F80030F61B71 +:10410000B8443B44C9F80030D4E90E32DB1942F11F +:104110000002C4E90E3294E7626CBA421AD094F9F4 +:104120003030002B0DDA012351469BF8010002F0DC +:1041300029FC0028ABD194F8303003F07F0384F8D9 +:104140003030039801233A465146407802F0F6FB9E +:1041500000289CD16764A16B4046C1F30801C1F5FA +:1041600000775144B74228BF37463A46FDF7B2FDC3 +:10417000C3E707257EE7000070B596B00E46002223 +:10418000019002A901A8FEF795FC0446E0B94FF49E +:104190008C6003F075F80546D8B1029B00F50072FB +:1041A0000199D86002A81A61FFF7ECFB044640B9F8 +:1041B0009DF95330002B0ADB1EB1314602A8FDF7F2 +:1041C000EDFF284603F06CF8204616B070BD0624BB +:1041D000F7E71124F8E7000070B5B8B002220190AB +:1041E00003A901A8FEF766FC044608BB039B4FF435 +:1041F0008C60109303F044F80546002866D0039BBA +:1042000000F500720199D86010A81A61FFF7BAFB97 +:10421000044650B99DF88B30980655D4190653D4EE +:104220009DF84630DA0706D50724284603F038F80B +:10423000204638B070BD039B04931878042814D12D +:1042400004A91869FFF780FB069E9DF84630DB063F +:1042500010D410A8FEF776FF04460028E5D156BB1F +:104260000398FEF7DBFB0446DFE71F99FFF782FBAD +:104270000646EAE7039BDA69B242D5D024930021CF +:10428000269624A81B78042B01BFDDE90823CDE97D +:1042900028239DF817308DF89730FEF7EFF9044684 +:1042A0000028C2D124A8FFF741F804460028BBD05B +:1042B0000428BAD1CDE70246314604A8FEF7C2FA77 +:1042C00004460028B1D1CBE70624AEE71124AFE7BE +:1042D000F0B5BDB0CDE900106846FDF70FFF022232 +:1042E00003A901A8FEF7E6FB0446002841D1039B81 +:1042F0004FF48C60149302F0C3FF0546002800F0D1 +:10430000EE80039B00F5007214AE0199D8601A612B +:104310003046FFF737FB044640BB9DF89B3013F057 +:10432000A00F40F0D880039B009F1A78042A68D120 +:104330001B6904AC03F1400C1868083353F8041CE3 +:104340002246634503C21446F6D15022314628A8BE +:10435000FDF7C0FC394628A8FFF714FB04460028E7 +:104360004CD12A9A169B9A4206D00824284602F07D +:1043700097FF20463DB0F0BD349A209B9A42F4D17D +:1043800028A8FFF733F904460028EFD1039B04AFB8 +:104390001B6993F801E093F823C09C8C3A460833DC +:1043A00003CAB24243F8080C43F8041C1746F5D17F +:1043B000039B28A81B6983F801E0039B1A6982F814 +:1043C00023C01A6982F82440240A82F825401A6919 +:1043D0001379D9065CBF43F020031371FEF776FF13 +:1043E00004460028C2D13046FEF7ACFE0446002841 +:1043F000BCD10398FEF712FB0446B7E70428B5D1F9 +:10440000BEE7239A04AB02F1200C1068083252F880 +:10441000041C1C46624503C42346F6D15022314693 +:1044200028A8FDF757FC394628A8FFF7ABFA044641 +:1044300000284CD12A9A169B9A4296D1349A209BF6 +:104440009A4292D128A8FFF7D1F8044600288DD1CE +:1044500037990DF11D030DF12D0001F10D0253F8F7 +:10446000044B834242F8044BF9D11888012710808D +:104470009B7893709DF81B30039CDA0658BF43F07D +:104480002003CB72E770CB7ADB06ACD5169A2A9B59 +:104490009A42A8D02078FFF76DFA01462046FDF732 +:1044A000EDFD0146C8B12046FDF798FF04460028FF +:1044B0007FF45CAF039890F86D302E2B93D12A9A3D +:1044C00000F16C01FDF7E6FD039BDF708BE704282C +:1044D0007FF44CAFB6E7062448E7022446E71124F0 +:1044E00047E700007F2810B501D880B210BDB0F5B5 +:1044F000803F13D240F2523399420FD10849002233 +:1045000031F8024B93B2844203D103F18000C0B270 +:10451000ECE70132802AF3D11346F6E70020E5E705 +:10452000489600087F280DD940F25233994208D1AD +:10453000FF2806D800F10040034B803833F8100004 +:1045400070470020704700BF48960008B0F5803FD4 +:10455000F0B522D21F4A83B21F49B0F5805F28BF51 +:104560000A46141D34F8042C2146AAB1934213D3F1 +:1045700034F8025C2E0AEFB252FA85F5A84222DA2C +:10458000082E09D8DFE806F0050A10121416181ACA +:104590001C00801A34F810301846F0BD981A00F04C +:1045A00001001B1A9BB2F7E7103BFBE7203BF9E742 +:1045B000303BF7E71A3BF5E70833F3E7503BF1E709 +:1045C000A3F5E353EEE70434002ECBD101EB470211 +:1045D000C7E700BF989300088C95000808B5074B03 +:1045E000074A196801F03D01996053680BB1906862 +:1045F0009847BDE8084003F08FB800BF00000240B4 +:104600004436002008B5084B1968890901F03D01BE +:104610008A019A60054AD3680BB110699847BDE8D2 +:10462000084003F079B800BF000002404436002083 +:1046300008B5084B1968090C01F03D010A049A609D +:10464000054A53690BB190699847BDE8084003F0EB +:1046500063B800BF000002404436002008B5084B94 +:104660001968890D01F03D018A059A60054AD369F0 +:104670000BB1106A9847BDE8084003F04DB800BF81 +:10468000000002404436002008B5074B074A59682D +:1046900001F03D01D960536A0BB1906A9847BDE8BB +:1046A000084003F039B800BF000002404436002043 +:1046B00008B5084B5968890901F03D018A01DA60A3 +:1046C000054AD36A0BB1106B9847BDE8084003F068 +:1046D00023B800BF000002404436002008B5084B54 +:1046E0005968090C01F03D010A04DA60054A536B70 +:1046F0000BB1906B9847BDE8084003F00DB800BFC0 +:10470000000002404436002008B5084B5968890D66 +:1047100001F03D018A05DA60054AD36B0BB1106CDC +:104720009847BDE8084002F0F7BF00BF0000024014 +:104730004436002008B5074B074A196801F03D01CF +:104740009960536C0BB1906C9847BDE8084002F03B +:10475000E3BF00BF000402404436002008B5084B08 +:104760001968890901F03D018A019A60054AD36CF4 +:104770000BB1106D9847BDE8084002F0CDBF00BFF7 +:10478000000402404436002008B5084B1968090CA3 +:1047900001F03D010A049A60054A536D0BB1906D1A +:1047A0009847BDE8084002F0B7BF00BF00040240D0 +:1047B0004436002008B5084B1968890D01F03D0109 +:1047C0008A059A60054AD36D0BB1106E9847BDE813 +:1047D000084002F0A1BF00BF0004024044360020A0 +:1047E00008B5074B074A596801F03D01D960536E7F +:1047F0000BB1906E9847BDE8084002F08DBF00BF36 +:10480000000402404436002008B5084B5968890965 +:1048100001F03D018A01DA60054AD36E0BB1106FD9 +:104820009847BDE8084002F077BF00BF000402408F +:104830004436002008B5084B5968090C01F03D01C9 +:104840000A04DA60054A536F0BB1906F9847BDE8D0 +:10485000084002F061BF00BF00040240443600205F +:1048600008B5084B5968890D01F03D018A05DA60E9 +:10487000054AD36F13B1D2F880009847BDE80840CD +:1048800002F04ABF000402404436002000230C49D5 +:1048900010B51A460B4C0B6054F82300026001EB74 +:1048A000430004334260402BF6D1074A4FF0FF33F8 +:1048B0009360D360C2F80834C2F80C3410BD00BF56 +:1048C0004436002048970008000002400F28F8B541 +:1048D00010D9102810D0112811D0122808D10F2477 +:1048E0000720DFF8B4E00126DEF80050A04208D926 +:1048F000002649E00446F4E70F240020F1E70724EE +:10490000FBE706FA00F73D4240D1214C4FEA001C7C +:104910003D4304EB00160EEBC000CEF80050C0E99A +:104920000123FBB24BB11B48836B43F0010383634C +:10493000036E43F001030366036E17F47F4F09D043 +:104940001448836B43F002038363036E43F0020356 +:104950000366036E54F80C00036823F01F03036022 +:10496000056815F00105FBD104EB0C033D2493F819 +:104970000CC05F6804FA0CF43C60212405604461BB +:1049800012B1987B00F0B4FC3046F8BD0130ADE7C1 +:1049900048970008004502584436002010B53024DE +:1049A00084F31188FFF792FF002383F3118810BD71 +:1049B00010B50446807B00F0B1FC01231049627BF6 +:1049C00003FA02F20B6823EA0203DAB20B604AB977 +:1049D0000C4A916B21F001019163116E21F00101EC +:1049E0001166126E13F47F4F09D1064B9A6B22F0B9 +:1049F00002029A631A6E22F002021A661B6E10BD42 +:104A0000443600200045025808B5302383F311884E +:104A1000FFF7CEFF002383F3118808BD836CC26AC1 +:104A20008B42506810B506D95A1E4C0002EB410368 +:104A3000B3FBF4F3184410BD01F001038A0748BF2B +:104A400043F002034A0748BF43F008030A0748BF80 +:104A500043F00403CA0648BF43F010038A06426BC2 +:104A600048BF43F0200313434363704710B5074C1E +:104A7000204600F0BFFF064B0022C4E91023054B7F +:104A8000A364054BE363054BE36410BDC836002007 +:104A90000070005200B4C4041C3700201C390020F0 +:104AA000C36A0BB90E4BC3620379012B0CD10D4BBA +:104AB000984209D10C4B5A6B42F480325A63DA6D3A +:104AC00042F48032DA65DB6D436C00221A65DA62EB +:104AD0001A605A605A624FF0FF329A63704700BF03 +:104AE00048980008C8360020004502580379012B79 +:104AF00016D0436C00221A65DA621A605A605A6254 +:104B00004FF0FF329A63074B984209D1064B5A6B1C +:104B100022F480325A63DA6D22F48032DA65DB6D7A +:104B2000704700BFC83600200045025810B5446CDD +:104B30000649FFF773FF6060236842F2107043F08C +:104B400003032360BDE8104001F05ABD801A06003F +:104B50000129F8B5466C0B4F09D175680A493D40EB +:104B6000FFF75CFF054345F480557560F8BD746838 +:104B700006493C40FFF752FF044344F480547460FC +:104B8000F4E700BF00ECFFFF80F0FA0240787D01FF +:104B9000436C00225A601A6070470000426C012981 +:104BA000536823F4404304D0022905D001B953606F +:104BB000704743F48043FAE743F40043F7E700000B +:104BC000436C41F480519A60D9605A6B1206FCD54F +:104BD00080229A637047000010B541F48851446CFC +:104BE000A260E160616B11F04502FBD0A26311F09D +:104BF000040203D0FFF720FF012010BD61691046B9 +:104C00001960FAE710B541F48851446CA260E16084 +:104C1000616B11F04502FBD0A26311F0050203D0D5 +:104C2000FFF70AFF012010BD616910461960FAE71D +:104C300073B5134604460E46302282F31188426C47 +:104C4000D26B32B14FF0FF314030019301F0E4FC00 +:104C5000019B606C00220265C263C262456B15F461 +:104C6000807504D185F31188012002B070BD4FF02A +:104C7000FF31816382F31188012E06D90C21204671 +:104C800002B0BDE87040FFF7BDBF1046EDE7000081 +:104C900073B5446C0E4600250192616BA1632565D6 +:104CA000E562FFF7C9FE012E07D9019B2A460C21B8 +:104CB00002B0BDE87040FFF7A5BF02B070BD0000B4 +:104CC00010B541F49851446CA260E160616B11F041 +:104CD0004502FBD0A26311F03F0203D0FFF7ACFE08 +:104CE000012010BD216A10461960E1695960A1696F +:104CF00099606169D960F4E72DE9F74304460191B1 +:104D0000006D01A91746984602F02EFC06460028C1 +:104D10004AD0626C2046DDF804905568C5F3090559 +:104D200001356B00A56CB5FBF3F54FF47A73B5FB59 +:104D3000F3F55D43556200F023FE50BB636C4FF00A +:104D4000FF3201254146C3F8589020461D659A63FD +:104D50004FF49572DA6342F207029F62DA62E36C03 +:104D60000A9AFFF74FFFA0B9E26C104B11680B4095 +:104D70007BB929462046FFF75BFF054648B92E461A +:104D80003A460199206D02F027FC304603B0BDE899 +:104D9000F0833A460199206D02F01EFCE26C01217D +:104DA0002046FFF775FFF0E70126EEE708E0FFFD7C +:104DB0002DE9F7431F46436C01924FF47A725D6808 +:104DC00004468846C5F3090501356E00856CB5FBC0 +:104DD000F6F5B5FBF2F555435D6200F0D1FD20B16B +:104DE0000125284603B0BDE8F0837E0201A9206DAD +:104DF000324602F0B9FB05460028F1D0636C019AF7 +:104E0000D4F84C909A6501221A654FF0FF329A63EC +:104E10004FF49572DA639E62236BDB064B4658BFF4 +:104E20004FEA4828012F42461BD912212046FFF79E +:104E3000E9FEC0B9D9F80020104B13409BB9636C50 +:104E400042F2930239462046DA62E26CFFF7F0FE46 +:104E5000804640B932460199206D454602F0BCFBC0 +:104E6000BFE71121E2E732460199206D02F0B4FB61 +:104E7000E26C39462046FFF70BFFB2E708E0FFFD82 +:104E80002DE9F3411F46436C01924FF47A725D683D +:104E900004468846C5F3090501356E00856CB5FBEF +:104EA000F6F5B5FBF2F555435D6200F069FD20B102 +:104EB0000125284602B0BDE8F0817E0201A9206DDF +:104EC000324602F097FB05460028F1D0636C019A48 +:104ED0009A6501221A654FF0FF329A634FF48D7282 +:104EE000DA639E62236BE66CDB06334658BF4FEAFB +:104EF0004828012F424619D919212046FFF782FE82 +:104F0000B0B932680F4B134093B9636C42F291020F +:104F100039462046DA62E26CFFF78AFE064638B967 +:104F200001993546206D02F0A1FBC2E71821E4E7A4 +:104F30000199206D02F09AFBE26C39462046FFF79A +:104F4000A7FEB6E708E0FFFD12F0030F2DE9F041E0 +:104F500007460C4615461E4617D00E44B44202D1F1 +:104F60000020BDE8F0810123FA6B21463846FFF7A7 +:104F70001FFF0028F5D128464FF40072F96B05F5A4 +:104F800000750134FCF7A6FEE8E7BDE8F041FFF745 +:104F90000FBF000012F0030F2DE9F04107460C4649 +:104FA00015461E4617D00E44B44202D10020BDE87B +:104FB000F08129464FF40072F86B05F50075FCF797 +:104FC00089FE0123FA6B21463846FFF759FF002876 +:104FD000EDD10134E8E7BDE8F041FFF751BF000033 +:104FE00000207047302310B583F311880024436CF0 +:104FF00040302146DC6301F01DFB84F3118810BDB5 +:10500000026843681143016003B11847704700000C +:10501000024A136843F0C003136070470044004025 +:10502000024A136843F0C003136070470048004011 +:10503000024A136843F0C0031360704700780040D1 +:10504000044B9A6C02439A641A6F104318671B6FE3 +:10505000704700BF0045025837B5274C274D204602 +:1050600000F028FD04F11400009400234FF40072B6 +:10507000234900F0C3F94FF40072224904F13800CB +:105080000094214B00F03CFA204BC4E91735204C2A +:10509000204600F00FFD04F11400009400234FF4AB +:1050A00000721C4900F0AAF94FF400721A4904F189 +:1050B00038000094194B00F023FA194BC4E9173556 +:1050C000184C204600F0F6FC04F1140000234FF4C5 +:1050D00000721549009400F091F9144B4FF40072DE +:1050E000134904F13800009400F00AFA114BC4E9A6 +:1050F000173503B030BD00BF2039002000E1F505B1 +:10510000643A002064400020115000080044004030 +:105110008C390020643C00206442002021500008AB +:1051200000480040F8390020643E0020315000085B +:10513000644400200078004038B5264D0446037CC6 +:10514000002918BF0D46012B06D1234B984230D1C0 +:105150004FF40030FFF774FF2A68236EE16D03EB14 +:105160005203A566B3FBF2F36A68100442BF23F052 +:10517000070003F0070343EA4003CB60AB6843F04A +:1051800040034B60EB6843F001038B6042F496737D +:1051900043F001030B604FF0FF330B62510505D55F +:1051A00012F0102211D0B2F1805F10D084F8643078 +:1051B00038BD0A4B984205D0094B9842CCD14FF0EC +:1051C0008040C7E74FF48020C4E77F23EEE73F230A +:1051D000ECE700BF50980008203900208C390020EF +:1051E000F83900202DE9F047C66D05463768F469A7 +:1051F000210734621AD014F0080118BF4FF48071EF +:10520000E20748BF41F02001A3074FF0300348BF39 +:1052100041F04001600748BF41F0800183F31188ED +:10522000281DFFF7EDFE002383F31188E2050AD560 +:10523000302383F311884FF48061281DFFF7E0FECF +:10524000002383F311884FF030094FF0000A14F067 +:10525000200838D13B0616D54FF0300905F1380A41 +:10526000200610D589F31188504600F07DF90028FA +:1052700036DA0821281DFFF7C3FE27F080033360CC +:10528000002383F31188790614D5620612D53023E2 +:1052900083F31188D5E913239A4208D12B6C33B1DB +:1052A00027F040071021281DFFF7AAFE37600023D2 +:1052B00083F31188E30618D5AA6E1369ABB1506960 +:1052C000BDE8F047184789F31188736A284695F8B6 +:1052D0006410194000F008FC8AF31188F469B6E7FD +:1052E000B06288F31188F469BAE7BDE8F08700007E +:1052F000090100F16043012203F56143C9B283F85B +:10530000001300F01F039A4043099B0003F1604320 +:1053100003F56143C3F880211A60704700F01F0352 +:1053200001229A40430900F160409B0000F5614072 +:1053300003F1604303F56143C3F88020C3F8802183 +:10534000002380F800337047F8B51546826804469C +:105350000B46AA4200D28568A1692669761AB54231 +:105360000BD218462A46FCF7B5FCA3692B44A3616F +:105370002846A3685B1BA360F8BD0CD9AF1B184679 +:105380003246FCF7A7FC3A46E1683044FCF7A2FC41 +:10539000E3683B44EBE718462A46FCF79BFCE368CE +:1053A000E5E7000083689342F7B50446154600D24E +:1053B0008568D4E90460361AB5420BD22A46FCF758 +:1053C00089FC63692B4463612846A3685B1BA36067 +:1053D00003B0F0BD0DD93246AF1B0191FCF77AFC4A +:1053E00001993A46E0683144FCF774FCE3683B44B9 +:1053F000E9E72A46FCF76EFCE368E4E710B50A44E7 +:105400000024C361029B8460C16002610362C0E941 +:105410000000C0E9051110BD08B5D0E9053293427E +:1054200001D1826882B98268013282605A1C42616D +:1054300019700021D0E904329A4224BFC368436145 +:1054400001F012F9002008BD4FF0FF30FBE700002B +:1054500070B5302304460E4683F31188A568A5B1C4 +:10546000A368A269013BA360531CA361157822695C +:10547000934224BFE368A361E3690BB120469847D8 +:10548000002383F31188284607E03146204601F0C7 +:10549000DBF80028E2DA85F3118870BD2DE9F74FBB +:1054A00004460E4617469846D0F81C904FF0300A36 +:1054B0008AF311884FF0000B154665B12A46314634 +:1054C0002046FFF741FF034660B94146204601F000 +:1054D000BBF80028F1D0002383F31188781B03B0B8 +:1054E000BDE8F08FB9F1000F03D001902046C84706 +:1054F000019B8BF31188ED1A1E448AF31188DCE7B7 +:10550000C160C361009B82600362C0E90511114460 +:10551000C0E9000001617047F8B504460D46164623 +:10552000302383F31188A768A7B1A368013BA36068 +:1055300063695A1C62611D70D4E904329A4224BF27 +:10554000E3686361E3690BB120469847002080F36C +:10555000118807E03146204601F076F80028E2DAAB +:1055600087F31188F8BD0000D0E9052310B59A42F1 +:1055700001D182687AB982680021013282605A1CA6 +:1055800082611C7803699A4224BFC368836101F079 +:105590006BF8204610BD4FF0FF30FBE72DE9F74FC9 +:1055A00004460E4617469846D0F81C904FF0300A35 +:1055B0008AF311884FF0000B154665B12A46314633 +:1055C0002046FFF7EFFE034660B94146204601F052 +:1055D0003BF80028F1D0002383F31188781B03B037 +:1055E000BDE8F08FB9F1000F03D001902046C84705 +:1055F000019B8BF31188ED1A1E448AF31188DCE7B6 +:105600000379052B05BF836A002001204B6004BF8E +:105610004FF400730B60704770B55D1E866A0446D8 +:105620000D44B54205D9436B43F080034363012029 +:1056300070BD06250571FFF787FC05232371F7E789 +:1056400070B55D1E866A04460D44B54205D9436BAC +:1056500043F080034363012070BD07250571FFF708 +:1056600099FC05232371F7E738B505790446052D24 +:1056700005D108230371FFF7B3FC257138BD012064 +:10568000FCE700000323F0B5037185B00446FFF783 +:105690004DFA002220461146FFF792FA4FF4D572D8 +:1056A00003AB08212046FFF7ADFA0246B8B9012343 +:1056B0002363039BC3F30323012B09D103AB3721DE +:1056C0002046FFF79FFA18B9A44B039A1340ABB1D9 +:1056D00020460125FFF75CFA0223237137E103AB73 +:1056E000002237212046FFF78DFA28B99B4A039BF9 +:1056F0001A40002A00F0A78002232363236B03F0E3 +:105700000F03022B40F0A9806425954E42F21070E1 +:1057100000F076FF03AB324601212046FFF75CFA2A +:105720000028D5D1039B002B80F293805A0003D52B +:10573000236B43F010032363002204F108030221CA +:105740002046FFF7BDFA02460028C1D104F1380314 +:1057500003212046FFF756FA0028B9D104F11805B5 +:10576000A26B092120462B46FFF7AAFA0028AFD1E9 +:1057700002ABA26B07212046FFF744FA0646002839 +:10578000A6D1236B03F00F03022B40F08F807E2203 +:105790007F21284603F01CFA012840F28780E76B3E +:1057A00042F2107000F02CFF08234FF400723946CB +:1057B00020460096FFF7A0FA002889D1384603F06A +:1057C00055FA236BA06203F00F03022B72D103ABD7 +:1057D000644A06212046FFF715FA002871D15F4977 +:1057E000039B1940B1FA81F149092046FFF7B0F94E +:1057F00002AB4FF4007210212046FFF703FA054672 +:1058000000287FF465AF554E029B33427FF460AFB2 +:10581000236B13F00E0F03F00F0273D0022A7FF4F4 +:1058200057AFE36A1978012900F09480022900F04B +:105830009380002900F089804B4F2046FFF7AEF996 +:1058400003AB3A4676E0114620462263FFF7B8F9EB +:1058500054E7013D7FF45AAF3AE7444D6426444A89 +:105860003E4F012B18BF154603AB002237212046BF +:10587000FFF7C8F900287FF42BAF039B3B427FF46E +:1058800027AF03AB2A4629212046FFF7A5F90028B8 +:105890007FF41EAF039B002BFFF648AF013E3FF4A1 +:1058A00017AF42F2107000F0ABFEDDE7284603F0C0 +:1058B000B1F986E77E227F212846E66B03F088F95E +:1058C00008B9002191E70023402231462046009389 +:1058D0000623FFF711FA0028F3D1B3895BBA9B07BF +:1058E000EFD5244B40223146204600930623FFF794 +:1058F00003FA0028E5D1317C01F00F010F3918BF00 +:10590000012172E7E36A1978F9B101297FF4E0AE69 +:105910002046FFF743F903ABA26B37212046FFF780 +:1059200071F900287FF4D4AE039B33427FF4D0AEEC +:1059300003AB022206212046FFF764F900287FF41A +:10594000C7AE039B33427FF4C3AE052323712846C1 +:1059500005B0F0BD084F70E7084F6EE708E0FFFDA7 +:105960000080FFC00001B9030000B7030080FF50B2 +:1059700000001080F1FFFF800001B7030002B703B1 +:1059800037B504460C4D01ABA26B0D212046FFF745 +:1059900039F978B9019B2B420BD1C3F34323042B74 +:1059A00008D0053B022B04D84FF47A7000F028FE93 +:1059B000E9E7012003B030BD08E0FFFD70B53023FA +:1059C000054683F3118803790024022B03D184F365 +:1059D0001188204670BD0423037184F311880226C8 +:1059E000FFF7CEFF04462846FFF7D2F82E71F0E706 +:1059F000FFF73CB8044B03600123037100234363AA +:105A0000C0E90A33704700BF6898000810B530231A +:105A1000044683F31188C162FFF742F80223002095 +:105A2000237180F3118810BD10B53023044683F331 +:105A30001188FFF75BF800230122E362227183F3F0 +:105A4000118810BD026843681143016003B1184713 +:105A5000704700001430FFF721BD00004FF0FF3306 +:105A60001430FFF71BBD00003830FFF797BD000072 +:105A70004FF0FF333830FFF791BD00001430FFF7CF +:105A8000E7BC00004FF0FF311430FFF7E1BC00002D +:105A90003830FFF741BD00004FF0FF323830FFF7DC +:105AA0003BBD0000012914BF6FF0130000207047B8 +:105AB000FFF7D2BA044B036000234360C0E902330E +:105AC00001230374704700BF8C98000810B5302381 +:105AD000044683F31188FFF72FFB02230020237471 +:105AE00080F3118810BD000038B5C36904460D4627 +:105AF0001BB904210844FFF7A5FF294604F114004F +:105B0000FFF78AFC002806DA201D4FF40061BDE88B +:105B10003840FFF797BF38BD026843681143016002 +:105B200003B118477047000013B5406B00F580546F +:105B3000D4F8A4381A681178042914D1017C0229F8 +:105B400011D11979012312898B4013420BD101A97C +:105B50004C3002F06BFFD4F8A4480246019B217937 +:105B6000206800F0DFF902B010BD0000143002F030 +:105B7000EDBE00004FF0FF33143002F0E7BE00002E +:105B80004C3002F0BFBF00004FF0FF334C3002F04A +:105B9000B9BF0000143002F0BBBE00004FF0FF316F +:105BA000143002F0B5BE00004C3002F08BBF000094 +:105BB0004FF0FF324C3002F085BF000000207047EC +:105BC00010B500F58054D4F8A4381A681178042967 +:105BD00017D1017C022914D15979012352898B40B4 +:105BE00013420ED1143002F04DFE024648B1D4F8F3 +:105BF000A4484FF4407361792068BDE8104000F07C +:105C00007FB910BD406BFFF7DBBF0000704700009D +:105C10007FB5124B0125042604460360002305745A +:105C200000F1840243602946C0E902330C4B029024 +:105C3000143001934FF44073009602F0FFFD094BBE +:105C400004F69442294604F14C000294CDE9006325 +:105C50004FF4407302F0C6FE04B070BDB498000863 +:105C6000055C0008295B00080A68302383F311886B +:105C70000B790B3342F823004B79133342F823009E +:105C80008B7913B10B3342F8230000F58053C3F82E +:105C9000A41802230374002080F3118870470000C9 +:105CA00038B5037F044613B190F85430ABB90125E1 +:105CB000201D0221FFF730FF04F114006FF00101F5 +:105CC000257700F0DDFC04F14C0084F854506FF0AF +:105CD0000101BDE8384000F0D3BC38BD10B501214A +:105CE00004460430FFF718FF0023237784F854306C +:105CF00010BD000038B504460025143002F0B6FD92 +:105D000004F14C00257702F085FE201D84F85450E4 +:105D10000121FFF701FF2046BDE83840FFF750BFE3 +:105D200090F8803003F06003202B06D190F881209A +:105D30000023212A03D81F2A06D800207047222AD0 +:105D4000FBD1C0E91D3303E0034A426707228267A3 +:105D5000C3670120704700BF4422002037B500F51B +:105D60008055D5F8A4381A68117804291AD1017C15 +:105D7000022917D11979012312898B40134211D1BD +:105D800000F14C04204602F005FF58B101A920465D +:105D900002F04CFED5F8A4480246019B2179206808 +:105DA00000F0C0F803B030BD01F10B03F0B550F8BE +:105DB000236085B004460D46FEB1302383F311887D +:105DC00004EB8507301D0821FFF7A6FEFB6806F1EE +:105DD0004C005B691B681BB1019002F035FE019815 +:105DE00003A902F023FE024648B1039B2946204640 +:105DF00000F098F8002383F3118805B0F0BDFB682C +:105E00005A691268002AF5D01B8A013B1340F1D170 +:105E100004F18002EAE70000133138B550F8214060 +:105E2000ECB1302383F3118804F58053D3F8A42810 +:105E30001368527903EB8203DB689B695D6845B1A7 +:105E400004216018FFF768FE294604F1140002F0EF +:105E500023FD2046FFF7B4FE002383F3118838BDED +:105E60007047000001F052BD01234022002110B50F +:105E7000044600F8303BFBF753FF0023C4E901332D +:105E800010BD000010B53023044683F3118824228E +:105E9000416000210C30FBF743FF204601F058FD24 +:105EA00002230020237080F3118810BD70B500EB31 +:105EB0008103054650690E461446DA6018B1102277 +:105EC0000021FBF72DFFA06918B110220021FBF77C +:105ED00027FF31462846BDE8704001F039BE00007A +:105EE00083682022002103F0011310B5044683606B +:105EF0001030FBF715FF2046BDE8104001F0B4BE9E +:105F0000F0B4012500EB810447898D40E4683D43EE +:105F1000A469458123600023A2606360F0BC01F0A6 +:105F2000D1BE0000F0B4012500EB810407898D404B +:105F3000E4683D436469058123600023A2606360D7 +:105F4000F0BC01F047BF000070B5022300250446F5 +:105F5000242203702946C0F888500C3040F8045CB5 +:105F6000FBF7DEFE204684F8705001F085FD636883 +:105F70001B6823B129462046BDE87040184770BD14 +:105F80000378052B10B504460AD080F88C30052321 +:105F9000037043681B680BB1042198470023A3607A +:105FA00010BD00000178052906D190F88C204368C7 +:105FB00002701B6803B118477047000070B590F875 +:105FC0007030044613B1002380F8703004F1800271 +:105FD000204601F06DFE63689B68B3B994F8803089 +:105FE00013F0600535D00021204602F05FF9002152 +:105FF000204602F04FF963681B6813B10621204662 +:106000009847062384F8703070BD204698470028D2 +:10601000E4D0B4F88630A26F9A4288BFA36794F99F +:106020008030A56F002B4FF0300380F20381002DEC +:1060300000F0F280092284F8702083F31188002197 +:106040002046D4E91D23FFF76DFF002383F3118859 +:10605000DAE794F8812003F07F0343EA022340F259 +:106060000232934200F0C58021D8B3F5807F48D03A +:106070000DD8012B3FD0022B00F09380002BB2D122 +:1060800004F1880262670222A267E367C1E7B3F501 +:10609000817F00F09B80B3F5407FA4D194F88230DB +:1060A000012BA0D1B4F8883043F0020332E0B3F5FD +:1060B000006F4DD017D8B3F5A06F31D0A3F5C063F2 +:1060C000012B90D86368204694F882205E6894F88B +:1060D0008310B4F88430B047002884D043686367E5 +:1060E0000368A3671AE0B3F5106F36D040F602429A +:1060F00093427FF478AF5C4B63670223A36700236E +:10610000C3E794F88230012B7FF46DAFB4F8883088 +:1061100023F00203A4F88830C4E91D55E56778E749 +:10612000B4F88030B3F5A06F0ED194F882302046D9 +:1061300084F88A3001F0FEFC63681B6813B101210A +:1061400020469847032323700023C4E91D339CE7AE +:1061500004F18B0363670123C3E72378042B10D179 +:10616000302383F311882046FFF7BAFE85F31188A8 +:106170000321636884F88B5021701B680BB12046A3 +:10618000984794F88230002BDED084F88B300423BB +:10619000237063681B68002BD6D0022120469847E5 +:1061A000D2E794F8843020461D0603F00F010AD58B +:1061B00001F070FD012804D002287FF414AF2B4BAE +:1061C0009AE72B4B98E701F057FDF3E794F88230FC +:1061D000002B7FF408AF94F8843013F00F01B3D094 +:1061E0001A06204602D502F079F8ADE702F06AF807 +:1061F000AAE794F88230002B7FF4F5AE94F884304F +:1062000013F00F01A0D01B06204602D502F04EF875 +:106210009AE702F03FF897E7142284F8702083F39E +:1062200011882B462A4629462046FFF769FE85F34A +:106230001188E9E65DB1152284F8702083F3118896 +:1062400000212046D4E91D23FFF75AFEFDE60B226C +:1062500084F8702083F311882B462A46294620466D +:10626000FFF760FEE3E700BFE4980008DC98000851 +:10627000E098000838B590F870300446002B3ED006 +:10628000063BDAB20F2A34D80F2B32D8DFE803F0FE +:106290003731310822323131313131313131373713 +:1062A000856FB0F886309D4214D2C3681B8AB5FB57 +:1062B000F3F203FB12556DB9302383F311882B469B +:1062C0002A462946FFF72EFE85F311880A2384F813 +:1062D00070300EE0142384F87030302383F311887B +:1062E000002320461A461946FFF70AFE002383F3CF +:1062F000118838BDC36F03B198470023E7E7002139 +:10630000204601F0D3FF0021204601F0C3FF63685F +:106310001B6813B10621204698470623D7E70000E3 +:1063200010B590F870300446142B29D017D8062BDE +:1063300005D001D81BB110BD093B022BFBD80021B1 +:10634000204601F0B3FF0021204601F0A3FF63685F +:106350001B6813B1062120469847062319E0152B28 +:10636000E9D10B2380F87030302383F311880023A8 +:106370001A461946FFF7D6FD002383F31188DAE7A2 +:10638000C3689B695B68002BD5D1C36F03B1984785 +:10639000002384F87030CEE70023826880F8243030 +:1063A00083691B6899689142FBD25A680360426016 +:1063B00010605860704700000023826880F8243025 +:1063C00083691B6899689142FBD85A6803604260F0 +:1063D000106058607047000008B50846302383F30A +:1063E000118891F82430032B05D0042B0DD02BB944 +:1063F00083F3118808BD8B6A00221A604FF0FF33C7 +:106400008362FFF7C9FF0023F2E7D1E9003213608E +:106410005A60F3E7034610B51B68984203D09C68A6 +:106420008A689442F8D25A680B604A6011605960D9 +:1064300010BD0000FFF7B0BF064BD96881F82400FB +:106440001868026853601A600122D86080F824201E +:10645000F9F7D8BF684600200C4B30B5DD684B1CFF +:1064600087B004460FD02B46094A684600F09CF9D5 +:106470002046FFF7E1FF009B13B1684600F09EF94C +:10648000A86A07B030BDFFF7D7FFF9E768460020DC +:10649000D9630008044B1A68DB6890689B689842CF +:1064A00094BF00200120704768460020094B10B5BA +:1064B0001C68D868226853601A600122DC6084F886 +:1064C0002420FFF779FF01462046BDE81040F9F788 +:1064D00099BF00BF68460020044B1A68DB689268C9 +:1064E0009B689A4201D9FFF7E1BF704768460020D8 +:1064F00038B50123084C00252370656002F0E4FBE9 +:1065000002F00AFC0549064802F0E0FC0223237071 +:1065100085F3118838BD00BF10490020EC980008B1 +:106520006846002000F080B9034A516853685B1A3E +:106530009842FBD8704700BF001000E08B604B63AF +:106540000023CA6100F128020B6302230A618B84D5 +:106550000123886181F8263001F11003C26A4A6183 +:106560001360C36201F12C030846CB627047000040 +:10657000D0E90131026841F8183CA1F19C03383997 +:10658000CB60036941F8243C436941F8203C034B4C +:1065900041F8043CC3680248FFF7D0BF1D0400085F +:1065A0006846002008B5FFF7E3FFBDE80840FFF7A5 +:1065B00041BF000038B50E4BDC6804F12C05A06229 +:1065C000E06AA8420FD194F826303BB994F8253000 +:1065D0009B0702BFD4E9043213605A600F20BDE864 +:1065E0003840FFF729BF0368E362FFF723FFE7E7BF +:1065F00068460020302383F31188FFF7DBBF0000DB +:1066000008B50146302383F311880820FFF724FFE3 +:10661000002383F3118808BD054BDB6821B10360BB +:1066200098620320FFF718BF4FF0FF30704700BF9C +:106630006846002003682BB1002202601846996268 +:10664000FFF7F8BE70470000064BDB6839B14268BF +:1066500018605A60136043600420FFF7FDBE4FF0DE +:10666000FF307047684600200368984206D01A68D9 +:106670000260506018469962FFF7DCBE7047000068 +:1066800038B504460D462068844200D138BD036801 +:1066900023605C608562FFF7CDFEF4E7036810B508 +:1066A0009C68A2420CD85C688A600B604C602160D8 +:1066B000596099688A1A9A604FF0FF33836010BD61 +:1066C000121B1B68ECE700000A2938BF0A2170B5CD +:1066D00004460D460A26601902F0F0FA02F0D8FAD4 +:1066E000041BA54203D8751C04462E46F3E70A2E68 +:1066F00004D90120BDE8704002F0B0BC70BD0000BC +:10670000F8B5144B0D460A2A4FF00A07D96103F178 +:106710001001826038BF0A22416019691446016085 +:1067200048601861A81802F0B9FA02F0B1FA431BE8 +:106730000646A34206D37C1C28192746354602F09C +:10674000BDFAF2E70A2F04D90120BDE8F84002F0B3 +:1067500085BCF8BD68460020F8B506460D4602F037 +:1067600097FA0F4A134653F8107F9F4206D12A46E4 +:1067700001463046BDE8F840FFF7C2BFD169BB68AB +:10678000441A2C1928BF2C46A34202D92946FFF7E8 +:106790009BFF224631460348BDE8F840FFF77EBF25 +:1067A0006846002078460020C0E90323002310B487 +:1067B0005DF8044B4361FFF7CFBF000010B5194CE3 +:1067C000236998420DD08168D0E9003213605A6085 +:1067D0009A680A449A60002303604FF0FF33A36174 +:1067E00010BD0268234643F8102F53600022026058 +:1067F00022699A4203D1BDE8104002F059BA936869 +:1068000081680B44936002F043FA2269E16992685F +:10681000441AA242E4D91144BDE81040091AFFF716 +:1068200053BF00BF684600202DE9F047DFF8BC8069 +:1068300008F110072C4ED8F8105002F029FAD8F8B9 +:106840001C40AA68031B9A423ED814444FF000092A +:10685000D5E90032C8F81C4013605A60C5F80090B2 +:10686000D8F81030B34201D102F022FA89F311882E +:10687000D5E9033128469847302383F311886B69A3 +:10688000002BD8D002F004FA6A69A0EB0409824612 +:106890004A450DD2022002F0E1FB0022D8F8103068 +:1068A000B34208D151462846BDE8F047FFF728BF5C +:1068B000121A2244F2E712EB09092946384638BF7A +:1068C0004A46FFF7EBFEB5E7D8F81030B34208D0E0 +:1068D0001444C8F81C00211AA960BDE8F047FFF76E +:1068E000F3BEBDE8F08700BF784600206846002070 +:1068F00038B502F0CDF9054AD2E90845031B18194D +:1069000045F10001C2E9080138BD00BF684600201A +:1069100010B560B9074804790368053C9B6818BF47 +:106920000124984708B144F00404204610BD012416 +:10693000FBE700BFC8360020FFF7EABF2DE9F047AC +:10694000884617469A460446B0B90D4E3579052D4E +:1069500005D003240DE0013D15F0FF050ED032688F +:10696000534639463046D2F814904246C84700286C +:10697000F1D12046BDE8F0870424FAE70124F8E7C6 +:10698000C83600202DE9F047884617469A46044647 +:10699000B0B90D4E3579052D05D003240DE0013D2C +:1069A00015F0FF050ED03268534639463046D2F80E +:1069B00018904246C8470028F1D12046BDE8F0872C +:1069C0000424FAE70124F8E7C836002037B50C465E +:1069D000154670B951B101290BD1074869460368C2 +:1069E0001B6A984710B9019B04462B60204603B0F0 +:1069F00030BD0424FAE700BFC836002000207047ED +:106A0000FEE70000704700004FF0FF3070470000C5 +:106A10004B6843608B688360CB68C3600B694361DC +:106A20004B6903628B6943620B6803607047000027 +:106A300008B5464B40F2FF714548D3F888200A4319 +:106A4000C3F88820D3F8882022F4FF6222F00702DE +:106A5000C3F88820D3F888303E4B1A6C0A431A6476 +:106A60009A6E0A433C499A669B6EFFF7D1FF1C3130 +:106A700000F58060FFF7CCFF1C3100F58060FFF768 +:106A8000C7FF1C3100F58060FFF7C2FF1C3100F525 +:106A90008060FFF7BDFF1C3100F58060FFF7B8FF95 +:106AA0001C3100F58060FFF7B3FF1C3100F58060FA +:106AB000FFF7AEFF1C3100F58060FFF7A9FF1C3126 +:106AC00000F58060FFF7A4FF1C3100F58060FFF740 +:106AD0009FFF01F097FC214BD3F8902242F0010276 +:106AE000C3F89022D3F8942242F00102C3F8942212 +:106AF0000522C3F898204FF06052C3F89C20184A32 +:106B0000C3F8A020174BDA6952021ED59A69D00744 +:106B100004D5154A9A6002F144329A60114BDA6941 +:106B2000D107FCD41A6A22F480021A629A6942F0F0 +:106B300002029A61DA69D207FCD49A6942F0010232 +:106B40009A61084AD369DB07FCD408BD00440258A7 +:106B500000000258004502580099000800ED00E0CE +:106B60001F000803002000523B2A190808B501F055 +:106B700051FEFFF7BDFC0D4BDA6B42F04002DA63C9 +:106B80005A6E22F040025A665B6E094B1A6842F058 +:106B900008021A601A6842F004021A6000F06EFDE2 +:106BA00000F032FBBDE8084000F0B4B800450258E0 +:106BB000001802480120704700207047704700000D +:106BC00002290CD0032904D00129074818BF00204E +:106BD0007047032A05D8054800EBC20070470448F7 +:106BE00070470020704700BF049B0008542200201B +:106BF000B89A000870B59AB005460846144601A92F +:106C000000F0C2F801A8FBF783F8431C0022C6B2CB +:106C10005B001046C5E9003423700323023404F8F6 +:106C2000013C01ABD1B202348E4201D81AB070BD22 +:106C300013F8011B013204F8010C04F8021CF1E7FF +:106C400008B5302383F311880348FFF787F8002342 +:106C500083F3118808BD00BF1849002090F88030E8 +:106C600003F01F02012A07D190F881200B2A03D1DB +:106C70000023C0E91D3315E003F06003202B08D189 +:106C8000B0F884302BB990F88120212A03D81F2A2C +:106C900004D8FFF745B8222AEBD0FAE7034A426747 +:106CA00007228267C3670120704700BF4B22002084 +:106CB00007B5052917D8DFE801F0191603191920BF +:106CC000302383F31188104A01210190FFF7EEF879 +:106CD000019802210D4AFFF7E9F80D48FFF70AF87D +:106CE000002383F3118803B05DF804FB302383F3A2 +:106CF00011880748FEF7D4FFF2E7302383F31188A9 +:106D00000348FEF7EBFFEBE7589A00087C9A00086F +:106D10001849002038B50C4D0C4C2A460C4904F19A +:106D20000800FFF767FF05F1CA0204F110000949E6 +:106D3000FFF760FF05F5CA7204F118000649BDE8C7 +:106D40003840FFF757BF00BFF061002054220020F9 +:106D5000349A00083E9A00084D9A000870B504461F +:106D600008460D46FAF7D4FFC6B220460134037830 +:106D70000BB9184670BD32462946FAF7B5FF002810 +:106D8000F3D10120F6E700002DE9F04705460C4657 +:106D9000FAF7BEFF2B49C6B22846FFF7DFFF08B15E +:106DA0000E36F6B228492846FFF7D8FF08B110364C +:106DB000F6B2632E0BD8DFF88C80DFF88C90234F6F +:106DC000DFF894A02E7846B92670BDE8F0872946F2 +:106DD0002046BDE8F04702F0E5B9252E2ED1072266 +:106DE00041462846FAF780FF70B9194B224603F155 +:106DF000140153F8040B8B4242F8040BF9D11B78B1 +:106E0000073515341370DDE7082249462846FAF79E +:106E10006BFF98B9A21C0F4B197802320909C95DA2 +:106E200002F8041C13F8011B01F00F015345C95D62 +:106E300002F8031CF0D118340835C3E7013504F813 +:106E4000016BBFE7249B00084D9A0008429B000895 +:106E50002C9B000800E8F11F0CE8F11FBFF34F8FD7 +:106E6000044B1A695107FCD1D3F810215207F8D10D +:106E7000704700BF0020005208B50D4B1B78ABB91E +:106E8000FFF7ECFF0B4BDA68D10704D50A4A5A60CA +:106E900002F188325A60D3F80C21D20706D5064A8F +:106EA000C3F8042102F18832C3F8042108BD00BFF1 +:106EB0004E640020002000522301674508B5114BA5 +:106EC0001B78F3B9104B1A69510703D5DA6842F001 +:106ED0004002DA60D3F81021520705D5D3F80C210F +:106EE00042F04002C3F80C21FFF7B8FF064BDA6806 +:106EF00042F00102DA60D3F80C2142F00102C3F83B +:106F00000C2108BD4E640020002000520F289ABFBB +:106F100000F5806040040020704700004FF400300E +:106F200070470000102070470F2808B50BD8FFF7F6 +:106F3000EDFF00F500330268013204D104308342D2 +:106F4000F9D1012008BD0020FCE700000F2838B56A +:106F500005463FD8FFF782FF1F4CFFF78DFF4FF02C +:106F6000FF3307286361C4F814311DD82361FFF78C +:106F700075FF030243F02403E360E36843F08003FA +:106F8000E36023695A07FCD42846FFF767FFFFF741 +:106F9000BDFF4FF4003100F0ABFA2846FFF78EFF3B +:106FA000BDE83840FFF7C0BFC4F81031FFF756FF07 +:106FB000A0F108031B0243F02403C4F80C31D4F8F9 +:106FC0000C3143F08003C4F80C31D4F810315B0766 +:106FD000FBD4D9E7002038BD002000522DE9F84F3E +:106FE00005460C46104645EA0203DE0602D00020A4 +:106FF000BDE8F88F20F01F00DFF8BCB0DFF8BCA0C0 +:10700000FFF73AFF04EB0008444503D10120FFF7E6 +:1070100055FFEDE720222946204602F08BF810B9F3 +:1070200020352034F0E72B4605F120021F68791C3B +:10703000DDD104339A42F9D105F178431B481C4E47 +:10704000B3F5801F1B4B38BF184603F1F80332BF5E +:10705000D946D1461E46FFF701FF0760A5EB040C99 +:10706000336804F11C0143F002033360231FD9F895 +:10707000007017F00507FAD153F8042F8B424CF833 +:107080000320F4D1BFF34F8FFFF7E8FE4FF0FF333B +:107090002022214603602846336823F00203336030 +:1070A00002F048F80028BBD03846B0E7142100525F +:1070B0000C200052142000521020005210210052C7 +:1070C00010B5084C237828B11BB9FFF7D5FE012372 +:1070D000237010BD002BFCD02070BDE81040FFF7DE +:1070E000EDBE00BF4E6400202DE9F04F0D4685B087 +:1070F000814658B111F00D0614BF2022082211F06C +:107100000803019304D0431E034269D0002435E0F4 +:10711000002E37D009F11F0121F01F094FF001089F +:10712000314F05F00403DFF8CCA005EA080BBBF1F2 +:10713000000F32D07869C0072FD408F101080C374E +:10714000B8F1060FF3D19EB9284D4946A81901920E +:1071500001F004FE0446002839D12036019AA02E01 +:10716000F3D1494601F0FAFD044600282FD1019AD7 +:1071700049461F4801F0F2FD044660BB204605B0B9 +:10718000BDE8F08F0029C9D101462846029201F0DE +:10719000E5FD0446D8B9029AC0E713B17869410702 +:1071A000CBD5AC0702D578698007C6D5019911B156 +:1071B00078690107C1D549460AEB4810CDE9022399 +:1071C00001F0CCFD0446DDE902230028B5D04A4693 +:1071D0000021204601E04A460021FAF7A1FDCDE753 +:1071E0000246002E96D199E7549B00089064002037 +:1071F00050640020706400200021FFF775BF00007C +:107200000121FFF771BF000070B5144D0124144E29 +:1072100040F2FF3200210120FAF782FD06EB441014 +:1072200001342A6955F80C1F01F084FD062CF5D1B4 +:1072300037254FF4C0542046FFF7E2FF014628B13E +:1072400022460848BDE8704001F074BDC4EBC40498 +:10725000013D4FEAD404EED170BD00BF549B00083D +:1072600070640020506400200421FFF73DBF00003F +:107270004843FFF7C1BF000008B101F0E1BD70470E +:10728000B0F5805F10B5044607D8FFF7EDFF28B9C9 +:107290002046BDE81040FFF7AFBF002010BD000042 +:1072A000FFF7EABF70B5AAB140EA010313F01F036C +:1072B0000FD1094C0144A5686D0706D52568A84281 +:1072C00003D366683544A94204D903330C34122B26 +:1072D000F1D10022104670BD549B000808B501F0A2 +:1072E000C5FE034AD2E90032C01842EB010108BDD5 +:1072F00030650020434BD3E900232DE9F3411343CC +:107300007CD0FFF7EBFF404A00230027F9F794F801 +:1073100006460D463D4A0023F9F78EF80023144631 +:1073200030462946394AF9F787F84FF461613C2322 +:10733000ADF80170B4FBF1F5B4FBF3F601FB1541B8 +:1073400003FB16464624B1FBF3F1314BF6B28DF840 +:10735000004098423CD84FF0640C4FF4C87EA3071D +:1073600004F26C7225D1B2FBFCF30CFB132313BBAC +:10737000B2FBFEF30EFB1322B2FA82F35B0903F2B7 +:107380006D18621C8045D2B217D90FB18DF800403C +:107390000022204C4FF00C0C17460CFB0343D4B2D8 +:1073A000013213F804C084450CD8A0EB0C0001276F +:1073B000F5E70023E3E70123E1E7A0EB080014462B +:1073C0000127CCE70FB18DF80140431C8DF8023046 +:1073D0009DF80100431C9DF800005038400640EA2B +:1073E00043509DF8023040EA034040EA560040EA2C +:1073F000C52040EA411002B0BDE8F0814FF404100E +:10740000F9E700BF3065002040420F0080510100C5 +:1074100090230B009C9B00080244074BD2B210B58E +:10742000904200D110BD441C00B253F8200041F836 +:10743000040BE0B2F4E700BF504000580E4B30B5EB +:107440001C6F240405D41C6F1C671C6F44F400449B +:107450001C670A4C02442368D2B243F48073236051 +:10746000074B904200D130BD441C51F8045B00B280 +:1074700043F82050E0B2F4E70044025800480258B4 +:107480005040005807B5012201A90020FFF7C4FFB2 +:10749000019803B05DF804FB13B50446FFF7F2FF53 +:1074A000A04205D0012201A900200194FFF7C6FFE8 +:1074B00002B010BD10B56424013C4FF47A70FFF7A0 +:1074C0009FF814F0FF04F7D1084B4FF0807214249A +:1074D0009A6103F5805308229A61013C4FF47A7057 +:1074E000FFF78EF814F0FF04F7D110BD000002582A +:1074F0000144BFF34F8F064B884204D3BFF34F8F35 +:10750000BFF36F8F7047C3F85C022030F4E700BF11 +:1075100000ED00E00144BFF34F8F064B884204D3D7 +:10752000BFF34F8FBFF36F8F7047C3F870022030E7 +:10753000F4E700BF00ED00E070B5054616460C46C6 +:1075400001201021FFF794FE286046733CB12046CD +:1075500036B1FFF789FE2B68186000B19C6070BDE2 +:10756000FFF74EFEF7E70000F8B50F461546044654 +:1075700048B905F11F010126386821F01F01FFF706 +:10758000B7FF3046F8BD427B29463868FFF78AFED0 +:1075900006460028EDD13B686360A368AB4210D279 +:1075A00013B12068FFF768FE637B28462BB1FFF715 +:1075B0005BFE206020B9A060E3E7FFF721FEF8E75B +:1075C000A560206805F11F01012621F01F01386028 +:1075D000FFF78EFF2673D4E710B5044640B100686C +:1075E000884205D1606808B1FAF774FB0023237361 +:1075F00010BD0000F8B50F461446054648B904F121 +:107600001F010126386821F01F01FFF783FF304674 +:10761000F8BD427B21463868FFF744FE0646002845 +:10762000EDD1AB68A34210D213B12868FFF724FE56 +:107630006B7B20462BB1FFF717FE286020B9A860AE +:10764000E5E7FFF7DDFDF8E7AC60396819B12246E0 +:107650002868FAF73FFB286804F11F01012621F092 +:107660001F013860FFF756FF2E73D0E720B1036883 +:107670008B4204BF0023037370470000034B1A685A +:107680001AB9034AD2F8D0241A607047386500202E +:107690000040025808B5FFF7F1FF024B1868C0F32D +:1076A000806008BD38650020EFF309830549683321 +:1076B0004A6B22F001024A6383F30988002383F3B3 +:1076C0001188704700EF00E0302080F3118862B627 +:1076D0000D4B0E4AD96821F4E0610904090C0A43F4 +:1076E0000B49DA60D3F8FC2042F08072C3F8FC202A +:1076F000084AC2F8B01F116841F001011160202250 +:10770000DA7783F82200704700ED00E00003FA0505 +:1077100055CEACC5001000E0302310B583F31188BE +:107720000E4B5B6813F4006314D0F1EE103AEFF3E4 +:1077300009844FF08073683CE361094BDB6B23667F +:1077400084F30988FEF7A6FE10B1064BA36110BDB5 +:10775000054BFBE783F31188F9E700BF00ED00E07C +:1077600000EF00E02F0400083204000870B5BFF3FA +:107770004F8FBFF36F8F1A4A0021C2F85012BFF328 +:107780004F8FBFF36F8F536943F400335361BFF3DF +:107790004F8FBFF36F8FC2F88410BFF34F8FD2F8B3 +:1077A000803043F6E074C3F3C900C3F34E335B018A +:1077B00003EA0406014646EA81750139C2F86052BF +:1077C000F9D2203B13F1200FF2D1BFF34F8F536951 +:1077D00043F480335361BFF34F8FBFF36F8F70BD9E +:1077E00000ED00E0FEE70000214B2248224A70B580 +:1077F000904237D3214BC11EDA1C121A22F0030229 +:107800008B4238BF00220021FAF78AFA1C4A002373 +:10781000C2F88430BFF34F8FD2F8803043F6E07463 +:10782000C3F3C900C3F34E335B0103EA0406014608 +:1078300046EA81750139C2F86C52F9D2203B13F146 +:10784000200FF2D1BFF34F8FBFF36F8FBFF34F8F76 +:10785000BFF36F8F0023C2F85032BFF34F8FBFF3D7 +:107860006F8F70BD53F8041B40F8041BC0E700BFC6 +:10787000A49C00083467002034670020346700208F +:1078800000ED00E0054B996B21EA000199631A6E47 +:1078900022EA00021A661B6E704700BF00450258BC +:1078A00070B5D0E9244300224FF0FF359E6804EB09 +:1078B00042135101D3F80009002805DAD3F8000972 +:1078C00040F08040C3F80009D3F8000B002805DA27 +:1078D000D3F8000B40F08040C3F8000B013263186E +:1078E0009642C3F80859C3F8085BE0D24FF0011381 +:1078F000C4F81C3870BD0000890141F0200101610D +:1079000003699B06FCD41220FEF70EBE10B50A4C8C +:107910002046FEF7A9FA094BC4F89030084BC4F88A +:107920009430084C2046FEF79FFA074BC4F890307D +:10793000064BC4F8943010BD3C65002000000840A0 +:10794000D89B0008D865002000000440E49B000894 +:1079500070B503780546012B58D13F4BD0F89040C5 +:10796000984254D13D4B0E2165209A6B42F0006243 +:107970009A631A6E42F000621A661B6E384BD3F897 +:10798000802042F00062C3F88020D3F8802022F0EB +:107990000062C3F88020D3F88030FDF7A9FC314B9A +:1079A000E360314BC4F800380023D5F89060C4F888 +:1079B000003EC02323604FF40413A3633369002BFC +:1079C000FCDA01230C203361FEF7AEFD3369DB07DF +:1079D000FCD41220FEF7A8FD3369002BFCDA002648 +:1079E0002846A660FFF75CFF6B68C4F81068DB6888 +:1079F000C4F81468C4F81C6863BB1C4BA3614FF047 +:107A0000FF336361A36843F00103A36070BD184BAB +:107A10009842C9D1114B4FF080609A6B42F00072CE +:107A20009A631A6E42F000721A661B6E0C4BD3F802 +:107A3000802042F00072C3F88020D3F8802022F02A +:107A40000072C3F88020D3F88030FFF71BFF0E21AF +:107A50004D20A2E7074BD1E73C65002000450258C6 +:107A6000004402584014004003002002003C30C093 +:107A7000D8650020083C30C0F8B5D0F890400546E5 +:107A800000214FF000662046FFF736FFD5F894102E +:107A900000234FF001128F684FF0FF30C4F83438E4 +:107AA000C4F81C2804EB431201339F42C2F800695A +:107AB000C2F8006BC2F80809C2F8080BF2D20B68D2 +:107AC000D5F89020C5F898306362102313611669C9 +:107AD00016F01006FBD11220FEF726FDD4F8003870 +:107AE00023F4FE63C4F80038A36943F4402343F051 +:107AF0001003A3610923C4F81038C4F814380B4BE1 +:107B0000EB604FF0C043C4F8103B094BC4F8003B96 +:107B1000C4F81069C4F80039D5F8983003F11002A0 +:107B200043F48013C5F89820A362F8BDB49B000805 +:107B300040800010D0F8902090F88A10D2F80038D9 +:107B400023F4FE6343EA0113C2F8003870470000D3 +:107B50002DE9F84300EB8103D0F890500C468046A5 +:107B6000DA680FFA81F94801166806F00306731EF9 +:107B7000022B05EB41134FF0000194BFB604384EC1 +:107B8000C3F8101B4FF0010104F1100398BF06F178 +:107B9000805601FA03F3916998BF06F50046002963 +:107BA0003AD0578A04F15801374349016F50D5F84C +:107BB0001C180B430021C5F81C382B180127C3F8EB +:107BC0001019A7405369611E9BB3138A928B9B08BF +:107BD000012A88BF5343D8F89820981842EA0343F3 +:107BE00001F140022146C8F89800284605EB8202C0 +:107BF0005360FFF781FE08EB8900C3681B8A43EAE4 +:107C0000845348341E4364012E51D5F81C381F4359 +:107C1000C5F81C78BDE8F88305EB4917D7F8001BB9 +:107C200021F40041C7F8001BD5F81C1821EA030312 +:107C3000C0E704F13F030B4A2846214605EB8303C6 +:107C40005A60FFF759FE05EB4910D0F8003923F4CC +:107C50000043C0F80039D5F81C3823EA0707D7E7F6 +:107C60000080001000040002D0F894201268C0F8D0 +:107C70009820FFF715BE00005831D0F89030490128 +:107C80005B5813F4004004D013F4001F0CBF022013 +:107C9000012070474831D0F8903049015B5813F407 +:107CA000004004D013F4001F0CBF022001207047D5 +:107CB00000EB8101CB68196A0B6813604B68536055 +:107CC0007047000000EB810330B5DD68AA691368D6 +:107CD000D36019B9402B84BF402313606B8A1468AA +:107CE000D0F890201C4402EB4110013C09B2B4FBD7 +:107CF000F3F46343033323F0030343EAC44343F041 +:107D0000C043C0F8103B2B6803F00303012B0ED1D6 +:107D1000D2F8083802EB411013F4807FD0F8003B12 +:107D200014BF43F0805343F00053C0F8003B02EB14 +:107D30004112D2F8003B43F00443C2F8003B30BD8F +:107D40002DE9F041D0F8906005460C4606EB411352 +:107D5000D3F8087B3A07C3F8087B08D5D6F814385F +:107D60001B0704D500EB8103DB685B689847FA07C3 +:107D70001FD5D6F81438DB071BD505EB8403D9686B +:107D8000CCB98B69488A5A68B2FBF0F600FB162220 +:107D90008AB91868DA6890420DD2121AC3E9002431 +:107DA000302383F3118821462846FFF78BFF84F3A5 +:107DB0001188BDE8F081012303FA04F26B8923EAFC +:107DC00002036B81CB68002BF3D021462846BDE827 +:107DD000F041184700EB81034A0170B5DD68D0F827 +:107DE00090306C692668E66056BB1A444FF4002058 +:107DF000C2F810092A6802F00302012A0AB20ED161 +:107E0000D3F8080803EB421410F4807FD4F800097B +:107E100014BF40F0805040F00050C4F8000903EB5C +:107E20004212D2F8000940F00440C2F800090122D1 +:107E3000D3F8340802FA01F10143C3F8341870BDD5 +:107E400019B9402E84BF4020206020681A442E8A31 +:107E50008419013CB4FBF6F440EAC44040F0005001 +:107E6000C6E700002DE9F843D0F8906005460C46BF +:107E70004F0106EB4113D3F8088918F0010FC3F83E +:107E800008891CD0D6F81038DB0718D500EB810321 +:107E9000D3F80CC0DCF81430D3F800E0DA6896456B +:107EA00030D2A2EB0E024FF000091A60C3F8049022 +:107EB000302383F31188FFF78DFF89F3118818F0C1 +:107EC000800F1DD0D6F834380126A640334217D093 +:107ED00005EB84030134D5F89050D3F80CC0E4B21C +:107EE0002F44DCF8142005EB0434D2F800E051688C +:107EF000714514D3D5F8343823EA0606C5F834683A +:107F0000BDE8F883012303FA01F2038923EA02039F +:107F10000381DCF80830002BD1D09847CFE7AEEBD7 +:107F20000103BCF81000834228BF0346D7F81809A4 +:107F300080B2B3EB800FE3D89068A0F1040959F840 +:107F4000048FC4F80080A0EB09089844B8F1040F2E +:107F5000F5D818440B4490605360C8E72DE9F84FFA +:107F6000D0F8905004466E69AB691E4016F48058F4 +:107F70006E6103D0BDE8F84FFDF7E6BF002E12DAC0 +:107F8000D5F8003E9B0705D0D5F8003E23F003034B +:107F9000C5F8003ED5F80438204623F00103C5F8A3 +:107FA0000438FDF7FFFF370505D52046FFF778FCBD +:107FB0002046FDF7E5FFB0040CD5D5F8083813F0DE +:107FC000060FEB6823F470530CBF43F4105343F4D3 +:107FD000A053EB6031071BD56368DB681BB9AB6945 +:107FE00023F00803AB612378052B0CD1D5F8003EB4 +:107FF0009A0705D0D5F8003E23F00303C5F8003EEC +:108000002046FDF7CFFF6368DB680BB12046984739 +:10801000F30200F1BA80B70226D5D4F89090002779 +:108020004FF0010A09EB4712D2F8003B03F440235A +:10803000B3F5802F11D1D2F8003B002B0DDA628905 +:108040000AFA07F322EA0303638104EB8703DB6880 +:10805000DB6813B13946204698470137D4F894308D +:10806000FFB29B689F42DDD9F00619D5D4F8900085 +:10807000026AC2F30A1702F00F0302F4F012B2F51B +:10808000802F00F0CA80B2F5402F09D104EB8303A2 +:10809000002200F58050DB681B6A974240F0B080F8 +:1080A0003003D5F8185835D5E90303D5002120460B +:1080B000FFF746FEAA0303D501212046FFF740FE45 +:1080C0006B0303D502212046FFF73AFE2F0303D5A9 +:1080D00003212046FFF734FEE80203D504212046A1 +:1080E000FFF72EFEA90203D505212046FFF728FE43 +:1080F0006A0203D506212046FFF722FE2B0203D594 +:1081000007212046FFF71CFEEF0103D5082120467A +:10811000FFF716FE700340F1A780E90703D50021A1 +:108120002046FFF79FFEAA0703D501212046FFF74F +:1081300099FE6B0703D502212046FFF793FE2F0718 +:1081400003D503212046FFF78DFEEE0603D504215B +:108150002046FFF787FEA80603D505212046FFF736 +:1081600081FE690603D506212046FFF77BFE2A061D +:1081700003D507212046FFF775FEEB0574D5204691 +:108180000821BDE8F84FFFF76DBED4F890904FF08E +:10819000000B4FF0010AD4F894305FFA8BF79B681C +:1081A0009F423FF638AF09EB4713D3F8002902F49A +:1081B0004022B2F5802F20D1D3F80029002A1CDA02 +:1081C000D3F8002942F09042C3F80029D3F80029DF +:1081D000002AFBDB3946D4F89000FFF78DFB22899B +:1081E0000AFA07F322EA0303238104EB8703DB681F +:1081F0009B6813B13946204698470BF1010BCAE73B +:10820000910701D1D0F80080072A02F101029CBF3A +:1082100003F8018B4FEA18283FE704EB830300F5CE +:108220008050DA68D2F818C0DCF80820DCE9001CBD +:10823000A1EB0C0C00218F4208D1DB689B699A6886 +:108240003A449A605A683A445A6029E711F0030F99 +:1082500001D1D0F800808C4501F1010184BF02F802 +:10826000018B4FEA1828E6E7BDE8F88F08B5034808 +:10827000FFF774FEBDE80840FFF74EBA3C650020EA +:1082800008B50348FFF76AFEBDE80840FFF744BAA7 +:10829000D8650020D0F8903003EB4111D1F8003BB5 +:1082A00043F40013C1F8003B70470000D0F8903051 +:1082B00003EB4111D1F8003943F40013C1F8003940 +:1082C00070470000D0F8903003EB4111D1F8003B2B +:1082D00023F40013C1F8003B70470000D0F8903041 +:1082E00003EB4111D1F8003923F40013C1F8003930 +:1082F00070470000044BDA6B0243DA635A6E104396 +:1083000058665B6E704700BF0045025808B53C4B8D +:108310004FF0FF31D3F8802062F00042C3F8802094 +:10832000D3F8802002F00042C3F88020D3F88020E8 +:10833000D3F88420C3F88410D3F884200022C3F833 +:108340008420D3F88400D86F40F0FF4040F4FF0051 +:1083500040F4DF4040F07F00D867D86F20F0FF4046 +:1083600020F4FF0020F4DF4020F07F00D867D86FB2 +:10837000D3F888006FEA40506FEA5050C3F8880085 +:10838000D3F88800C0F30A00C3F88800D3F8880047 +:10839000D3F89000C3F89010D3F89000C3F8902061 +:1083A000D3F89000D3F89400C3F89410D3F8940055 +:1083B000C3F89420D3F89400D3F89800C3F8981029 +:1083C000D3F89800C3F89820D3F89800D3F88C001D +:1083D000C3F88C10D3F88C00C3F88C20D3F88C0031 +:1083E000D3F89C00C3F89C10D3F89C10C3F89C20D1 +:1083F000D3F89C30FCF74AFABDE8084000F0D2B947 +:108400000044025808B50122504BC3F80821504BD4 +:108410005A6D42F002025A65DA6F42F00202DA67E0 +:108420000422DB6F4B4BDA605A689104FCD54A4A50 +:108430001A6001229A60494ADA6000221A614FF4F8 +:1084400040429A61434B9A699204FCD51A6842F4FF +:1084500080721A60424B1A6F12F4407F04D04FF4BE +:1084600080321A6700221A671A6842F001021A6005 +:108470003B4B1A685007FCD500221A611A6912F0AA +:108480003802FBD1012119604FF0804159605A67D1 +:10849000344ADA62344A1A611A6842F480321A6045 +:1084A0002F4B1A689103FCD51A6842F480521A6067 +:1084B0001A689204FCD52D4A2D499A6200225A630B +:1084C000196301F57C01DA6301F5E77199635A6478 +:1084D000284A1A64284ADA621A6842F0A8521A60D6 +:1084E0001F4B1A6802F02852B2F1285FF9D14822D6 +:1084F0009A614FF48862DA6140221A621F4ADA6494 +:108500001F4A1A651F4A5A651F4A9A6532231F4A35 +:108510001360136803F00F03022BFAD1104A13699A +:1085200043F003031361136903F03803182BFAD1E6 +:108530004FF00050FFF7DEFE4FF08040FFF7DAFE0D +:108540004FF00040BDE80840FFF7D4BE0080005166 +:10855000004502580048025800C000F00400000125 +:10856000004402580000FF0100889008322060009B +:1085700063020901470E0508DD0BBF012000002042 +:10858000000001100910E00000010110002000525D +:108590004FF0B04208B5D2F8883003F00103C2F8BA +:1085A000883023B1044A13680BB150689847BDE87E +:1085B0000840FFF7B1B800BFB46600204FF0B042EA +:1085C00008B5D2F8883003F00203C2F8883023B12E +:1085D000044A93680BB1D0689847BDE80840FFF79C +:1085E0009BB800BFB46600204FF0B04208B5D2F887 +:1085F000883003F00403C2F8883023B1044A1369B9 +:108600000BB150699847BDE80840FFF785B800BF37 +:10861000B46600204FF0B04208B5D2F8883003F0BD +:108620000803C2F8883023B1044A93690BB1D069BA +:108630009847BDE80840FFF76FB800BFB466002058 +:108640004FF0B04208B5D2F8883003F01003C2F8FA +:10865000883023B1044A136A0BB1506A9847BDE8C9 +:108660000840FFF759B800BFB46600204FF0B04390 +:1086700010B5D3F8884004F47872C3F88820A306B4 +:1086800004D5124A936A0BB1D06A9847600604D5A4 +:108690000E4A136B0BB1506B9847210604D50B4A59 +:1086A000936B0BB1D06B9847E20504D5074A136C66 +:1086B0000BB1506C9847A30504D5044A936C0BB1D9 +:1086C000D06C9847BDE81040FFF726B8B46600208C +:1086D0004FF0B04310B5D3F8884004F47C42C3F89F +:1086E0008820620504D5164A136D0BB1506D98476A +:1086F000230504D5124A936D0BB1D06D9847E00461 +:1087000004D50F4A136E0BB1506E9847A10404D5DF +:108710000B4A936E0BB1D06E9847620404D5084A99 +:10872000136F0BB1506F9847230404D5044A936F1D +:108730000BB1D06F9847BDE81040FEF7EDBF00BF0A +:10874000B466002008B50348FCF74CFCBDE80840BF +:10875000FEF7E2BFC836002008B50348FCF742FD2B +:10876000BDE80840FEF7D8BF2039002008B503480F +:10877000FCF738FDBDE80840FEF7CEBF8C3900207D +:1087800008B50348FCF72EFDBDE80840FEF7C4BF5E +:10879000F839002008B500F0B7FCBDE80840FEF746 +:1087A000BBBF0000062108B50846FCF7A1FD062165 +:1087B0000720FCF79DFD06210820FCF799FD062106 +:1087C0000920FCF795FD06210A20FCF791FD062102 +:1087D0001720FCF78DFD06212820FCF789FD0921D3 +:1087E0007A20FCF785FD09213120FCF781FD072166 +:1087F0003220FCF77DFD0C212620FCF779FD0C21B1 +:108800002720FCF775FD0C215220BDE80840FCF73D +:108810006FBD000008B5FFF779FD00F043FCFDF7E0 +:1088200047F9FDF7E5F8FDF71DFBFDF7EFF9FEF75A +:10883000C5F9BDE8084000F029BA000030B504339E +:10884000039C0172002104FB0325C160C0E90653AB +:10885000049B0363059BC0E90000C0E90422C0E952 +:108860000842C0E90A11436330BD00000022416A9A +:10887000C260C0E90411C0E90A226FF00101FDF7EE +:10888000FFBE0000D0E90432934201D1C2680AB9A8 +:10889000181D704700207047036919600021C268E5 +:1088A0000132C260C269134482699342036124BFEA +:1088B000436A0361FDF7D8BE38B504460D46E36848 +:1088C0003BB162690020131D1268A3621344E36286 +:1088D00007E0237A33B929462046FDF7B5FE002884 +:1088E000EDDA38BD6FF00100FBE70000C368C26934 +:1088F000013BC3604369134482699342436124BFCF +:10890000436A436100238362036B03B118477047D6 +:1089100070B53023044683F31188866A3EB9FFF7A9 +:10892000CBFF054618B186F31188284670BDA36AAF +:10893000E26A13F8015B9342A36202D32046FFF779 +:10894000D5FF002383F31188EFE700002DE9F84FEE +:1089500004460E46174698464FF0300989F31188B1 +:108960000025AA46D4F828B0BBF1000F09D1414632 +:108970002046FFF7A1FF20B18BF311882846BDE800 +:10898000F88FD4E90A12A7EB050B521A934528BFBA +:108990009346BBF1400F1BD9334601F1400251F819 +:1089A000040B914243F8040BF9D1A36A40364035D9 +:1089B0004033A362D4E90A239A4202D32046FFF748 +:1089C00095FF8AF31188BD42D8D289F31188C9E78F +:1089D00030465A46F9F77EF9A36A5E445D445B442B +:1089E000A362E7E710B5029C0433017203FB042184 +:1089F000C460C0E906130023C0E90A33039B036384 +:108A0000049BC0E90000C0E90422C0E908424363B6 +:108A100010BD0000026A6FF00101C260426AC0E945 +:108A200004220022C0E90A22FDF72ABED0E904236D +:108A30009A4201D1C26822B9184650F8043B0B6033 +:108A4000704700231846FAE7C3680021C269013362 +:108A5000C3604369134482699342436124BF436AFC +:108A60004361FDF701BE000038B504460D46E368DA +:108A70003BB1236900201A1DA262E2691344E3623C +:108A800007E0237A33B929462046FDF7DDFD0028AB +:108A9000EDDA38BD6FF00100FBE7000003691960F3 +:108AA000C268013AC260C269134482699342036199 +:108AB00024BF436A036100238362036B03B1184739 +:108AC0007047000070B530230D460446114683F30D +:108AD0001188866A2EB9FFF7C7FF10B186F3118897 +:108AE00070BDA36A1D70A36AE26A01339342A36258 +:108AF00004D3E16920460439FFF7D0FF002080F35A +:108B00001188EDE72DE9F84F04460D469046994649 +:108B10004FF0300A8AF311880026B346A76A4FB98E +:108B200049462046FFF7A0FF20B187F31188304661 +:108B3000BDE8F88FD4E90A073A1AA8EB060797426E +:108B400028BF1746402F1BD905F1400355F8042BC9 +:108B50009D4240F8042BF9D1A36A40364033A3620A +:108B6000D4E90A239A4204D3E16920460439FFF785 +:108B700095FF8BF311884645D9D28AF31188CDE74A +:108B800029463A46F9F7A6F8A36A3D443E443B44D9 +:108B9000A362E5E7D0E904239A4217D1C3689BB1E9 +:108BA000836A8BB1043B9B1A0ED01360C368013BF0 +:108BB000C360C3691A4483699A42026124BF436A4D +:108BC0000361002383620123184670470023FBE7FB +:108BD00001F01F03F0B502F01F0456095A1C0123CF +:108BE000B6EB511F50F8265003FA02F34FEA511723 +:108BF00003F1FF333DBF50F82720C4F1200013409C +:108C000003EA05003BBF03FA00F225FA04F0E04056 +:108C10001043F0BD70B57E227F210546FFF7D8FFD7 +:108C200018B1012819D0002070BD3E2249212846E4 +:108C3000FFF7CEFF2F22044631212846FFF7C8FF59 +:108C4000064601345022023653212846B440FFF72D +:108C5000BFFF093804FA00F0E6E730224521284634 +:108C6000FFF7B6FF01308002DEE7000090F8D63053 +:108C700090F8D7201B0403EB026390F8D42090F8FF +:108C8000D500134403EB00207047000000F018BA31 +:108C9000014B586A704700BF000C0040034B002294 +:108CA00058631A610222DA60704700BF000C00406E +:108CB000014B0022DA607047000C0040014B586302 +:108CC000704700BF000C0040024B034A1A60034A81 +:108CD0005A6070478C660020386700200000022030 +:108CE000074B494210B55C68201A08401968821A7F +:108CF0008A4203D3A24201D85A6010BD0020FCE78B +:108D00008C66002008B5302383F31188FFF7E8FF55 +:108D1000002383F3118808BD0448054B036000233A +:108D2000C0E901330C3000F017B900BF9466002091 +:108D3000058D0008CB1D083A23F00703591A521A73 +:108D400010B4D2080024C0E9004384600C301C60D9 +:108D50005A605DF8044B00F0FFB800002DE9F74FB2 +:108D6000364FCD1D8846002818BF0746082A4FEA0F +:108D7000D50538BF082207F10C003C1D9146019033 +:108D800000F02CF9019809F10701C9F1000E224603 +:108D9000246864B900F02CF93B68CBB3082249463B +:108DA000E8009847044698B340E9027830E004EBC5 +:108DB000010CD4F804A00CEA0E0C0AF10106ACF187 +:108DC000080304EBC6069E42E1D9A6EB0C0CB5EBFA +:108DD000EC0F4FEAEC0BDAD89C421DD204F10802EA +:108DE000AB45A3EB02024FEAE202626009D9691CBB +:108DF000ED4303EBC1025D445560256843F83150F3 +:108E000022601C46C3F8048044F8087B00F0F0F8A8 +:108E1000204603B0BDE8F08FAA45216802D1116059 +:108E20002346EEE7013504EBC50344F8351003F1A2 +:108E30000801761AF6105E601360F1E79466002070 +:108E400073B50446A0F1080550F8080C54F8043C2A +:108E5000061D0C3007330190DB0844F8043C00F099 +:108E6000BDF8334601989E421A6801D0AB4228D221 +:108E70000AB1954225D244F8082C54F8042C1D6000 +:108E8000013254F8081C05EBC206B14206D14E6807 +:108E9000324444F8042C0A6844F8082C5E68711CBB +:108EA00003EBC1018D4207D154F8042C0132324446 +:108EB0005A6054F8082C1A6002B0BDE8704000F007 +:108EC00097B81346CFE70000FEE7000070B51E4BD1 +:108ED0000025044686B058600E4605638163FEF7A0 +:108EE000F3FB04F12803A5606563C4E90A3304F1C8 +:108EF0001003C4E904334FF0FF33C4E90044C4E96C +:108F00000635FFF7C5FE2B46024604F13C0120461C +:108F1000C4E9082380230D4A6567FDF70FFB7368DA +:108F2000E0600B4A03620123009280F82430684617 +:108F3000F26801923269CDE90223064BCDE904358E +:108F4000FDF730FB06B070BD10490020F89B00080B +:108F5000F09B0008C98E00080023C0E90000836070 +:108F60000361704770B51C4B05468468DE685CB3CE +:108F7000B44213D103690133036170BDA36094F857 +:108F8000243083B1062B15D1A06A2146D4E90032E2 +:108F900013605A60FDF73EFAA36A9C68B368A26842 +:108FA0009A42EBD306E0D4E90032204613605A60BF +:108FB000FDF740FA28463146FDF72CFAB562062047 +:108FC000BDE87040FDF738BA03698660013303617C +:108FD000336BC3603063D0E76846002008B53023A8 +:108FE00083F31188FFF7BEFF002383F3118808BDC8 +:108FF000194BD96883688B4210B520D1302383F395 +:1090000011880269013A0261B2B90468C368A042DA +:109010000B631ED04A6B9BB901238A60036103680E +:109020001A68026050601A6B8360C2601863184649 +:10903000FDF700FAFDF750FA002383F3118810BD05 +:109040001C68A34203D0A468A24238BF2246DB6852 +:10905000E1E78260F0E700BF68460020024A536BF8 +:1090600018435063704700BF6846002038B5EFF3DF +:1090700011859DB9EFF30584C4F30804302334B19E +:1090800083F31188FDF734FC85F3118838BD83F331 +:109090001188FDF72DFC84F3118838BDBDE83840F8 +:1090A000FDF726BC0023054A19460133102BC2E9FF +:1090B000001102F10802F8D1704700BFB466002029 +:1090C0000E4B9A6C42F008029A641A6F42F0080242 +:1090D0001A670B4A1B6FD36B43F00803D363C72295 +:1090E000084B9A624FF0FF32DA6200229A615A63AB +:1090F000DA605A6001225A611A60704700450258CE +:109100000010005C000C0040094A08B51169D368E2 +:109110000B40D9B29B076FEA0101116107D53023DB +:1091200083F31188FDF7FEF9002383F3118808BD4E +:10913000000C004010B501390244904201D10020DA +:1091400005E0037811F8014FA34201D0181B10BDB0 +:109150000130F2E7884210B501EB020402D98442E3 +:10916000234607D8431EA14208D011F8012B03F86B +:10917000012FF8E7024401468A4200D110BD13F8DE +:10918000014D02F8014DF7E7C9B2034610F8012B73 +:109190001AB18A42F9D118467047002918BF002336 +:1091A000F9E70000034611F8012B03F8012B002A10 +:1091B000F9D1704710B50139034632B111F8014FAA +:1091C00003F8014B013A002CF7D11A4400219342D5 +:1091D00000D110BD03F8011BF9E700004D44350034 +:1091E0002D2D0A002F6172647570696C6F742E6189 +:1091F00062696E002F6172647570696C6F742D7690 +:1092000065726966792E6162696E002F617264759C +:1092100070696C6F742D666C6173682E6162696E23 +:10922000002F6172647570696C6F742D666C617368 +:109230006865642E6162696E000000000000000035 +:1092400000000000ED0E0008890F00083911000829 +:10925000C10F0008810F000800000000000000009E +:10926000E90E0008950F000871110008E50E0008CE +:10927000F10E000853544D333248373F3F3F0053FF +:10928000544D3332483733782F3732780053544DAA +:109290003332483734332F3735332F3735300000EA +:1092A00001105A00031059000120580003205600F5 +:1092B0002F0000005375636365737366756C6C797A +:1092C000206D6F756E746564205344436172642031 +:1092D00028736C6F77646F776E3D2575290A0000DF +:1092E000EB769045584641542020200046415433A7 +:1092F00032202020000000002A3A3C3E7C223F7FA2 +:10930000002B2C3B3D5B5D004355454141414143B2 +:1093100045454549494941414592924F4F4F555521 +:10932000594F554F9C4F9E9F41494F55A5A5A6A704 +:10933000A8A9AAABACADAEAFB0B1B2B3B441414194 +:10934000B8B9BABBBCBDBEBFC0C1C2C3C4C5414130 +:10935000C8C9CACBCCCDCECFD1D145454549494965 +:1093600049D9DADBDCDD49DF4FE14F4F4F4FE6E80B +:10937000E85555555959EEEFF0F1F2F3F4F5F6F7DB +:10938000F8F9FAFBFCFDFEFF01030507090E1012B8 +:109390001416181C1E00000061001A03E0001703D9 +:1093A000F8000703FF0001007801000130013201DD +:1093B0000601390110014A012E01790106018001DF +:1093C0004D004302810182018201840184018601F2 +:1093D0008701870189018A018B018B018D018E0133 +:1093E0008F0190019101910193019401F601960181 +:1093F0009701980198013D029B019C019D0120026B +:109400009F01A001A001A201A201A401A401A60143 +:10941000A701A701A901AA01AB01AC01AC01AE01F2 +:10942000AF01AF01B101B201B301B301B501B501A3 +:10943000B701B801B801BA01BB01BC01BC01BE0152 +:10944000F701C001C101C201C301C401C501C401CA +:10945000C701C801C701CA01CB01CA01CD01100172 +:10946000DD0101008E01DE011201F3010300F101B3 +:10947000F401F401F8012801220212013A02090064 +:10948000652C3B023B023D02662C3F02400241023A +:10949000410246020A015302400081018601550241 +:1094A00089018A0158028F015A0290015C025D0213 +:1094B0005E025F029301610262029401640265022E +:1094C00066026702970196016A02622C6C026D02C5 +:1094D0006E029C01700271029D01730274029F0171 +:1094E00076027702780279027A027B027C02642C8F +:1094F0007E027F02A60181028202A9018402850206 +:1095000086028702AE014402B101B20145028D021A +:109510008E028F0290029102B7017B030300FD03CC +:10952000FE03FF03AC0304008603880389038A0358 +:10953000B1031103C2030200A303A303C40308037E +:10954000CC0303008C038E038F03D8031801F203AE +:109550000A00F903F303F403F503F603F703F70333 +:10956000F903FA03FA0330042003500410076004DF +:1095700022018A043601C1040E01CF040100C00497 +:10958000D004440161052604000000007D1D010097 +:10959000632C001E9601A01E5A01001F0806101F12 +:1095A0000606201F0806301F0806401F0606511F2A +:1095B0000700591F521F5B1F541F5D1F561F5F1F5F +:1095C000601F0806701F0E00BA1FBB1FC81FC91FEF +:1095D000CA1FCB1FDA1FDB1FF81FF91FEA1FEB1F83 +:1095E000FA1FFB1F801F0806901F0806A01F080611 +:1095F000B01F0400B81FB91FB21FBC1FCC1F010051 +:10960000C31FD01F0206E01F0206E51F0100EC1F6A +:10961000F31F0100FC1F4E210100322170211002B6 +:10962000842101008321D0241A05302C2F04602CC2 +:109630000201672C0601752C0201802C6401002DAB +:10964000260841FF1A030000C700FC00E900E20001 +:10965000E400E000E500E700EA00EB00E800EF00CE +:10966000EE00EC00C400C500C900E600C600F4002E +:10967000F600F200FB00F900FF00D600DC00F80065 +:10968000A300D800D7009201E100ED00F300FA003A +:10969000F100D100AA00BA00BF00AE00AC00BD00CE +:1096A000BC00A100AB00BB009125922593250225AB +:1096B0002425C100C200C000A900632551255725FB +:1096C0005D25A200A5001025142534252C251C2578 +:1096D00000253C25E300C3005A255425692566254D +:1096E000602550256C25A400F000D000CA00CB00F6 +:1096F000C8003101CD00CE00CF0018250C258825EB +:109700008425A600CC008025D300DF00D400D20041 +:10971000F500D500B500FE00DE00DA00DB00D90060 +:10972000FD00DD00AF00B400AD00B1001720BE00A9 +:10973000B600A700F700B800B000A800B700B90055 +:10974000B300B200A025A0001000024008000240B3 +:109750000008024000000B00280002400800024000 +:109760000408024006010C004000024008000240CC +:109770000808024010020D00580002400800024094 +:109780000C08024016030E00700002400C0002405C +:109790001008024000040F00880002400C00024044 +:1097A0001408024006051000A00002400C00024010 +:1097B0001808024010061100B80002400C000240D8 +:1097C0001C08024016072F00100402400804024043 +:1097D0002008024000083800280402400804024023 +:1097E00024080240060939004004024008040240EF +:1097F00028080240100A3A005804024008040240B7 +:109800002C080240160B3B00700402400C0402407E +:1098100030080240000C3C00880402400C04024066 +:1098200034080240060D4400A00402400C0402402B +:1098300038080240100E4500B80402400C040240F3 +:109840003C080240160F4600010000000000000026 +:109850000096000000000000000000000000000072 +:10986000000000000000000000000000B56B0008D0 +:10987000B96B000885560008BD5900081956000844 +:109880004156000869560008015600080000000013 +:10989000715A00085D5A0008995A0008855A000854 +:1098A000915A00087D5A0008695A0008555A000864 +:1098B000A55A000800000000895B0008755B0008DD +:1098C000B15B00089D5B0008A95B0008955B000880 +:1098D000815B00086D5B0008BD5B000800000000B4 +:1098E000010000000000000063300000E89800085C +:1098F0000000000000000000E046002010490020A9 +:109900000000812A00000000AAAAAAAA00000024E0 +:10991000FFFE00000000000000A00A00000100009F +:1099200000000000AAAAAAAA00000000FFFF000091 +:1099300000000000000000001400AA560000000013 +:10994000AAAAAAAA14005554FFFF000000000000B4 +:10995000CCCC0C0020681A0000000000AAAA8AAA39 +:1099600010541500FFFF0000000C70077700000086 +:109970004081020100100000AAAAAAAA0041010029 +:10998000F7FF00000000007007000000000000006A +:1099900000000000AAAAAAAA00000000FFFF000021 +:1099A00000000000000000000000000000000000B7 +:1099B000AAAAAAAA00000000FFFF00000000000001 +:1099C000000000000000000000000000AAAAAAAAEF +:1099D00000000000FFFF0000000000000000000089 +:1099E0000000000000000000AAAAAAAA00000000CF +:1099F000FFFF000000000000000000000000000069 +:109A000000000000AAAAAAAA00000000FFFF0000B0 +:109A10000000000000000000000000000000000046 +:109A2000AAAAAAAA00000000FFFF00000000000090 +:109A3000000000004375626550696C6F74004375E7 +:109A400062654F72616E67652B2D424C0025534550 +:109A50005249414C250000000200000000000000B7 +:109A6000A95D0008195E000840004000C0610020A8 +:109A7000D061002002000000000000000300000090 +:109A800000000000615E00080000000010000000FF +:109A9000E061002000000000010000000000000064 +:109AA0003C65002001010200B16C0008C16B000898 +:109AB0005D6C0008416C000843000000C09A00087B +:109AC00009024300020100C0320904000001020241 +:109AD00001000524001001052401000104240202F4 +:109AE0000524060001070582030800FF09040100A0 +:109AF000020A00000007050102400000070581027C +:109B000040000000120000000C9B00081201100130 +:109B100002000040AE2D58100002010203010000B7 +:109B20000403090425424F415244250043756265F0 +:109B30004F72616E6765506C75732D626473686FE8 +:109B4000740030313233343536373839414243448A +:109B50004546000000000020000002000200000056 +:109B60000000003000000400080000000000002495 +:109B700000000800040000000004000000FC0000D9 +:109B80000200000000000430008000000800000017 +:109B90000000003800000100010000001F1C1F1E13 +:109BA0001F1E1F1F1E1F1E1F1F1D1F1E1F1E1F1FCC +:109BB0001E1F1E1F00000000BD5F00087562000828 +:109BC0002163000840004000746600207466002095 +:109BD00001000000846600208000000040010000B9 +:109BE0000800000000010000001000000800000054 +:109BF00069646C65000000006D61696E002C0438BA +:109C0000040438080C10141C202425260000000031 +:109C1000000064040100040000000000000C0010BB +:109C2000283034004468FF7F01000000000000007D +:109C3000270400000000000000001E0000000000DB +:109C4000FF00000018490020203900208C39002036 +:109C5000F83900200000000074920008830400001E +:109C60007F920008500400008D920008010000005F +:109C700000000000009600000000080096000000B0 +:109C80000008000004000000209B00080000000005 +:109C900000000000000000000000000000000000C4 +:049CA00000000000C0 :00000001FF diff --git a/Tools/bootloaders/CubeOrangePlus_bl.bin b/Tools/bootloaders/CubeOrangePlus_bl.bin index 93755be351bb07f2e99fe3d22cc95a788ae9e4df..8008bd1af3db49f2a81d2a94e107397222b93867 100755 GIT binary patch delta 9324 zcmZ`f33L?IviEk+(%B~@kQJCE2}6Q$AS?j_OeUep1__G_t`icWLjZ%I4@I2-vP8v4 zxS)`r26_5H6dA)PLB}AX&-ee+pJDle+mBCV2t2g|k?u@prhnbZavsm~=bY+Wx4Nos z-MV$R>S;O3>~CXsj$;l#-k6=4-M9sDZh$U;;ad@x5AgkL#Ho42jR$xDpaH-M@IBuc zJ%U-awei(y;Y+q5ZWVxMYh!eBbl4ok{lp+{Hc<9#1Fm6{fbsx91Aq(Q$2pDBqr$_A z5H|^+vIwL`Y~0i@MI{Ge<2DkFOPE!gT7SR{Zq#$6lUd1W#b}>KT-`?&v4v2{fXbCV z(!!?Q0dGzs4bmec074x13+jYYPif};h@N&=Z232~Pg1qxG?b3?8gWlB(uu_NG8QxY zkeD3cpteRf^GMY7_IgqJKfP-HnisWWq&>#Du-Hgm(WaOW^s>hukX3!TE{kdN&DiY; zMXV6vRExhW$TYm9yywX^aYbtJvO+qwnfH|VCYY-1S?k#>t*1)JYGd?RwEBQ)ZIwOO zO*`_57IAw`NWT+st~9ZZHAi0j->XRE)C@Vyc@= z4R4Lm%8g#Is1Avji4>lN|4B>{hKMLxWl--_A41~)kn)HWoIz?MrY!kRVf2bLCpg-- zRknhoE`x)QIoW+y9#1~dZDr=$=I0}^OF`yeJSTY-pMPUm9Ai))n#sQ-$6Jv2f-=IJ z&STJ#9!x837LM4om#D+vBYhE*@EkHeauOa#mPd{>>;|9wyMI*FM*xukyU81ocZ@_b zZc+@6A}ku@@@t3KFK%vQo+>u;m|#&)ev2H9t4U1Mq_MqnJ@57ALQ9;Y-g(3Or5s-m z{e#|p6=b}~RBcclQV}G&$*QP?>7#+?%D+$#2a(y)v;QdVd!HYfXZ5^vRJ9k0QOY$h zrFDmBFC0Z;Drt`zo{*qud6hx6Qw92W1gG+C-U)gnt{~T=rbp}#4*Kt${G{^c&l-N-m2we<;VUQkXRb`)pSrRe zd`Kr$%T`Rh(aTjDagIzD#8^h{{5TN?s_P?!bS@Q$i;AAtx%=^J3TcV4Cw$k4xI4PU z@^^lp^|Y4H7qBt&5F_p+2|5%0flSxAMsVU%`Sld;x(1IpRGw*WFE?`H5}9aXGsAz_ zg}4?N+|EWaEjD|+S2^aZ7p-BMV>)*oZ7}`U_bkw?;$Q4U1`CfTAu%k#wIO|-n*rZ! zA^T!S7iz?3dXac5nAnEW&3y4O(Otu57BS)l@LZ{9Y?+>CL`5+J#jlKkXRl)5jYTX> zZ)E=2QwMt94-$XuC><-_C&T(^{>qb7gv8f^By(6=AuHwspUaaYSor&dy>n8XCP5#< zkhneg7Ay@uuZsT-mWIpVi5`Fm=#&AV5Fj35WZ%`gYgn{4^4kxsc_sY3Laq2eedO&V zJ@Z)~`6}sA=J`HiOI|(ZZ~*ChsG1z4*TG=K(?Kz5T?~&6QQca!L)Kap=@gNYN5VWG zo|5IDoRkZO4b{2A=b^OlxoT1FwbYx1ob8)!+$FX6OK+B-D#SU*e@C;j>^IKUxl#KS zkZS=@i^oo)Ze&NlBMTDh=1_bWqBXTR{v<-`(quthnzFq)d9#hVq$^a5pHtV*p|YT3 zj6N5}NIQ3|(=6x<-B)w1YVoT!imSyFy~upCBNrNL$st!#CNO`=A<3!FFfF@CQ|e4T z9b8yu9xrp|k4xvx?fL1NKDAh#q7wJ|d%SgSaxwKIhY7~-YY*3%wSv9AiQR1b?+!&u z0@{ChkluY&-i-Bq-oJn;Olk6ZfI8^Fkn?0$Qdts=@kkhJSd_)tN}52|wc+#5%RBYM z=bn{Sxv}L1BEy~rOp)%RfnBT;XUX)vDh=L~xKSyo6+xVL%Olf%G$Agr80r5GEmEf+ zY9b}0ERM{NsYeG#Vvs>}9XPh;ePqIVlvbaS%qKwzJ{>6U=~!+knUNk>WBTx{tQ#Nk zAuFi5QRO~6D|{+PcCf;OfQ`0eAwnn+F&h!WOyZ~k>|3q>JiDQOV!ojEu{U8vM@Qt_ zFM1epYk*c_J0Jk&Ma;!8u$SbV?FVh@OLR2wM75Y8-}2G{|5C1e-vBcNLTf>P7?2l7 zWjnB8yDhh!#*P^`sq#$IC4Zl1<&FDGMVah?yKO8 zV-V(FOh)>VMX(Iyv#YY&u(7+~Ke&|5aAi zvtmNP%(G&}!oDIW&ZFqaK)k4^e)Z`2iFGlZk;T{;3G4Z~Am$UD^!?ZVYhDf}XRM6% zmO5DfHllXgI5i{>Mui&lPr#4wB2SLKg>%UoeHQauU+b&-MGSMzM|zA#=Aw@znlhLc zAF-OO%!VM@1hwTs@|J0trjyF=Y8{dGpQ?GE^sa2EX27%Mux9n3Lckn%Uefa_vD#nH zTbxE78LGokh9bS)8`fFP{pvOGCzJAdVLc0LPhwj}VQs^!ww`lVkhsrJvd8L~j}%fd zHW#lV4P)<#UaO?9K}P%fSm;-yLVg{a$Cwo|E>q92O6$DL&v95D^emt#4r}Ykam%&L zcG9{vXBQsvZUC8gdFFb{MHN>9E5>#Lr!zvbCw+k@w@Q;%F^tknmgO3$z;n4f8QSC2 z=@*$=AGtL>JDdY{3?T0!*?Bz9Bah|fFgtwYt-NKU0@5Lc-H!~(Mtx0&B_JJ8Of`CA z@|v_7R@~wv*)wugtT@9*R?K)YdXn;P`7868zxCG4QJ9(JCnKyz z=C=TuW}Rjo3tQq5&u-abVMPb~EG_q9(=>iQZ(YxbxB8HIzh`;%fm$p7$xRM_@;my| z{K5}x=JqN4G(I4`7a+&2MriginS5i-24tm7BJ;-qQYe$W{E2|%%4A*s7tE&$nQ2?h zobr>swp8Y2g}iTj58p#-3i_C$m&mfh3|hQc_?%-ebpM4taH@1^OSL6Q0v2cBefEWL zcH0R{y!$F=WyL?AKXFLSC^avUR})~?-PIE4U43_;VR0z zumqVwZN=fHK_EWl)_bu=RS`YH4kNSx}zroQ(|ohe0|Yw6Clxr$v)OLiH%I-$o= z9@Y^bdc*X;alpPyUoDa&5i6L)(JX6M3&TaM?(?XwN3t{0h#Yz9AwlJf?8&nm($x0C z%3;pE8<2S1Z{cM(w!GsF^=3A+nD$KPvZOr=*Dpod1s5-R5$ivs)`Nu8k4?Jbr5jiu zb0b19U1Qj9-dh}DFKLS`X{nYM#1C4R+%_~o@c-~ea5Xl^mUIQy1-pJ(T=Dd)C4b1GJ)Z6|U42E7DrUZZ`?G8@jpz zk!4MG_f?%0i}$+glQjsBm0kSG2(b7uA-s5oRgvyj)CIG9>hF5YF1yzWn&Ld5Eg;+Y zukmH_(3}sMY(GgY8poJ|q@-wG{1|X1OD_?dr}227eib8*@{_lVtk^?-DN4X?L|t4H z`%z!JH`eeE?}P!CF3=67NX+x;OV4yAOwz;2 z9f>iwNu+|rTOo<$0f{7#F!_=~5{V&+TmDcRp%#W0LtA2FZ+t0jC9YyX2#Mjo*pLW& z%mULxKNW`M$KTb}(~!Q}iuAD+FjWeX^#!0;=K)vB_ExhPv(6 zW;k|NTG?)U0sDJp!KZS)9>9Q1^)kw-o3m@4ezMDduqLbUV5ONqDBPEF5C%B%(z_{% z`~==F{fB=V|D#|j^h>Y%e-fq_UiT*QnLuy$le^~`nFc?3a$aiklYYE!8s9052flS7 zzAi82TJ0yt=9S=Kq;K9_{4FUipM^gp4do5^aS~TC3D=V1idlF%X{cC^w~_9OF-iOU zYLjV=W7oY1;b;G^)g3jgy}*wmbez=#~$rvk4)nq?~Day#wtZRL9`1^_zRM?Fsb+r zxF0!sM!ie(FUqZ=ck#?wJqhpj8*wD~y_Xv2?A_|^H}ndazP%Ujy@p1}L|BdEsd+?W zQlwb2V_^zr$>D{jF$K`x>$UwZToclN{wUj=V{`O$9A%F%#(sON$<2j#;i;r}(MW72 z%NI>AJu7Fg5xt6(cS2Rl+A$0zG8I&v>I#R*L+t_tH>|HF6;IdIPnIf@O=jTAZdy}6 zu+9#?gIg5&Wzo}P&Yq-tK!^QQ7n1|})=@n#+@?p7?j((OZD48@5`A}a$uA!xM7OPY z3nO{~FN3lj4oQ?o@ixHeyAS*M##7ui!1sJV-vr9HrJX!_cQ!LONM65tL8cN2D^=av zZ5zw0y2}u=`^zp=Ro-J=%ZQ%`RmbYw$H64^{fHZT9~pJegTudvb)yVDD=(^e1hxZu zpGD$1(s)mLq}WkFK5xF~#55btFVGa{_4uP$Cu zVG7WQKMr{~>a<)pH~?XBfg8i%AwwvCB3q{SNef{IIn#x6V2g$f%b+9EjQMtCh_v)c z1#m6J;^F{Vyu>)8Pr5^CsY!G~a=_3hjZwz)X5M|Z4z`1-;EK(H9_XxyI2OG`}5oOTjik{sP9{Segi&&qWbSlkjI8TT$@Rt3q6_l^jEs24#P zGh%sf>(P6y7zfF3_idP27rbyX9vs zabgT^?MT*uh6{}Ng#3<|5m(6M(EX|5j5tqjg6b@pe0BeV@XO%;?*KaYlFSEog`HDq zvsnC;eD=VU@YaFaL8VpmAcNJt(#3XxL_L%=eSa@??vDy;j&lmIL%iC1XoVJ*aYg!C z>Gc9df2j&_Do9>@E9?}Sg}t`j?Qn^O#DzdAA4=EuO8emCC6FBtCFD`=To*QRFubO^ zhwY4bxsMUU{pw;3WQscdur$?e2@N4?*TGfzpI|PPL2ywf@o;ye70#tdKPmLqph)@T z6?;z9*mhR<38sok@p=XFy?x}Qw4t+ty7XJY;AHK4m$Hy9Ol*f3w}d7dXkvvdCo(ej zM1CJg%jC|=q_Dup{Tu?BUpX9qN0wKP#9xvvmHBGX$A}lne^sV1$37xgE5}W11A^06 zkfPxa+BD~$N;M~q;U~dBx_vji;diPoVVXCAljoL?WH&Wjc4_!1c>l7G%v(BBO-buX z=Fu-U$pk}Xx`>Fc3M+H9_i z5x?wJmz?e5X0s`YNwd2VKHbG(nn4oCrK&NoZsO`vc+Rb!1J6Cxcf#|t>Zw}3)Otf% zGn=R%9_^S}n!GZ+Ai26}b$CHuanrKq)r#a%Qpcm;>+Op4_aW@BL)hsd%sqsi7{XeI zu%koR;UVlVL)dEy7GL%oNZZ3>9El~L$}ReY(r;=OFrzLs)pTf87lxNK*_rOb2~GA` zpnD*Vlf1&%Q_mzXZK|=+gJ$J7HD`fJYZz)=$+;Su?BU#~kXa08_QmwziT1$(1U`d| zMjQ(fxL|r_5?o-hI6tUJZhutiH?=m=N@AB8@M@B?tk|e(M%*IEiJXAURh_Hpn40JK zcpe`{;%ONl>XSCh0zB^5`F5ZBbA(LyJ#^@@3@B<&(?AN~EWTOa#(QfVluP1IR(} z`9S>h_h8yjWYsR%tE2==eG3hY>(EM z4=bQgs#nNULWasG!DjNNFd;e(`c0dd4&}IJaz%I$&m*&I7Q%C14Z%mq9V<5D=ZSO0 z7FIiP}}^svsns%~L)4$+)Q{`=+NDmLgw(((d%&rec0HB%*GRh?PnBXOg~h ze9qtD-S=Iv6`EZgC6Ee&K6KL3CmjfU>4lR@_Di09-ZC&^XEoAS0MwC&m8N)~v?-vu zUZ}$pGi&aW;j4uBY=E3vIVxwJ`^@z-DmTa2?3o}ZPsaJXtMm?Ulz@SVm>6Nz0 zWb3MLhFKm)daEr4)z8OhrzryMZYGbeeha@wMm}P|FOpf0R5^AB&31lm9vt!}L;9~F zm?b3Ik#oPj4%X>;K?#OccE#|+;k!^#o4R{6#u>SSK^%=0=>vt{@oXE$^0|T{Jr|_M zw_iNdg(~|&_(r5V8|TymT?kffF!NcU`@W#wu5W9x{{&|kLs0gTuXOfYD_$@24hsW8MAr77(>XI!U1EB2nR!k zn8A>=VC@Dtd4eGc&}DtwA^Xo@$e8Z~viEKKR3QoSgl54f&FV8lvX}OA(5SnW?6nTP{jQn3`DmFcARYFTTaS*5J{rggEkncfLFrI{Sk~4(M+BI(+&f#qCztU1q21;b@ zmpV_HpINR|Bqt=Qj*~D)I^fMAd{PMC62dD(_#+{FM+jdM!rL4VsTC>X#BnmRew8CA z{Q{fX@n!v%`K2;HZ6hfCBa~yN*7_w|pr3XzbZP9Tbb?MyqpFmf&= zelVczLzul91Edt;?sXubF=+LE=@lqB2O#?Z34?MEl;Kb|LYV;N4k*n~HUz>9PeQo` z%JEQc3}_7#pnN(IX~=-`2`I-v`52T7V7uq6e(4d2ZyH)p1dv$Z4@h%*VNB$JG_o%s z{ni_lKI^4?NF>KM7BR}lB)D-RbMa#`aZ?)O3X*#_$;>moWYOjYIFtOx=BXHyA2*L- zz7LS_XJzJ1xmC4AgK;8>*g9MN0=O=h+_iNKet|r_HA}M_>gpY>N4JJ!yqmObI{>kK zvyVKueHxA-`?jaYTlzF`5T_?A5d!flz~5dZXSZ7mX8I1U*e|pSuM17K>*q9`=V6i3 z^Ktfj?E%T^GxOsiuEzOXOEu8PI%`16J;~N=wc{MNGN<-ayQQiF&RuskEKwt0K&l|E z4Tgv5F@u5ZW@14_)!=z6*Y(@Y*e$QL{dQCR?3tUK%3_-6q$l=(G|}IG?CY=H;iu`P zTsOTG1f-0QkV##V#KXBg>vR{2Wx6>=_E4S2N$m4A(ZSxK9W@eJNyqbx$lEV`bjL5z z@VAK=#7&Jw+$T_O1V977E_k;G>TBTL&wzKg?%DCR%ArGyl>3816$su;9=pdL@<)jHHNP*0@tnpkvVpq@(QwRbv@ z4zjcyfSxMga*=tUo<)W=Z;5z|o})FS~bR6a5fZ6Bylr1DXP zsAZs@OXZ_yqZ0%5JSrc9c~ZM8-QlW5TpPfayWu}AOAwa?Wj;U+00uztTXQe`F9l#9 zz!rc;fTsa!0PX^K1Ay{1+=sZw0Gt4?02~I`1F#Wb6@VLn@?rXbUzG*Lp{sD}@2?`% z31OrwZZ(pn_`$;ufH4okDhdN}3Jy6P0L%a*J5W}_dy47+I^jLV2bI$`5Mu^8S3*QU z2OoekAD{quPBoE#>@HyFq*?QXZb?wZza)MEJ+doz}VE9 zYtrrl>RJ=|3a=T_vkCE6ng0Y2{Zz?(w5j7O%-~jmCs&wyUMrmrYo$vHna`F%8&OQN|6gM!fDt-5BZG_)aVxCa>#KEFC_!?LmbL6m(k6n{UT8k1S`M z(d`;(Z3vl%S625w)ev6}?Fx}Ay6pQO@Q*XsIC3_!IXX{`GpCCYur${XLXXrq3f#0a zAL&D#@QtR?31*VmE6YZ#tN=bffy`f0|FOiLWD`>32kmh+SFBOQBrGsYdn z9hG8O9Yp415${LA`@$f(9%VJ!ed+B7>?ux^gQPLfA+Ym+!nUycQO>O|F||z!^&Qbk zN~;%I^?5Q-Y*`iY(uIPK%saa%)&TW7Hg(D*j4Iup;T8I>MVFVz7}B zPPgxO9xK)L&;dVB0?`xjVv-j#0Z%2XV@4VKVNCw-_;7TL0Ac|8$vZLkjA9hLPc=4{ zW67*k-#Eg4eES9F=?aU836@Oc$CxzyI2jr{A?qEbN%VRPz*DlSX}RUSpd>Uw|DbnQ z!i*Q0R~oq^96{1w$-3B)lk-64yMN=pA4ZnO{sYHp-vdEpnbyDiIJXB$Y3dCx<@H5) zuN+5GF6oXPJ~B(yiJXyZ;lTbI;X<*?J5E5-)8uCCI8vQ$>8>{Eq}~u=;+m zFpp0JjUohJ>5U-yYSd``@-VE?3Kq@+q8*){`d$D}x$9BD?fIREm&%ba7VOax`SVU9 zjn>Kow$8Ql?N$)Ff$5SZvg`fP8Haff2f5Xd{ zBUp)8u)1JJKa0AlC2DmFw2)e^0{Sv+58*D}L+&x=Fde>*CC2#-b6g>9W)pKjA(zZ! zn3W0%nr%#GkW5VPVd5$=f%Q>gvb!V~h=eftxMVC4{|XVM zWIPa8Ld077F|#&A{H2QoAyg<@j;L}%0D_#Q%9Fis#QuGy+KYU;1%lPI5ZN&OB>pYQ zC<`$4t;95A3`LbQUb3En&bPHdN@PE`W^bvbJ4xJJKim0osi9Nbvt)D?Vs4hO9fAJa ziDd@2aONx`1(j2>iK>O9;e4;btg#89K}AwH2zoPIWlU&eB^3*K~V4)?fW*uk%g7;8G;>yh zJ75)Ada7+M67gPP9V7iZKn~2b;djVCW{$+m$eo#WadQLR-ZmE_@B#kiRK zYSu`65BX?T&CtxiId7uzpWXoz0-01jlMBg$k2F_L1cLREbJY{s=)e{-ZOL$Am_4^K z807jA5ZZ~%)%|FLxdKVA`6y+o;Q9)HZ?r=m=ojqgdq++X;4neb)&I~)1&wDS8p(qi zNuVM7k|G+35sgmZ207{XNM|tJQc8T()BB2E8Hj+2zaO|TnhtvX@8*3GR; z{(ImhNLBmme&cOh(Hx;pdtuC9K!}vj6PTqcSu-y=d8S$d%@ zEe7Qhl^mRBD!5mzsmm#=S#A*zJC~*$cCc{d#`cU8Po&`1pe(3(Z;^P#nFs305%pd# zRZdWeGOrSkCDZ56#CJ&R{Au`e;+g*w;-`0r4zY4XJG5!c6=TS-x;& z-q*p5h5|Phf^f32W~q~H*xJU4s{EuMnFKKosI!nqf4+e|#v28w^^l_rQ!@VKPwaZz z&hCr19cvdvoT19ie#UHWnDh;M44EcHB)drO!mQX9l|2T_DZ*(cY4>ML>h&|QDL?eU z^s{V)|C}FLx}ct@d24MHaB{%U-+*_*!yJ2Stu7+tBAf0{S^bO;TWq&pX!5S5y97z1 z%10)>P=tlETb2I|S}%GEAZ-5DXI^_~1uG3@nVbzC_SniwZNyFqNHlnsRj~V$Z0-JM z`zoSnum0|1j?v{}h{)VaLid-%{kM-jRwO=tB@S$xYE=23qP{1@w>IGbVDH@EJ_$v49;(RI$m6Q zdcW?+&(rNTQyy(N(VA8HUedS79Q!aheQWK&0KQI)i<4mbCNExqSCQ7mqi`uXv3PP` zSjlaWysGRx#o1X0HnR=LJiX?FUVT12zF&c*X@ENuC(>KfhbvThJxN)TgkK;Nmi!_! ze46TjyyJsjCLeSkr8;f@p`*%6Nzal^wHLydl()+vCE9O%Qg9;aYaauNBSHyQMyfuG z5F|wTl&%1}3a}CK7s{h_3efc1r~$b=N{<|r`+k5oj>>t@lG96bnG+#$W9eMHoD@Hh zWUz#}HkbP{w8^~?@!u>UwGTWrT!t-Pg|;a3XFn`qOj92ueNTEG$cRY{(JvWKfUywK zKln_{>hPj=e3Yi8$3tZ2gXQ|yLU<2*l##ZE$afE}$=({IQ~v8Pirgy;+%N(NOK+XQ zW}68aY4(j2>*SyeN7YjgrRsxnuMgI^bRcxq>}!(a`{?}Pe4DCda!kP#b+ahW;$H5dg~Cu2q#oS1H6U0LD> zO7rX(t4-k^2+CVPXN%&Rjit|nWc{*QlRH%7-0$q@+Nm^I<0Xe?!bJqDj*(6%1NaT4 ze2x1F&k%5((a3aUP&zoc4qwzsUB4K zL3M{pMy!~t=LrNo0FICiD_)HEAXa`9=@P2~n;UIm$brML%dc7qJ?3p%lxhsig)Ryi0+3@}oC zKvSWGTS#dT;*o1BYyp}QUx&QZ0G*;bNZQx+_4q6XQq}_k!$KXQ@}M{Yz(Id#N+gvBVMYnC{@-r5pPfuE5C@^x(rqr6XowPTAgFnqr0DO&MxsrIv{ zQ!PoE;sjVG8viY?{$8#J)3o2lNEhB$+|<0%sTE`4``13QV)axFWz8n+XZ{k9GG#>8mT$71?dK)P_P* zxF)S}oISZ-KRtQnzV-U)`)aL~``6Q>=%R}5G&z{QRIJLM4AKQapC6>>1ATUob^(2A zkbVW|lY{gTpno|?p9lKgLHY{NhX(232&n8+nLDpEP=~6#Q^nF>0z=6cYcjL6mA_LC z3A`JXF^doafDA63ZW?$-OG7+MpRhg(sq$aRV{5bUIP%8Y3X^3Q;^)JS|>{SM05*Y86%E^-YB78sDRbLo~e0UFIjID%s5hb=< zl~c*r^&?ZiQ*U_(9>>`7upClvdY=aSha&edGHl(%s*jf=fx2A;tQ7za0Q4Hn!<+}? zSNy*}30r$SyD_>eQFOV-iCMs17dfM_a2HlQoo$U61Kh{`Waqjv!#$@na&tX8QwapU zfL!1w*Vm2V04hF)BHni>_qL}3!p-^!?_LkyS0Sdsvr{e99q$XGX5e8a>yI7` zO<-Qd(qhuuke6?R@Biq9Xlm)aSP8c;=+_mB1M*_!f)^5w+})nNUKcdXxe^H$fO2xD z!JH6~ixln6G6No;UAI7icPvQ>lCc{`=U+c_{^ofO7gyi7#Qi|u2fC?p`JggqROMng z;>xG1@`r%=b}TI*zu1sDoX-A&FkAU)FB*U-0@*+4n&5zJb;3sE7$7Tr3hMoaOD}Hvg;NKjjL>%QgliIUI!RePLg#Xj&lM$!A z;M7ajK5oPYvhDGaoB_s!)IV{MfeT*D#+9+cYls(CBOwCh7aO;gT|R5*)WaU`3SE%po{Rd5uU-F0QO+IZ2d5qZ4sKYq1|NGlT{p&CPDuFVlVs31N9dm|T9cDJh}``<(81TLQAN@MMCfSU+eZ4Nui!iG2Cg9OmM#j@(U^92b^% zpCV5;j!6j1CzMGV&FAzG+z2^GSl*?O-!xW%M5EH7ZQ8&jA<5ZIZS$Qh?CLdPdZxfj zWOo~BeQpyjB11P{(<14!F4TQ;%S1f<+i@eJw&Cj?i(>Q~tIHT^ymGh|qPvA{dgd`9kt$fcFC-d7D2h&+(IS&9j)_c9Z9t$1^S6 zLG`d8rV0kyS5cGP}ZL`%4OQBhbgH$KE0-Xc2x2^>2qF0^c8r8|Qg?QOO(!mt+x3`VhvgA-UHN(RD8a zO^4eC^s%Luy!-e;xcyJ@lkz9hlaN_cnIz(TL(aKg6vy=OjN+j__YikW-9oGX=QAz_ z*~0P%r?91<8w)hh&^@wIv3AkvgJ)!I=xc)TdRRLQVe#69;R;fj~BV=)mT=V#rh`%ySX3p#Z(5nQZzxEJTZRHOx` zr!t-#C);j@f0Db1+lC^(I1ce20p1FL27lkfx4lq*48HXO zeW#=0)h{?wz9+r0q89Np0gC6q=lO{D%tpKqzzFp&z|=z40>lpom;+D@PysLjzz7fv z@E`z{D}npdJpgq83jme_%mgR|$N+c@fXZQ7z^}%N;!zCEWd?tzVA)(R?+EW%f#a4h zg2n*YkPYpD#Nr5P*cV@vw0J<;02-%&OBH`IM9>>!Il z#Q_A1B{-lkF9-rrG65uliZl8fotG$%pfVFjFyJ6;q<{XCVb&pqd! zd+vVgR(0ogeem%s!JF;TCl5=EnVDrIv$H@J$GWkuj5AgiS;<*sC9_6WZb^@J#a1#F zha-^Dhm!_l(TEw%>`Z%m~P-syh?;u|h%@_{5E!RX4_Yr9)3`PvAomwybB?S{yfU^w_|xX*jNoXI6`YS%=}6gJUC(DjZiF+dK1~ zQt5{6ukq2rGoNSHQXF*~5Zb$Q&;(}vUSihq2-^NUDRv!&pgA};;;6>)-2?>p3l7R; z)=@YLGAUxuHP87XQe^#D^Ss=d^K7Z~xtf1+F7fSlZk6jLUSbVYIyVIPK}-fQBq_ds?UMPsMZL_t}tzp#3o?G#3(OX16LP-%^nZ<_f1!2!xuPg_HPGS*Ww z+{{BwbGdS>kt=UB2Pk{mERF!>b+6fR;Z&ELJ?Rk__=r8}X}?vBGN0wKYyh(dDBIgY ztC+IF!<8Y;OzGWf1ugN!IhbN=Y;0fyer~Wher#Z8ISV{)t>(%Wc~2nk6SuF?bbOA- z+?-UM7_;_PSVgZ)lQX2sqTKPam>$`aZ$G`HTc$<1>XqvQ`H)Aln}){}=Etuv#Rt|E zI^$1CcCMs0L2FrIeo`%E=KVls-4Vm=n{jQ;2`@9ngMmB(;iCD#V=KDL`}EatH4!6A51-zHxV;)zkojj>ggIenZg zo+$&LW3ZL&F>N;OX7Rs$!^ys!9L(Pd3G{4ffLmouxhlJZc|8AFjtSvWA)P$tD9dKc zL8kmeo*csa@PYEe5Ptv6Z@rS;>z>foziERf6=il6WqrKLv@_Mg@7s4XRhp7MC5xuc;W3F%qAmd(F4eCFw1j(j4Qe{Yi-SWHor`Jnj~ zrqs%%op`S?{h{=O5PYbO#kp=*9;G5^Zeei`-hTC{c?VNEd4Fu6u$yYwOGlX!DWC1c zd-Uq%4Rn~J%$v&&}N{siVTE(Gu9BSJ1% zqk|8j7bpu+lA|x!qrFkVurb@~b-&gUiE939bGPHQ*Ofo8ga>cO9}Q7LOd;{E+XIhM z9xMkf$ioo%mCiis-UH1Rc=#8u!;yk)Kkfa~wE)MYA0{g-i2rcf@$3)xJ68R$4P{9k zZSMvyH+1Gtm;;mv9{HgzJh9*A_rg(YH_k9-t2V=c;fA9QvMR=DSFe~-(e@^Wj;02)<3AWWuA)G0;|M{1H6?657o%Zs)Hx7*x-p4#nYHr9_JiU zu{Pa$*`oZ?81FP^@DV5Oum|JwfBT}WmYw|p@%G}dD92B;n=GH*VTsIHHi53UG9rsI z>@;JRoZe1LPM?b1z1OBomu(pq~fO8($3IlCWEbPair%2lrq zT|=qfcYMj8Sq!(c*z$qB9T8}dt6L}EzVJj;_Sga4ieujW++!OS@~+8gzR3!9=9`=! zdO|OloR8tEe?E7HIL9g66rx_mDE+jnZvtB`nw}{indY=KnQoz8`-i0EU#gRo4Xp%W z7tjnQg-qnA-pig56>p?lE>oTGkrt(w=l2Gx_Rl;8e~vj-$^y-&BV}~8+U|Pk^HNc9~-Rbs$m{( zPb|Z@xQ3mj#L1Bq)C)QDGp+r&FkwszKQ%C8;l|g}Z-0@B z7>~Bd34<{Vobk$egLx7!l{XINk91z<9k7H&=dTDu9=CYqUkCFPDb6bo9RgL8w`S51 z{udsUf{eC$y{^=nzC-yFfl|dQH5*3ot-R;4Ru;FlZeqh^#ca*SSW@u{mU*wp38VPO z{Jt9ZC|)W_-bQ(T5^|16FC_8J5*0z@7=B4w*d+fxh9?AD5sBmQY?TvIxPzz2Pp0q@ z(xxW)%@jVrU#t6|*Hp=(dPm!f2PU?<_jzNA?a{rL#1@;B^-XfZSe|4yDPx=D1!MWk zokw}!4w!n8#U5`kDG^O_zythO>7$mK-yh)pxHPIo?wJZ#{?jUtPUWLh2V*upT(`}W zm}pX5rge1Q!DB`{rZ`epNXqZcSe4g3QM7Mis^k4zR{s7S_CHfHYSQD*-tQRgXm!8c zDxZKgB>tpF{yLQ>;HtzUhokb&(A0 zw(Az2WGgptZ27G$(F!oyWaQ6|5;}K|1DZ5 z+e&q#pZ%Av?ktto)KVC3*RA<4-Hl?&Lf5v4?7FO}lCrOZa)+W_1f!}V>22zu_g_T| zUE5;a+5h=3UENu=WEaCO>AKLsB&FcLlyz^_qFvmr>T^#y(@kf$ml%r)&9YVZc7)`H z(}^r01u`|6UiEJz4RNcqRXf{0}_Vkso+MN7^u%Q6tWjaYKd%-6hWD zskU9V#n~=|#f4qy8fUHR5*uj$m*+%1ANWrX%iD{!1{;`FZ+6^n=n~89HyZ+Dn;Qa} zn0st`YF$+BDoIP|j@CiLvW&SLbza#r+)J-}x4~<%m($!eeY% zk3VB-l70(u#{4LmzJ7Z~NPhOI(CjS>qZH1!6oxILbJ+Z@i@K4obpbiM7Dg+Qw5zc9 zB0Be;-)E7nmJ(t}(5l@+dfk8560_E>E%{)97VQTn%Gzwdx)JlZ;rg5*&~zXqvLtHC36R6T=~v;{@_$q1u5C8GfD!o zyzXV*{QMYa`fs+faf-nEMTSz}YZ?%7_;xbe5k zr$3qRsa@_2$Vx%jL-O+u{uRF}&z->El@eOy$V@&|ifNOxGx?5sDC#M*R)Q^t}H&57t6I-P?F^@vv^^b zea#;0?F_?vy z#$++&!$!J_&NAOjLU>dTQ&O7jIp=Tm8fC{_08_ejh!KexZ>lkRYcV1aBc>@rjS;TK z_`O978qMrQsmvahht8A1 zQeQ%NQ3{T9W{;wWwY()022)@26Y%&e4u~=P+n4S2b@mklvye`S>KB z&AZCYllVmbjhr=^Kgi#eH%{go`BQSYJlyLql(X^>I7Z%>$DiQO%Qy4*popC}Gb-yDIo5FiVOl)G&c1M^4-4&ZEUoJHrwno`OZ^;Eyc%K1( zYzjZMKgYDITk7E|yMqrvlWvk=@BZ&hhgtOfs_G_r-xNN$(^Fp4VYEgyXtw;-6h6RJ z+a%%M@BKQo9+OEGJlw?MPJzQMuP+QjNIa5y6Jf{dq{FW-3{-V8ngS5(PjxX1O-dJ& z6rZa6q5RosR}?KzBb#_!>Tl1NH!P$s$dsX8tJ;#19cYcOdfj_rYhzs!G^aPk^jx_2 zai58$b*95b*#WBg9`crlc#kf}8>Pe4>TGJDNv?i~r-dDDG#wu8c&a`O=AsL|?vrxh zRNQ%gEXPmf5m^Ut>*c!L?-*_Ucz@44#vgd_cCTYTM-I1LX&?uy8aFifoc#grS2W_@ zI%*3xK2oEHk&CYc#CY9d@}{ZS2QtZrV0_Rxr1|-L4Cro&RS z&+8)j)>J;7C(BvWaGM$@KQWDu$@$!qutaI_x>HV?b4>Xh^~z$#6`s2hj26kxI??Vi z8poI&Gz!1}xYwQTk+3-sv!q-bm30~J(BxmH@zsMqKTU>UB>&tEX#@-|CqplFFywXL zD{q<3pOF@N<<1ZD-r2vr#~96X-4i9H0oS=WpT(+*!sz-Gu1WT;Pj47qS8IAN`t*jA z-ukoh(uaA1G_g&7{bByl5N~Txj`{a(>4P2So4HKd_Sp?qIQe$!GD-PMoB4QI?FqPL zna!+&AC>z(!XN8#1tUu?Tj!aUw-{3h-8D1i3wg^Ud_d@*F-+yM0sn(U+T;%&;m?Lz zyfdo!A==2uZIg3n@XX**ZG4C6kfdNFer*O{kQdWR{on+)1gZFvYEcr5D-YFj)Fq2j z_ia3hW18JlG4q_i!AD?f$Igykq_NRy`7A0lvDrNiH@{q&(JIfF$)m?MyYKPtEe@~3 zPDE6*dysdSBhFEKy$o|mGKyra(~fYH!n=|EwfQ#0?}7NfS>}XXGm}SQBDg%0$4C>- z%55{T_1x_KXPe!z&Qq4hmG!Oiz*&60RN5xLJd5`Xp4-UKyd`CFW6jZ7m_vA*{GUhp zGY^!t@;LJa39Y&NvG|-_4e>cU8o2UE>#c@up63!7_P?yhwt3bic2m0WcP{h}fQ>ID zWu@n>21!}qkq^%1k-?HO$+HXmphy1uZ2nO2RaD2fIO=!EL+0?UL0@<&ZLWMMe>4Ys z&F^UVhPNi*F>GpE8r_%9I^|AtdBm8?Mk?y>yli*3Dko-@*BTEl2*l9ub${h;Y(R+p zav`&tv1#&+bF*`|b4U8Nv$$)sPNI$8X$5>J0F=g}e zCFN?fqy)EEvI4MIRo{Z~t8BemrR=N?ci%t5X^O*eZ!UMw=PSa9tkquk_g=dF@Ve9F zJ^6e@r@?1U&hOEUV!RCvPWehc?>j2Cec55j`NkPlWy;_2xXJEyho433PgHv$Y?++# zRd~>mAMV(R=pOmr0v-|6`kqh4DNiZjJ@~is69wqmpULYBc$!6Nl9WsG-wJpi>G&D> zdI29g`V@kyn#T1BaJ-Qo@WragxQIcHQK;M6rr#QZ?=@fMv~7c>?D{jFTFQW@I>6Bh za=A&K^f-UOLSZZ9Esyg@2G2bGigS%KB;ys7&A6uM;_r&LIx~8|o__Um7d}NFg73Z*tQ zb=P?#hp{{5`Cj*@?N@(ozxts4s=Wc$@S?N>+JuMV|e?Qg&Oqn9gkOO$+S9v|ci z&;HP}*WN4V>*9x`eqZh?z7S~svPbr=eCcM!@Ll;~2(QC_Qtt)Px67s8kMAl@r&Vmh z*TtVBl!$|@*h_)drziM*xk>@ElQSa`_5hBFIA~AOissma_16#?IrdI&Q}<8pAHv1dAgSq3?O+I494rT{|@(A)ziXIt_zmle^q2 zuX6H%<|a30pg%eJ@XoQwKBY1S=b^jhADsL#K1m*5%%|eCvlve=4$Jo};A{Dda@7L9 zo@dJUFXU;Etz5`U2bkNiF&>v(XTOi{+M95zE(?QJQ!9ntTgP{0Ir?LR>^C{2gh%je z@_-UPY{aLKUb%s}G_LwWHuk2FpL#ksx%ahx)_^rn!mD*V8*<^z<|1a#!%-%0Ea5TT zo7~T}2KQC|00 zOqH4AyzcjLwpMZUudq@+XkuCQn^mbla#J^~R=d;%;W|u`S*ip3kZ(^UE->Pik|csy)?R96j)CEAy1)W`E8HCOM;& z{@m-X@zSkj`ZI$aNlvf(g*I9c{!%x_S(yI@o^#ng?^b0;xU;SBnK(y0Y(Ls&&$pl2 zoBur)Ls4y>h6DL_r^Th3B!fv96<+oZTz0X6rq$Fc=B!A!)a5&^RZZ^Y&Dd#OMw2%= z)7@c#Gv*G?tks-}Qk}`roH^`#LvNVtdOOj`O77IQ%2|aY}LWI*J^VgY6{9Z z@7bJa#ouj-RyFL8O@V4yfEs42O`&v|HT448#3l9Gocir<`A|a(b!@cGu`IBY57*91vEay|CBfD!hEa%x~#Qou{d~pRI z*uB;5_1d`WZsiWWO|6t7|BxKg$Mf8LtMR^nkz1X{#ta>ZJ0!r-%@%{TF8oW3OA zc!ob?vR0?a^H%X|p)Kz0CXzAb^HVi>t8wqzI+NI!p@(i`&DZ-Q))D8@1l1H zL}8B;_k83b zFlso?t6M{(2I9OD=Rr6>iSt8PE?84r+>6ojsm-lyWy-jgR`-NP)Q_jt-M6{b{h!7* z_eYJS#}xU*8lEY6-;>+c@R8D`_vDe!@mQ(4O`i1}_ejq+%G1{Jhxicrf7kM4&gJjc z@J24Or5d3PvpaFh8;I z0@icWH}aVl*3|0Gli%6Mqvp|~MZykj__(}6eIb`r{hwQ5>-U`c&n?Tk^S7+##F&v) zba&9|9@*ksQu^qg7TN+!s->HdR`dpJ->9u`y*YLH93q~-^Y0k4yJu>K(-yc1hQ+mzFD(<6aUKW zvN0*uii25kun@eB<6|>8fWyAVR#Ww5;(CsF*)i%Bv?W_sP4p}LasJq$Iq>E&47sR^b66`~z#(axChc4RIbGUt z)I(0!x^)^R@mdh8DnX+_4(H&UhGQIb&h3)_y$!Dph3=LUw(~#rt(^gvn(Cr0#0GZVG} zq?fsx{)+>pzFi}=SHw)rSBkNf^67!n1L^eM3-l4{s}GtgeH=t5_4P0x2OBs<<;u#M z(SxMdxD;7g^L3o`9(U;$87x{*l*HlC<=`G*dcz1OmB|J%PWV{SA+eDva10bx#+l-e zBaZ19pO|86@g=rHj)<4y{vvP^mERHUsZ9@Hv6WxfX%R9@?PRjwRLk zp<#Yr!I_KE3n$c2$$N^BBq$J<8Th!sl;HBNeuKm*Xk|Fz<4bUcfz|X>xs|QuF7-FCEdXjf}9*UXW;7syGWr$2p|t5`}h+ed7Qv%4g@CoYy;;T zxWvG#{Ot0zXn%m(1}X(si&S7r@VtRPHt;2ZDgJGNDZZzjUA{VHksWhv7MKi_2uuc6 z2u$({fl2<7z$C8}nB;qPc4>|3xE=r|g%bw8XyEGxw)O3p0lR?{1ty11XpHvfOYo#Y z;k>})(5C{Efsy?>CYUKO$yW)imWaS4AByb>oT&Z#s(@Zz0^nn%cRm?0CX4n_klrRD zDakKFP8tK2b2&Z;^V#WsfB9H-k;f9C|{0>cGnpi0T zvwR>?>d$+~A0XBs`e?ZwzI1n3b+p-5MN{0a=t z1K+0^BzdJEzXtgp@Ox+g?IjlDPw+R$=YWR`@i%L7b@XU~!WIN%3ku%~2Cxgst{4p1 zV*Lqphdc~?UW-pT{#1~Y!xsha3;i#_D`@o4JXhb!ts&V%P=$@0srQ5+bF50Yd1JKky+2EQlEpj!Kym+_d|XMoF~XLhWX`3 zAs-K(Ey(u@@>7uS1OG0_cMNZj?_wW9VJ8B_R{N=6fz?6&8Tc{5z|axx2H3Zd-vbU8 z+ED69znn@aL*Sdx9}hmL>T9cttD`zb_*vj4MEC_f8)v-=GLk#$X9^sMAu$U)L~wYy zAnynHlVEk=qkcgit`igzps*h76cVgY>6qZp0#ltQj_oKPY2e!rc9gG3^Re15$bm~* z0OgVRLb^Y~XgHLFS7=aT?Gq0%5Fg*fL$6e-2u_DSF;4CJse(Kc0%8nDE>&S70_d&D zay5d)rh@6!%T5~4B1_swpGmJ~_#LDYu#fjMWgu2yl4lA`@?4dvUn0k(P$4J~Uo=fuFuh34ANa z$$=JuDL$TTv^zxdIDtuyF9=xG{Oct!&7d$_U@}lHFd3*2nB)fqCi!uJNq$jal7H)9 zt_~iu34V`B!74Br7%DKyM+!{xX#$gcw!kDW7ntM~6Y~5ClEM*#!U=&%eo0_5P%kja zS*AQ>jMUFHG}CWabyQ%|n;|gC^93gPI)O?4lE5TCCosuB6&P|C+nm+Wfl31(7nlsP z?2h_aBXp=4^+i0=LvU~`MpSg)bs!F=_`dfXNiMMsX025b>fJR`Ft`nkxi2_URrifI zNrL=x* zF~Q>klYG^rj`H$$*5<{G$sH9k4ZO|3^#;BwFeRwIWr;I2qhF9AdKnYBX>Udy&i=}Zr?RHSj+1rO;> zO=PycI#gCQtn3An*NFm*zK&*bO>?FxE z402*kPC2A^Mtv-?!+}2b?L|oJJmTvgz5OT;`Sjb@O_5Xm2L5)J2$_QX669InS+J@% zxc!2>9`Xa=8G^h;kW-a~PgB!NS5+t=&lk|nl?GIjc++{J&U zJwhRm)#y6Q-=$*%zi6CfQ+FoU>EY0$f}K6HW3uG}ll-K>WcQ4L6$9TEnBt=l^@{WL zg;0Nh>S&z66oKB7#0ejX-9ko*V?i`hG~XrT8A5y-DaM1zQN7}(wadHUE8W<2rUywl zF-cxCUh3wWhP!=w=0wjL^f=D;I1=juU3&hcMu7&|E)(Qau(3hUt;G1N1bHt+q-R)S z{B?f0i}i(s9(IWaHv1J=H01OkOf;}VkjFtl56r~)`vv(ukkf;+P$7fI+vVDZ%Zc^? zU$gjFV9N2Q2EHyZ)f&B$iW5E(bE6iB<3Lnv!^v~)qxaA7M>T!Av7%~=K!8|nak>KJ z<6vMg*w>kSRZt?xsc7i2AEl#L;c`JvRZNcy#S$vlG`7=zfzD>71MJ{G5$fHoR(mi0--<;F+~H%1p{#q(8EsAz!^bKbxaREY0A}0 z;G7`Oh5UVRh9Ec3rYcaEfD)Sr1$uWEr*;FOssaKKLRDiEnCg7Cz$AAXc&~xKHSld> zHGM4s`y78Gq6B6LObN_3@IeEIKjx25`uPGcLe4US}g_W zt#&09h4#@~ZINJ5&9Q;k8Tg2S>kZ823O80{Fm`Uo9Ap}}+`#({d`4h(FvX*0Umko_ zxLjb8Z+_g>QDLv3Kn~dp{qnUa5qhB*>j<@9lL2C!@R8US$m<39AHi1zCVgU69r}l< zgthW-zyH`FBzOV}JHg`4?@2-aSIAEpX%7lnWy;PG4Fp-|L4z9h)W;LifLLSO&rjZ_ij zq#r)7V~%4xFv>qp2%rdf^R2y(i0Q=}obd6jHtFRF6~PwtC*nk5aY-)(>2lR!q0W0# z|Ii<$$@nOll)_WN&cz8B=@v47CbNA#lx0%1>Z=? z7Wi{S2F(Vx3cT$u_H2T@67n#xI*#c($%%pjd6>JfV}d0Dll+LlT*!NJNcck>KB{Dd}r=ZHo;B0~a1ATh0YMLtbtx=B%a?(F8a4YobeJmPY$N{o{ zT9x;~6#^*2IUxcmSmnk%t@CG=`fGzk^cEIQ`1r=abJ{y##DN&Rh-u3}-)FlZ$h$&L zEXwNzc|XXBHF-1}i~t1zj|qb+F(pq4E|Nc*DD`*U2Q_-H-;O|9(u@Ps8(_2u)Hk!~ zy8u9ZB$kIO;#iO_r|$`&w%K1Du;u9_I2cw{s2}4Rbq-k2|S03bKr3r zlL7i>1Wx!!>;SHab^SBA2nEwaFp7Uk(l2#wl?7Cne8VWbS zHcr*+E1v7};Az^d!EB3v>seKSPO z9sIl(c_F3%y;qkB@>Ix)&k6Eep>aDPC(cymXspu_pnvq%{H?(OMPMp{+XAa?X?e#I z3>TQ>Ndi;+6rJ_Pxzx(vkocTHYk)l<@fmcyCkqm zkdwnN2~7632~6_+2F7aIuHEKX*;XV#0lp#H%Kmtl1P>YvoEMl9{8(U0(E30A43Ior zV3N-!ru0x%01_`HF?6_^a- zj?j)1KECDFB?Hqd^Qsu~1Z03%UtT4-5U>sb`Y=KUiS-D?M=-4TSYnybCl=Q|^zAEM z{t)EEw1KLxo4ys~k3vqY%U$?stoDyS(%%+xxCrt)U>eu-Y0|pZpCA=+sKDefTh~!; z7MSF@>)YiHR&f^xHv1LSx$mUFl;9bG$>3Fa=PYe8Y}?RoTb(qz3rwmh0+Xp!fl2NZ znB*k_ll)VGNq)i4zC~v0^Bo16POIl5Lk6UVATPENxn*8l9#tL=512g+#cW? zK(-lpzrfq>Quy5~{2ADF7kP>xR~^(@zgt|V2cW@_!VUwUH1N*`wr%t~K=E@8eAU3+ zU-0RpFZ&W4ss-qrX<(;;D-C?!z~&b_Ihd7tfV?s9P4@U+Ng4MBo$t2u$yA zF9~wW@n(UkN_PlM@=Ae8e#Fn?)FMCb5Aby$fyuxbfyuymfop?hN50hWJ_^4mgj2kF zfl1Cbb;kD@GW}Mj81ICE z={GP%xkqPtm_zCoK)zJGBA|(oEDdy55O`!q`JxYDIq!eKn_!Hbspe$)+MfzvJ#j}08)Wjcw#RUJ)z?VYMXa~&m?MP9CpPl?*En?Y{FtGE*}m+$b&U93L>#3C9D{s?n%s%GGRgFFqq zDbp{{0$a?!Mny&Xh(W&q{23g6NwfD9_?`$o!x*$*MgV=|^-WD-Cs_Z+r;P=%{{{2u zzQr&lZ~`nk{GNgTYT&QH^i^!i5Vd*>#zgvBHa!`Ora?O%0rgt9z<06PgW%dl{#Ks{ z-jm}m(s|(NX!W$$O%9cUt0pq_>#xMmf$2XD&>bi7i(t{=?E<^Vqy0hv@lgYx2IHgl zTN`H955e^N`4m8{{u40%Rf8rsu`hl4Y9#8K^3ugQmkMSJ%d z_(AZ^&e-@$7;g*U{YKTH*GL}& zi{9wo0$)az(Jds!e-A7=^s$e9uWge9bq0lR41CqVzZ%$MU?~jW8H)7n)sq83;Cs-E z^eX8CuAPg0g_BtRk-}gEypN?zrsnY|u;}pv2F?WU!O~dI@pNz)=8iZm{ycE9J}^m` z{lN5IWC`TdYn}#=a-oRKT7(S<*ooUByT&`gs2f6NV*%_Pa9uibq&a*BOg{^tJNzkl zQ$J=s0)5KRTzJyB#5d3o{~PjOF!DJyc`Mj;LmPP1BEoZxD!5j!DMW(lpPCHScmTKu z92}_eJ>VN?M6`aUDoh89C6;U8hYeiZ75#5mUuLb)46ZjQybO*&E2pQ<Ce=_O|7WD@j_+IdK49ytt)C?uN5Wt1$G8_C0idb)@1>h<)vQRBT zDYz8dn>4>uk*@%Y39d2liw52frhh1-SE=id2%tuW-h);d$le53t@3x9TJT^ee%)4c z;1lr8nf^vw2NoUp22B6NMo-`x_%l>Vq848P*ZU{Ce$0gaBO2%g9*d!II7N_eF2r_a zCu}u&wD|WyoP|c7p>Zbo5Nd3*#xudysA7GbS_1wE`B|mO*MjfBe|=oq0v40sZQujl z(MI(jim)*gdj|?ZsB)atDtsRo>VL}t+wgk=Ux2IOf2t<`CpZgpjXsy%0WX2WR!!al z799xafm{7beKNi2jp$)$qcKpRU;Ch5N1b8}c(pJ!JOUOC7J!p67bR%=%fRbVLP%GQ zzuut#2k;tU`LNT4fCC87XV-n;zWTrh2dWJQ&VuRQjXqQ&pMkdvbJ@SZm(%=JieFb? z^kXY=(5DP3;46!n^{U1$3A5nd_96*oJ-|QXeui=oh6vGMF~>s@$pS(Dx-9|T{^ z@K;ebc>84E*ICJd8Q`5LA#J(fVon5nr!`vYbx(oU2)%YKn0_*5q~`G!@Fw(HePrJO z79HFNrdQ%i)C^eJ0q_#c-n1kn2abSe=IH}5)~F{D&;wJ2-iZDNu8#Ci74={-fg9k} zxN*{3xfw5*it5#27o7mvxFj>1*Y$0Ow)3d501bJ zOe;e6q#?cwJQ#HxtvRs6Ab%aKPc7;iwFUw7yB=gP3J!b%zKJ^02g++;`WIVztNs-% z=GbFkj-t8p2fuy@_!-`K-flR9jzA`SpBvX_w|Cq;48vx zeF99sU8Jwj&Vcu!&FCfcDR_DN@*<_7Und`gHm#cn=~J zX$c$viw++HCkJXnD;CYQ2KisXST9fkV7(B^E`zf$yXxKEb=45zS8&}1|FYi=zJq}x zR%`X9z8xJ11?wN$zvv21?(fgQAn+;NhUl$68Qd4$R-2ApYzhKs8@wD=sE+1<#T-6i z;3eS8m|pb~ssQ&u3F?h@EBG_?q6@G`z2J3l6dcfd#UZfYKIZ>-5r9{4)gMQo2jFM~zZIFDd?Rc+e2xZE#~Q?&dXz{%Vld8TcD;EM`Bd61wmC*&x3IrhR@?p$iHUYeT?# zd$-lztG>19P~=45Y}L4OQ53RRe*Wgw?r?((fjrnd+9 zcrKX!4XNJ9oZ!#Uh*oI^@C!j~B3kigjbApz-vPEP@ZU$g1}?>HsXL5c5b|Zn1p~As zdK&?qFuS3*sjc>1@SIZLJL6PEe*+g|des+|SHNP4{9s@O{FX31b2|(NF#3yeAb^GA zisHK{fE|bC6vn=p6VZY)@umz1wFTrQQqQlRF@65*h zuPf|Cz+l|l=|yxHT>FIYr`V_jPJ)*}K9c!L=+;#{zp;B@f&z5Nc( z0UruNBgA)&NWYZit}=hCf8JnV3%D3L(uPX54_ttOB~(lBT`>JGT)hO(gGZr_bk*c_ z#LxIwOxM7Jg*NsJ*hN2Ts;|pUxML7=&?=GYVDvkr`oL2Ug-_tIo`46uzQW%qLt-%bpw6)pQ|mAm z+@P(1s23%JMTf_Mt5M`M5>lP#fj6RCU)1<GIZmT!K2=F`%?RvM20#Cv8o$7PI#qL8u5Qa*<4Sc1t0P6yW_!`KP%)lsfNVLCV&t^5cK zl7o+fZ#w-;uH^>(XTh6<1<4EGAULdNU>_L0O8wBbT{X!kKu+^7CGZ{s=y#>5kx-HT zgCew#Q~~T~a3{2KbYoTjHdxGID|i?hRf^V2f(M~dVvVTJrZM1;FtF)WoC2o!l)jpv z0|E5U(RGjW$Uqn0Ktc}91Jn0Es7=rks|0)n{T?-@I^+V24po3l(Ma_L%T}-jy+F7B z7Wmp^%>R0;{s;m1-B9&IMf5FrU$%c0`y;p%tk3^$a1Y$7J*+tpf-yV-cS@5q4hK)c z>_|MPBu?^qd^?2dR&(bY5v;X<0%c!$s-hr{>8={~!&masNSDz~$mC(t{{yRXnWuW;eqd4+{@=Pg~jc(vg}3SyFiKx${;O7p<7PYdWL|d!*xC;Pc$#Wt8W+%L?Ytlk4|L-}_xmD=ArA zSo6VaQj*CS=-G$=aa418zx1%V#&Jj*z{9AlGK!ZKJYF*I;dzD27cZ3;yeSog6*?cD zHeufKX~m`UrY-)XD|-5i?Zi%rUwv_ zl^ny4zOhbUIP!g{u~E1Q2R((4g`Qa+c2xQwzFdwvhTqmWb5sfqqMf-F(RfEjt~)CA zx6mqbx!m^{eqcNFm=x;gm>?33d_rQM%2~&x{=xJxqOuZChzsSV$E0W&-F{3OB)uOk zzjsU;7;qal!@2w;M4duoCAJxBRXkW^pUV-)r9PI*=Op&DoP1o0vGhEQJ6&?D+y4jZ CQ9|+n delta 32048 zcmZvl3s_Xu+Q--0Gr)+bqoU${U{F!az)PZO4u}&1DwdX-1`6nqXsB3rvWD`KmKK(} z)I1&Say~69$vmiuTIo5}m*+^?Ir^P0SQ%PcW2rM-=lj3=!YuaV_Sww-t^d2;b=m8- zFEj4{Ch~esWVs`5<=YBlRu(p#IamZsV4Ybf#u+PdZRO0hmDyZdH>JgSGqy5Ddl;jQ zlLcdOh#AKm2)CUB(jHFXy6zB+VYksvp*0@fNNyZ}M(=g%4G#=wo!`-ZEyZ!X8@&hJ4DSda5~){i;DeWx0tDwyw20qz^pzMZ-`1gs4y2a}wu{^+=_ zTZYBcwj#{8u!%XlWKOyMrzM>;kh3OH6Tt`FKf8XYGe0kJg(WefI^UCcSaERQJ@v3! zmY z_fDOa*swi!x!(>%Co$hE!LGIa+#EjoHOFVY?0G9K;yl&;Nzu@jkKi*!auh!95(}bu z@7U|8A9GzObx)^*-rb;Wu?Y7Il zDR18x_e6v{)x+Zk?NNM5qO%<>^+_?(&JT8t@crKOYERoQ;k@gfDT5M@Pl=20U2YOe zM?NT0c^-W|o;j==#T^~_kmO-a`|Hbmt~TNO?Nud6mG%4ey(AQ%L(_~37MtYeBbcvy zlkG5blvF9Gr!8VjN8UF*%=cz9^KEU8In4ScxF_!SRTa4hWhlPosK%`7f!PkX;`>W5 z0U-*M`H|My|ME7PP~0Y)PTdTF`4ek z=@GuTIPreHl_hwFty`65J8$*%3nqH3>3rDxH`utu zyx+e>a>v~?!C|-hE*%$nJ$ct`tFP!dX0)sxp0KQ*>t61$Dor_WPq+G-k0JASlP$$b zp=L8_U`2w*kzREv#bxz{AE#rh&xa=e$C(uPX2ZotJu&%Mhl`s%`IE}YjpC7B7zobx z;z#)~v8gxjJbEC`;{R4NN7bdkD(+~gwZgZO)nf(r5~S8rb%BH3v%BN0KH3=T#yIW! zOQZOf6*5*nX{bx{q{Eb$eD&HO3t7pT2PYD{0ribh)iQOTGAcAX;`=lZYC` zQ}}5yVGzH+{m7<%OITdqijFAR^d|A~-1O#jhX8JWoc&fDxnv6_NG@2<-8 zgZY98W#99aX~X%8yz2uEEaAoKNwrgaR$C^z$3Eos@blv55&RRrwer9ne37E$){D4N zC?_JhNAYq+`6M9D-O0}>4+O+}WB8EB!HCokdoM&B!`*zRNFK|FDI)@6{#ZW0PqW_^ zunci{gaygJm4&H#PwJbUqmB=_<1Z(LC?P!6#ehw&$r(ad@uaovn+mpt>Swl zC_cK2|EjF7uY7MD@57b4I`M@IS((x-Zo2qr$JIKP@K*KaKvI&$=e4Y+&u!c}+CA0n zTA}!k)QOx_-bd-wEJ{*&91`i>EVicdAvlU|7N4Z@!8p3oBm${?IF4$XL{b|6L|ND* z>eKiPhofnfJ7G`IAKicvG9kNq(2lMz???+jV~bC~KsT;QEFI6^$QTgtRM2R7uc()U9u8(4}1TlHGtzlig+cHr-c>2 zi1sfoX7X|OswNYZ8TNze#o-f!{zbvOJf|n^cYDcrpT*+LtGZ-&abHGNS&wkW2L=wh zi`!0VQ@z|1IdQBj=)W%*Hh#kOvgyn70#&7+@QGs(mMtF5;{V}ah$-3p1LbUkh?>L) zEB+=idJ>-;UDc4}w$LoOYP6egcPvtT?>C5@lemk&A-TIdX`RQ}`rnliyJ%)=lAe;K))Z zKEjcuZNq9YZWiw%>^b}%Z)2nNS~O#unRCi@w$wS1`9vKZ#Z9zcOF?*S7S^5hj;xcH zyNz&QdSbpGTE*yv7*DD(dgw8_BZj}OyBZ@#jq#ZlLrtN}M5N^_tc%W~R66JAk(lq> zx{hiT%l;&cXpJd2TNiGGxkfXG%f%eXhK;2&muD1s4E8kUNT#q1<~mDZcQHpQ*d>yu z^4Hpx;-r!bGCwOWOy$q&n9sYr! zc<5fjsDc2c;#LmmvVbBzbG+1e{O>NHO~V* zU(2&#DsOjwsQcZXd{d*}5#-xPyK6kjh~Gnvf4P=oM+ZgVUY^MZi}BO=Bz{9|n#RZR zuSE4UzMhwh2c~0fxkhZ7j=<@ndOBZ#HT0s}v zT9&NYZ*>R#kJYm{hr1(=j$sl1)l$n_wpa(~yx4mm@7eEv>thbTo@Lq5+4WY1!_E5z z{p;!#r*p~33zoN7+(^~*u(*65AK0!uXn70mObuEm`rgm`jl5j1p!0rMjRs+{sKV3r zEa5OXChXOPZ4i=(r2dVtcdM1RUR@ZW+LVaL@8>-iJXyyRT)#h4R=be;5%al&Hnkm$ za-%J64f;PvwDr{~7JhnnZcbsuVak!UQc}2^75T& z-s=P2wY)XRJy4BTEjG^JJ!4Kae^X2ITIag8wNJ)*V-wszEwuQ44u}&ocy#Zv$iN@f z2i8AuNp=a4nalE-6rw#1N0=&^)7p@1@o7J56Hq9G(#=n)o)$Ud6YjN&Ga2 zKQw4fBQ=Bfo0)pGn^J|UVBGiWQSNlbu~=ICvp~|Fjebmce|nJjifr^>u0z}R?P(Od z9^`Rj8~tC_?JA0?z*080(SN!w*`467x>SMzem!bwmB)c_i;s6EPpk6mNsayw5MP@D ztRnazkL9r5q*mXd+)6M=O(QAw_Vb#|kFHDav}l;m*VSB+wE zE}tJ))s*jf*>m9V=0I6eXJ1~}h%*e0QSrSS&_4eXsJxkrNq|olBj@tRV@@>k1nU_E zO*s19#H<~)iCNofx$l1(#by@XK`yY(fp zbRK`PjWbB8a9?N9E+025EIR(tTsb)(cSUB_`&S;pg|j0nE9u}jo~&NaV1VgxCehs{ z(}ThPZzxUBe<8?T?p#59sBX_g5g4(9{{IB)YAN2P2ay)m+yC{HqmX_Iz8!~u`=eu-1AoI-CB;1r8)^{fO%$^FTuJ825Hqe|wBl4$u0pXH-R+Cnj%JUgx~=c~)G0|Deax z;%vh@sE0?%%hBU~Bp#oS6b^{(^Lc7mO1PO6WeoJp%0}tp4}f$lI;wIbCtaL^&%(!3Mf`4jd|JeB z$46Ze9~Ch=%k_J3$tW@EA>P+JG^Bl8FKBOOS!0~(f@g5xS(~nQ$_^P@%>*q7NXbo1?0Q_%k}v3wyP z$cKu*EaVg861FhgG+g_9jVrd2gFE(zxoz%fH{Z*A9|icH2LGK6BC?pLwcj4lMlSe2 z?#mFfiuq`Mzt~dDM|EU%e47&6E)zF#0_`$_{$Ap{V&1LSPr=`7wR?M(jAnmR@R!<^ zNMo0JWhgo=;&)_!GM70h?HLH0hkXflxSg4xJ#;rx(6b3 zkvh9^$4&GGI{jhpD1<&zFE%gY>Gs=>^cymyIwCF=qho_VrCwZG#QR$t{LXsOX)zz# zJ_DttRC4i|vqjvqm_Nw-i;BhkUVMZ-j5}N}i0u#aRru&#!q@O@@mdK_g?6!oFB-R^ zi7pF9RXgtBJ9Z8Eqk1C7rNwI4?bUq8M0a1@GMf+1`@rE2({3jX{Ir@QFUpJDH&bj{ z!jp%&VDQal48I8n&t&3i5Jjw^&j$a@!0B2nU50F}-d?&83H3iJv(7)WK@3{P|F4s+5d9~u11p=#S-G<Rb>PQ(zyDt6|TU|f5s*^jeWa}Ro%+au9vi5S4xU)S zH>RIEWo+d&ID{zJ_)AK|v@@%>`c)BJHhT69>&FNQPUmxtN$zpdtX z@GjpsPw|yu&iWRg%%#m==S0>T+@!#LVl>@t;_w>Y4{%t8iyFM9LdUhLvQdSx8a%2( z(ORAx#(e2j+r;U$e36&=+EVy@Eo+Vb!A)A$n0jGN*=_X4>Dj$`l&-zBuoyk;%2B!& z)56;8Vc#F6OE=p=<{PDZJCA#~;kXlM!_s0{AUrk#GyCoMw9UjpA`aT%a{xXg@#(~8 zH+=TRX97NZ2HM2_37_5YnT*fQfrwbTo!uc2726-5ZSgq(pAq=H2XiIWEI%ZEy@wC! zL$m*aCgyv$vB`h2uF1a&`v(n8{*Cp`{;Bn1=sG@GsXQ*8UdM+k<;TULbv#~K6cpdC z;{oNPMsaRER=?ki#Ao>^epnPf%Lgc1n#J?aLjAd+a@})0ob%P;o3o;ECRNUps zrY8U8dW^{1733aQI4ElQeDT*u_$#<0F{WN*Jj&y{GiO+4cQ+qqPyFaI>!@6_DS>KA zb(^Rv=SBA=)wj%)QOwosKXHgBq#WlC8keXWtq3F?rn8Eh?Y^i$+1=M`X<$;aVm!zH zc;E$c6oX;Hb}$_0{yyBPZ1Q^>vGN|IC!}xV_+CnNqQ_F<#B(;*=6Ek;t;yg1s93j&AHD5bduH3% zf!W4(WVTcIT!WqI+f``W!ONjt#_^5HB`@;-SVhJ*9`BtvpV=m1A3GHW)0nL~huP|| z$AS;zlY9)E&TL(moh4wxAA$r=8?L;8uC}nVP*FaSkDv zq8biq0K^koHemrWfI?lv{uTD|u=#PbIJSdlDoI-e9z^}M_wrfD>>Or0kDZdpMhl~z ze9ac8U&gvLVR6vQ55)2hp4%FyME9qgjPJaY`R+ z`W9w;DVE1rSKwUYAWxLWDdp{=C=RxD&*54}TyQGg+Btw5fN}Ut7k_ptJ-cV%kTwT) zib1>|CU$WxPU*&1h&E0ok(SC%WtjaO#1jzP<1@9rZI#GzDlxdt$k>_Z#A2rsXHUSf z4;I5=k=EX}nk=HdF`yhMv?X9qZEs&?U2R#TJkOb|B|%GTZ(nU)V_8dDJecCeZ$ODP z&4@QW@}H+pe%zj=wMDq>g9-p2h8-1ZwCbc3PUu8ZDUHmSnY32AS_}PpDU7W~bjpvM zcQPey4>YUz5LFyL1GsO4IObG(gs;HyCmY1KIBv5I$LC+UZ5dm|J@Lw2Y4q@y z*rGRnT90VlhCb9+8#InIG1V<}frlE(D_n7Htz6n)ImW$)M=VZQ7|stdodXW;0;b38 z_)wXA5aR=zjS*j$*a<_G@k#N=6FXbSC#KkXe1!!>MS_xOUjkcWv$AVJ@pXbS+lRyiAgWhnA*Qq<@DqpfX&8gsFi~;Z>!?~MW83|_`qgkH=q+IfM}c`ot~rP z1DlOCLnk(d**2Iv=!rUlTkMG$8=yrX2kNT^gmBOe5r}Edp#=Jg+lDB8`5j`?5XI>| zDGebmm=M$C$WfGgD2l!rBS^Wa?1vz{Ha?BIq$mBF9>G>4oR|{83u^2|h0dA286{jPWnd>F7@MK5 zmh|1w*MRBd(hxi8|&x5J;82){d?mY*CYY31NuscGhpayzJ@DRy?OVTexPX*Juj}o9$SR(0E zBc&3*h@31B*=u9w9?9S)9PS0*p*ti8HIm*8{Q~$H50z+FTqwhBu?E@=9xBB@E9qUJ ze+AA|b$!fqI71F%VGs+J9ZZw-+n`SepVSke65HcL@hQVG65j#)?%)-=J?Z6!PGe>| z3^pNPh+ZOc_`YEPogy4E@riz+1hWzULvXp2Ku-UVJ`MU*aJW=sGX`k7I%dv>!At}s zNe`;xv6`a$rUlAbqEjjxTFFT!9h0=7y9 z0nI=S*#W%{ybGU3Ba0p!$^g}nLt?7I^4nVL+a&%U_}LEro~z~8O0@F!P=xnk@B|n) zd|FDJk`&UbppOFQNcuWS{|EH-;MtP?qojWU{UZ3LR(>r5UnhqW_!}QW5+B?1}NwV!z8P z8O(*U3yc9yHJA^kSFg%cR#-8Z-rs7c^D^?JZ^q=5kRHk))j)y7R0AG~N%wA$0?43T zVlw#L#4!_ECqS=3!3>+iyvPvo@2C=5KTv#nMM{;yYoQZUuhMldE8Y|`*a!oaB?n(g z8K4aQTjG~)Q3DPsgS(-}f)fzWXr$?q-X7}@mLUb~M}&!BV>Y7%S4ujSXs5)a@0XZ# zpTwj$N=*82cc{SassG{4;+85RgV_?3gFJ~z-z+idyG*>##Ai%=Nn$TKh`u|N0b-ZL z|3HnTg5`l`m!$s)eK&Xr;u&+p8A&I9cnPyr0gr}QoBvOQ0@OycVPYr(IVhKyYG7Js zYkh`^UpKMO#MfIG^FKLM->t(Z_1k)sh+e@%aa#JR%DPVW0X#ua5%y8|MhY>awb;{Z zdz!AWzR-y&fLi_S+BaBK+3M9V%WS zF6`-TG}(TPuE$am6u~7$C_)5!T}_Q3J{^tAge3@?iXdYhNof{HQOJcyV$$)NL`x-* zo*^;mKT1scb%{x*+o1TshG~id=ot+moh4#=K0`#j0U4y%@lc$Wv!JrB3)1mwUMrng z*Iy+auj#eYiPa6$)Z1j>G8qu7n~fbNJ-s6u(@i?Du2X^N#XyY}RuQ2w)i{5<(HaQgGTj(4-3r0q>nJwu*L7xMjA?fc+I-PPAG$vz%+?}yG4NxNxGULjcJ(FG7vBsIHtBvV2s36rO|lYfDde1{1k~vFOirM zEH&{Sl_`DQ!9K}=9GsAt9Go<9jl^V6uhHQHo5Jc)1H|zl8X7om#TlD%iW@1unm!C@ zXlOzJC1jlAsOcex?csnPmXIGqkCyaEv?hAULic+O-682+5Ro3Z$ng`vTKb66tDE+u zMs_e8XwEV2q?YA<)wuIevzuCqSnsKXUw>>C!TB2o!omBs-WbIT!|=9u?6Y zdZUCMNvE1CmY7aSnZ%^8Hu0|M(lU`E&`XW@z^1S!oD$*$5S_ym%DTQ8=kSc=kWOJW zSU!a{l0FgfFM!kF!ze(!SAVEQL3EDkK^LWC7z~zlI>+>YOs=66NvCs656k5EE=i|T zOb^-Q_}*;EfX*>Jag!ZPlXN=A^khzUkSFO0(CMk29N#19bc*Teo)q89N+kn2$Ml$w zW?Z8NR!I6i&>sV*OZrhsUkIJv{lrI0{F9PSr{)uh+fx6FzCU!%$-rUa87AIr;(aDQ zCo#1t`;6B9qh+T4mnR2+&zLx7X2?M)ik6NWU6@1AC?nL_lHPa)V$&KevC(L~R2BMW zG}>O0KXsYtkOHU%#+bOk#M?}K$i!cpn9T}hko>2FSX(B}4h5)dmQsnS3LSG=I~Xi6 z=@}AJ0y9i}PU7`cBY0|zR> zc`)Sf2=u97`9@rcq0{_-8U{;D2IYnU^zWe4>#bwd>}j*z=aNn(zG7mZ#8g93xuFb^ zy|fWI+P}gq)SUIrXr+5h z5za_V8Ti`7H734p;^@3k4NwN+Ri^ay8laa?h-lGC2J|`sk;=#*aS|GVasQcKicw|V zo?Z&pSkd~Y2Fxf>f|LO&z-(eQeLVx~Oa|p9-X$?*@N0?5VU3BenAkcultGH$3#_G& z43GndWI#MzVv3L>G3nDxTrBb6Tb$B$l0FRj`nj0@2f>liNZywW#>3zsSiW6+MbdMi zUj-YhUdo_rUZ{kW!E}j>VLt(!qo+sq8|HaiN7yVyAP0LSrU>@@*7ng7lYUm>RY=g- zj5hGKq?0}K7PNL~HL*=%ijXZaWiUr#(l<*?`ZkG4KPmBx$e@1yG2-dhtDi^)UE(Pms#6r+t!e38YPlsQ(|D=# z?L#ue!@0I_J8_F_O_Sn(3Z35fG42hKzm*|fo1)f*0@yi3SP#yIq0w~DO8RB!^x{x2 zT_=ZEB%KQ2llTVg>1Cs7lD%tzQQ*6^&Y9j4fbkM_L2oG)ND(GWIwdeoV#>fyu_P0f zNrzvXBziRo!PvBskKUJ35!?<*5z{RLuIqawJq9|ltQ#*@k-vE8#JV2GZbtyUF#e!4 zloA^WmWnx(mA>9FFq?*j4u#V~XCjzhi=w5Wev6UOd+1s;h24iE;&@4?chn6%4@bnZ zPTy`ebgGxnL#*AGpqJ?lgNJZLOaYXEbvXDDJYHvVKri7N_HW^c*s%Wy2T9;gy8XAh zCD|LD&)0Hd^v74dJRygaz&VM3y_Ew=zX|;sSZ;;3qL4poBvBGa;oYHj;B+>#MyzMc{2YCo3ff2{3p9Z0B0Xrvz3Ox6Z%@6K^*0PKhbLPhzUUMwNTw z2sJ7(LsNg`hfQej3Qufz_78yz=8(%sOBPe?j_-2jM9VcF2tuOEP@ zy*~gpHndl7kn)yd%0RZnq~}OX8O&Q8N`UlIiAmoqG3nbRCjD#+kJKusrX@h*>n658 z97>QJWQe&r7+s2`U`nS%Vlpc?F?~k@!PsofgNh)gnxcwb0X~F^!_~Q3QBSt6D7Bt8 zOa73amz``Kz@ke+`J@abnRuPV8*h=oHc6)f?2(xK?Uz`+>OIja04p1*gxin+u{PG) z*c-P<@T4hz%97Rv7-M3W#BFJa`9uoXcZ&qRmh>agzX8ib*>w>+72V)dNOh3zgG*yB z&RH7D%Q@&%!O@alAnEGamY6DQkHn+{HWnTvp*`ag4;7y;DBWR{)&)&XXppP zc6we*^8{7N$;U$mRKl|olYUNO(l1F&`V|vfSBCtN-pjk)DVW5F2Zj5#ZTiqeoK)iOJgVcVn1&cSg_K^Ns;ldF?GzM95y&9tiBN)6h0`P^ zedm)Qea$U0P$TJNk88!20+PQdV(t1t%h7O?L5jp`jwL1s1rn3KL1NO&B_{ol#H1eu zYw7D%(yOd>4jmGcgK~+omWzzj?GWgtNa7JR%Ya}KIKbrWu z#G7t$N(!C|6>yuX>*Y5ZO}S+7$}Joml61G zvmGrl=`j+Mo**&lgC!u2*+k)r*Dzq=9UQBh_FXua=72b=Om^K9D1g8jUF}FxEv{#GVp)M0I>rRIpWpc zB17rxLJn_0p8%%&xW+t~A?cKXlM-7fK;Q5JjP{=WS;>G(R3kCjPg@^Kkn|ZQE|!?= z&&n(%Xry;e)2W+lRr;e8A^H{(E=fAcgP#p$hM&0R zcaVj?895woN+3sKs)1<|Q}oRelm5EIq+gPFoRJ=t-$*bZ8IW#&u5}6N%c2OzW@D2K z2OuMUw8=h4V#?5Li7EPOaLY6^>lO~_>sYYErm%ur==A+8LtlIgeZQoWeALAF8sVJ| z&4GfXsatnv_g)Sq(|7k0pd_d{r-G2)^pJaFB7JB@KkRPfU`o5Lnm(0r~ z{`eO0=?hl6{dl!;y&eisSB>;7E5qUGTR7M!>Hlsk9-NJWe0K{w`Wlwu=dwvBr0=d8 z`psMDrMS_g=@BdleFZoV0mc(HVqM3ApH^-9Ms14x(bp-pAgvd%Pz1H$^fQo}uJvN8 ziRpI|Wu3klC^P-=p~hbAnIHYcoosN<#Mb9q>%B}o*u?uxOwSlK|5|$VKul$0Bo2M? zQY#Vt_Jf?EERzGeRVM36(sG$GMnEU% zy}h5Z*OsBP3p^deN{-H%;KHXu{vH5-iZ+G|2CtgHJOsqz zIWIk&pad6!U&zy*j1#{G-qcfjmw@;qFufF2 zOy%#0g8dx<9pR9k36jBo!Ey$!fR``UZg-O2VA8|zuBmL_!NlE7>;%&{gt6$?s&o_r zE@1Lop=Ti76k#$r79|+0>odXaa0(2bXR7G1i2(WL(d4zubDeyY+YlR*TA$cdJW_K5p1q8#W1ic#3wBNB(DlR7mRqd<6HF~eGBY}(HsYRhye-r$+J5+;hJKzQ~rikH)PZ{bA{?MDj zY-jX<1O(78VMptn43=|zr-?I7Jk7*;U~Fmu?HGKE!1PK0vk$XV${z@Lkm zEl)T27%b=bw2A)>zR_O$4hs#%4d6}b8dD8Lbi`}M)3vXt5O)L5#K>w4Yy-ft=+^X& zYSO(U5YP@eG#XtxcoRlKx;H`w)4_6va!u?p@lq2%ZsIkq*~?yN9l*AO&-c`(@F zfybg786($wVEVa$L%8rD{RFrRx>bgr;m^TxhQBiLci`@5Q(A#>C3Xb?-{foW_>jX! z@F=U+D>^9(YllZn^ongU5}-EH5quS`n%WH6_Xc;tNa)Zx32ZD_>@1vRlAeYF=^4Hk zOh2WdW|-#xa|xIX&<1E=A&2=exQ3C=qw|wse0|IYRP|@U{V7+AaYit^IySo z4ZI89gz2}xu2+KTXDE;#=A}mTxhcZGOom>M0112obIb{DwKBcWb272E}l z{1ZI`bHID2Vg5I&ybu9$1|Bx?W8m#LB}ux2)!-VvQPS)uO!m9M12Iw#)$I?M^eS-S zO3eR0-QY6>Ou{)!*ZFJkRdBh^SHT@IG#evXSQiYnDB((7?*@JwB{BxCeqgykx0`qr z_#(bnqILsnM3WF;{6d7CS=a;M(Cm0ExCp!(C35Krt^l9HWMs^CFM!u$ATnxnD_G9J zF0k<*XxMR~bAWV=KWe|GZdio?`au=ymz1Hez`Lc%;~GVf>>I!pNRZAs*>}RMvjsIY zMCW+$1@sbBoT}demgBp?-VfoxXvJ;>RHIcJ5puvcz>9SUGr+x#kr4?NgJp-0fa!XI zHY(w2ijTR(sG)7(tB;3f$2YrT{_mZtJsY7C9Do7+=1l?|5Ptw(@({EAsPk!Xs0yQ4 z4Vc~&qYQV1{Z+7>A-{<^UfC_gDIcu+i|mH}H!wYPPP@S1jZE!Juap5N_y(%bSa1vj zUyx2gDtHtoqd48+WH9}3&v2b*gWI6r8*L&VEN8ITivaq%hB3L6fWsDr=7LATMOmS- zeHHjLCLg0pw}NGde*tgDz+&`*BPRW0a5ZLARE%1~-t!39G%++V{AP+!XJQLH&y;G& z4yJDfO@l+49lL_Vu!J*eED*joitXUN=mkcb=mBoYAkF{y=`2==es2twBfwWN(7>;Hj$Gi4Pcz$S zohQo<5dVHK{X&$nrppDN!t|<@P+<>)=?7>K9o;g5tpv}-z(wPPms;EPMe1&U0 zV|r|dqR0t$HL(LcLRw}ggBMASE)86Wr_SjpAr){6cnem+Myr1iJO?YR7wP(+3|1mQ zPH-)F5{6#moNWcKL5}gE+P{K>!)V1uzy2F|s6H~%Z1}%m+22OlDKBcc- z%@!fxDjJP3^ezFf$3SAt4bOq+z+t?ez+b@U(T$AB=Y6nT;$z?mus0gzCy0Tsxx;ot$2gF^5dXw}nn2alQbRp3i_^^fLr8VNU=bYbG%;C8tG(vpF9 zOa_(Ur_czEbB5o4Vbz$f9eM`-YqGy+;@`lrm`#mFd=q>T{oWX7?7h+dqS5pTnuLG z1`|yN_ks&;7|HY+DFA@OI2K4m~~Z{~{pFj&r0Z z@B?@RTDf8H8<<`O*@*~LWjDZWri3!A^lhC$TN6ivlgEU*U9Z-ijoFZeK=nn3J6;`w{|0g0~?>y}%)M%ti0ndTKa3nxH z8Qgt!Xl|Gb9)W?%7@CX0at0nTaT&PErTsbp`FjSe7SM|X>@1QA1dPQRt`S#HWbi6D zbqRiSPS3yra5ARj89ILsmJ|F6e6dF;gWrJnw!!R)Z&8xJtKjJijaHBQgjj!5d`e$E z1sxI4B;ACH1+T$C6Qw73ryjwu#}h3Ui#CH>L23e1!5d3ME2Kj31*y?30@LrJDtdaW zz{r61yC$^k-iUxrMz;WO1uwz^qgYSiRq!=jco+9@iYM0&kHT>GQW-pue<$>FPy*oPYx?FR_MzKg6Y((MB@B7ji=-&IL~b z8|VBn@NJJW+w(|(PRX<2>bpZru+Lz4TADk&uaf~1FeZl&z;cF8fe%g&>0f{kKNY&k zR0Ed#^-WX!2rQ>%fA-ewWjzouX@2OOjR1F%mQ-WFZKOuzZtZ~K7ra^}Fw4XR;LyF} zYr!Sp-Dne$Y7Jrje;NVwm7P7P8d~8z1AZG95=OUs9(;an=qA)|Fg6GMv9mCC5Gdq;TGna)|33swL@VE?8`R1M(650jqyN2#%`VKq_)2q>{e>XX30AEHUG!`sj z7*o5Tl^ZoeKN5KZbA{2UQ^1S>8`aPha0PDnXB+eX90WXpfZ;Hp5RQdff>>M} zf^9l~XL4{EeE#vu7oS#2cx3+aWu*@<8j@d9BKT@0*Iw#bS~#~LcUf^^VM*?yWsAhD z)ym_Q->grZ5x#}am90&mF6yAHf-pSBvx9q zsBmfSyt&H?5pu_HmhZ`bcxj<{cOzaIDkv<@eYj*uem+}V_^5Q`nY*~4xNs>6xw9rG z56!(hdrDerc5d$E+~nk8xw&Mm+e~0{=RLf%bVxp1RJbUA5uDM%qK6+T#L=>%1&ikv zw;aGBTUNR>-=iOhD;t&GJ&G2UEMH32+Cgr?+|s#hX<^~w(#r7Xl|?)vcVSU+aqd#F z^aW*M<;542nM&oP7nR;AY+ln)E*iDqYtwgmU$+19THDV1cBh~-kLjXPEowt=Z z_^W0EGV!t`}aA|Y|jka04{(mvjCzf4z9Q(=p%~@nU>jxYlB+i8rcG-mX?-wvN3G2 zG+(SVkVr`pODkJnFfFw#&2%)g9#ouXnC<(W0ekEJz5naGKCbIGXS>gR?sK30ocp2T zlxEFYO$N~sQ;R^vF?B@ry-&oH4mSbrb;SQ2qt0y1=qc?=q2eh(lS;)*;9j8q7b2bm z!p;+MFfbcf57YykLrpCaPXV6*SAn&u8($j|va~x5rd~~@8~emYT<9R?8D8yp4T4Xg~hjT@DC63M+F4H)lvW*NjV)Jw(0~AoA}4v4$k4N`gGnQz4bs zl4O;M$h(vrDOF0$j|1O)?|_5Tmsg*`uThsqDryxJ$A!*+=jVj4~LU@8~6!LWWRF3g} z?Iex7vXtnmp^IwMFe;`F(O36}YpfH;sar&1ke3A1E&bt^229dWb%8p+;gT^sN{;=o zJ@Z%di0QH#nyjO8t#50KNi{WR>L{^6S2yZflu9tus$GiOM&-k-Mbp)|(@(6O3nt!J zzA!p3Lf-6WG1{K#i~N19GmF#9RO!0rnfCO0!9-=dA4H317H2gKOChG-S|Z+)N=%d4 zgW9f%`3E`0u!BM&u}mv29XlBmJXNU^zW`5JEu!2 z-&bg|1k7ZEq3TsTl~4HU3Zl!l)l>8Pd6A{6Vw-j4^~g0Udq_=$yvawb?*(Pu1zA@i z#M8)@=$dy5No8E|+sLU(M+;e_OLr99UOZ7I2J*_c(j8K>L{akXJ}T$>d)2&N*v%eY zPtu5-{v;_!!d+g~2GtglPEQkgr=RS#4A7W_(0oCY;A`l8pMffQ4+{+?E?xdNlBxEH0p6v|j zM_uepNcZmNy(DeqjhA+-H&Z#u^P7{Gb}AURZa0-PJm-QjO)Nb$m+oc@Li^B{*z2Kv z#HYORXvu|b?7Ps6!85%T5P9T{&btGy*Zx zyy6+@k6EZ|5e8K6%krpR<4#vsNMVw7`Q7`w?@U7x%Y1BA_$*FSfTU%ygaH6(pr z$P1MxwJDeiIF}W(iK!ZHc1{E-tqYSnNr~X}kejVC9)Mh;kNMIhy)3v*()QLJld1fyk7kf&rGch8om=lFrg3)#busbzYK;^s zk@rI7j}?-Z-)wzCNblBs{u!Dc(`=AmaWgq`gfQ8|Y*F#TpB^?L%A^jJ7bvxhqQ=pX zUp&JLV^)au0oMcU^XQ3P?(!(bB(400e>b%Z7`bs@ww2s4`5!*V*0nBM5`QW#qn zSre5PBA@f?ZN62@0#hM6f`U+LG z4eH@4$TD`W^S?3@+}hS1b2P0xrhL$vy5L|l>9e|g`7pVio3r38OwjYkGZCzg8^IK!FUiSJ0DMadr zjDPz3;y2tc*Q75uyf_05*|h`xuwermJ%~a$n>-OV!F_u+0vLkQ_7HRtW!&({G`t$ z85@jsq2o;G6iXF#>y9GBIK5n|=nIHRpC2hduke%~L8mFu2A7sddG)?_jqy&!mzPf> zvEg9u7;AZCIT2UK5>ab-aB)(d${vF$Jkn>hltB0-FO`J6fNN<$Q+=EG`zu09*if>h?x1fS4*!| zi%>^a+bpc}?|9AjiFv7+RF3i%&&}IE9*cOhhswLWx($W!e+mD;yyAv@_&y3lrbb$-~`(R9cgrr3It5&d#Os zlgPdm?h|17gL81cW`oJDlk?r0%0c z;M%+JDt3!#?hg>|(VvLZ2NE&6a2&Y+cMa0tf;%1Q0|2ou;K~dT()+S&A}02YM2_>4 z)(Q+owZba84HVuEuzlS|2%7^;={Bs>PBfxMnq{SyuofNVonL5UdGX0Zei+W@rvTc_ zWD>CiXe46|F;jV|yU5Z#KTYaB@n@x~f}#;RnfVOfr^6l8#&*OHD?jZe8K;{>WWCoj z%rZ(EDjm8^B(fpyiZ|2CYB1_{A@x}Od6kR!oY(sK$`q4%%$A|H=SPa?*jFw0P6s8ID0Os zOF398I?IrJ8^k%|ZmQ3M&nO@BRnosED2H?Sac59(4S;C>6PEax5Q_#Vb$<8 zE?bl@)OWL_2RR&YSJh`1&n-rT(CvB<8vvkep6rTl4+wJaE!$Ys2EK&ZKoA+p}UGq&bGj;{i5O~pj4(+)W zwK)r10@{EsBdBNrdIO8mo=ukt4Y=k9QtW6;=_flMEZNtr77cm|g&2qn-^_dwn zh}_~6s!P$7rAygG)3E4pIbXrn7lqicbLtQL$_AM4zvov>!aTI~DTD9!sTTi>l)2yI<&5}qK~!W#KRe?3)wPn5{faMq zd&zkb{9XaVW!nKJn`1`R>?cH17-!cMc3ZP0Ze@;e$~Zb)mi7}<=~zz4GYHuF#vpdo ze$vR}ZiNeZnB`mg(e3PUOS#ZAg840zg}wnc+3GFd9;A#b6AI&kOEa$uuUu(e{P_3@ zX;S>SQ29zA6OA4wM`P{|m46Mypi#o)P-UQa1K@P<;$H;K~m~qWQyQ zy_=^+dhZM%xt8z3=Tg!3k;$1#ePHHS|u$2+h=9yG%+5la`tpdJ+ zKwP(`d~=~(XRz;TrH@zUXq!TcC*B~r33<;Jhsrb%KMtWqB~rHuR=Y_`m`kixV}-=d z;|*uh?IjTY=MrMwH&&Ey1W4=hQd@C4MCbJ7VR^TRHD|0KHRSyW(ybuV+Q=EB5xu6{&GjEEL{dVFOd{C=Zow z%KNP(DH6w2!-SCW6y3w^?zd)Jj^O=Qxo&eZ#| zk{c$eC1TzHg=AlQBr4!~-fxvm7J|uD-D1&&;8<);5G*Ey52c34JCvCTDvJf75P564 zvJHWhV4zaLw5l>%(t;s|kWnRCvVx&?2t^{49Sp5TC<>vxVCV^iI;l*SqG0G@gkn_L zmeOFT6d@BRtAn8ugvZgMb(wr*dTbkaq1t=pIFYatOLsCCySc2T#!yjT~^F-QSDt(J`-jM#lwY0g zON9vKnk-g{ZlJ}76qPYV)nJd&Fw*|HZ{VDL@2++;9^l6Z<26QIA ze(>fB$FfPxT_v0JsHHsM`p}mysnA+B$snH&%!}7pR6+mo!2B|5P3o1_n3Q~qs9LB< zhi=P>|CaXubka0I#*HPF=2%!lhm{E1!u<7fw-=ig!CJS1@@g77Pmf zi{q(9XC@3WR)d`5KVDx8(M7Z@VOA+D*&t{6Ys-u{iVu?ZciU5j0rah|e|mYMmd@H!py ziT#I4KXr(57<#!i*t($oRzQG&>pQO%S@=*h$T$6;)<>kyjMoLVV37atzv!m6YUzP8 zlD@C8yu12}PCssp*sL2Unv5P@aeG%3Q?EF;#s9tUl^f({|8Gvd?d2nz7xqoCu&pR8 zt)s9*{)6?lRNlcLaj^Kk{!WS*LAoDB4>)S7koJv1kEhy`+ABv1FG^mKmU`7m2XW1v zk2T1z`>+0`-Tr9k+SVt_gH2tIwx(8Nupsi1L7wRQ5pAot7(3cF7HvDmw|Gr$Yel&; z*t(0>{O<}jqH&FA+{G0aoI?|W3J&U5>`w<7WV7#9Qy+HP>I|dB@f&kkr=CNEsR35h zGhWCKu!nl?9(@+8{EvYILWm$u`lyX}#P$ObF}0x=WP?IzGFi2N{m+ZZlgtD^Wt$eg3YtoIJ+d^s&otQ1fhUO^h_(Z9-d0PqX*KJgj(W-iTuvA>4Vp{ox zm!y4#J3uQgPQ@+wRaNE~n%}hRw_tf~Zgg79y473DLuxejDG#Sfp?q_8uLNJM)=rd99C@j^MfkWvOTT1y+B{EHr%*{O{S`{Hb?VX)SteXDe6Xr@` z`Lt@i(%D8>g#5L)qK5aK2>A_iqlPj`v#g;sYAMz_RA(e>{k_+lg0_|Q3QM&Hz~p~%~wWblX9!{4wq9&N*3 z?>krk$?3iW4I)T5r+Y@SxPG4sp_AD!{a%RT8F}myU}HZbBKoQR7qv!2cbdZ%4Vb3g zfRshq?AQQH;&dgu2D(`>W<~B|^YT&Y4)XxokCF@w=PbWr=;Z<2JfJ#fJ}1j~73W*&ObN8X>D?d+-e6L=g20wdXsLF4Eu_THd(=plA@ zmN|}-cqK~sPS+_@VqFEq%5vT?p%Vs%)9}3FzRW|!z z@B{;=IE$39Q7nAORH4el>_gTWOrtRDkTPf#^ADLu`>?x)4h`m-Jc?Bgog|b=?2n;Y z;^YQ92%j0nGKNV8?tKNQ8pWRYXYiY0bF}TLY{>8@455>$SSC?1eh&M1cz;^VT*Kdr zibpkK#}JXz9Rf^q*zOT`1ewYRcFJMlBkwcwR9gb9)9k zh@;t@+>CZ+qgiF{2m>eJgsAE-xdS`%U^1Z8X(WxD?IR|gJcjii-QAq&R!cGa^|-bD z80RLP+ymj0^&-L_2E%5ybaZ!P7-GfRS1=k)lFzlz&)yxqDv>kg0&&J?GtOoN0x?1l z_$fJ?(U4a=VN54V2eO$`?^Is1dq$&+0PUjVVi}ZNLf%>?xSK}Tejw#g1Lx3AQ!C{C zBn;u)d466}HS(VVgfUdy1Y`ikz#8zlmG3u%aRwG+=G4X&?x9h3_?2Wz4k11UJYpsG z(>M!FV|09a*gc#%FbgPVgU7GbZvc56FqwTa{?RZV`Vp9q^n2L&31h=~i~zW@frkK2UR*o7=)91~>&D3{LGm_G4`d>pA~xW zJ#b_ZZYeOgnbHzT zm8W`v%1qG*clgcg*rI12(!Y-!r+~+5FF$)HMRSc>|9$3gzy7RhXO>-%n{ZQIT{EC2 zMy3&RQ(F6#=JP7~qTg1dmy>YaYLZm)&n*ABL4!Ff1rYC`;zVE(+N>wsk!fO`=A^bz zpsFjxxMixfUN2wv>anFKCK3C~$5{Py-D4d-wKTOxB|q;cX@559<EPGN_4{Q+x-zV}nIo3ij_$VNYzBYAjVWIDGN6HHh4F2fMf-L$lz3N?y%k zH})QG1N%!g>Gp1ADp^(;)72>A1<(Bu;A+6c*UnIns^I^?HzHdhjFzvKE%|!pP2wt19pSIvGuyr8c#+K#m|PJhYgKFF0q~i`P)*b}b6fow!Vf*6YBLq@8Y3$uA+# zapd`?tzDGo*p(O3WAB4t)zH-vr2dA~cfpZMFrW2dJ+!>!raRbuEHU$uAfwi%f7W|h z8?W~z)N}wC{0asScChcwb}@`Z7QpY_?6w#0ru*5h7ss2P^6=(vbhisp?n&dPvHp*D zRP)juEN+u6`aals@RoZCTc`H=O=0(L>fX5((y8PTK^6~puo%Q%-jr_G56aEx4R^WO zH=DYQ8}II7<)=JVahjCXK+FNx!M5CZjihTf!CFOe>*ZnYu8{ms=ho?0QFhoy5_}TK zPTN%djI>eOEG53C-k?9Fm($$L_EM_Q$<3y|l-%{-K4Olp`dS%X@%811okaF{V^Eu$ zjJ-6L9%Dbew3u$Lo#=RwcHzD2v5p=Vb|)2YpzTubWXCoq(<8O6&Ck;De!seSuroTD z$eK2nlWRH~bUY8=M2k|S6ql$uEy}<7H zlkDG>-RKwWO6AK~SXOUIimJe>zY16b%m?4+?_?irG0{@?{gx!#d>?=FQZQg{C0B!l zzj#H1<6Nk?(b<)!+uq zMCE}&mZkq-$(Fq`0_UB&SH@bnIJ_(_5*OzXuPXfK;WocQMDS+?}mLZNgj z`}oy4shu!64+B(oV#f75u8pVR=I;6^jU<}ZNL}%w&)-qlgx4&Y0bfjg56ntbUfzZV z4xXngkX6XzuT4z>J~ymGag;wx*2B-9ZVi8!v5x#HTG_FzQ z7und?duKlG=KkewyZ}14LYz|omT5aKlv=}=*^oAi=j_XJG|fCTo4xgVrf!^@`}5hE z*9Y}U=}3=m=A2U9V{1l9dGHN#+v<56@@rHcjtrI*&T_Z*?j2A#trxE;Km4s!jTD2; z0g(@2=`ht~CgMH?uYm*Dt6RsH6L~#i#TqL6l=s_K$-RoR_1QTXH-yUB^)Mu<=ZE=r zWv=t{sdjsZGM~nB#r?)Q1D?jIdrP=MPkupm{vs;}ri#z*w`=ZY?GyxR4;c zUevrMC#zA!MMdfXu|_L*KTtZh*7RnKI{hdl^wyDVFLDzS&_&nbC3Z61SUg{Gz15bK zW;kWC(3g3r6PvliOsBKeJElbBAteJTB@$1WQhRwvS8C?wA|_xMpe{7l#g?h1g7~=7 zfNL|3ipGXdYRy$TDy+MU_1rnf@SlQN<<4W#3*0JmXOmi<=l;&AGIxS+4l92<-#AhU zX)%WIM+Up(a&7n2o_u>94L<;>j{sz}Ftz_(wTs?;PG!hKu{?g*UCdCOL!Yl5U;R4m z>^cB*xjJelII+ItZ@4683-VP)_e7_kM+!BIbs{w8=twz*xLae9>rHJF>(ufwHgZqb z&Xrz@TO73wThAa*?)#C=+taNJ@vG(S9X4koOeoZn-*qs+UfGiv`J=C>W_!0An36ST z@k$~eXJ76~n()nE#9U8mDO*twRm&=D#`q1=$qxP9iZ2OTW?+p(ydcjxNb0s!|9M@% z!fvrkH(faamQ|ZdGuZvL30>dw`JJ?I>Ria)NJ2@rM*d>IMt--J)vl!aaefV+0$i>< zmQ?rh;CFmP4pWHysN!;s@hh&*Fkcwy;R^D)rtE9)He3b9I*qL2D`vgl#e9C(%dDlY zYx!*7HKz=DqNa6Rh}7!~E}HduF4t5@%V!Raob=)0c&n^}c|mIvEpVEJyg!3^vXEyC zuu{kCu4&T2aPNbKI^-P!{!@YbI(P(J&6uEzIW3^FW!0Hv6$!ZBEyPC4@5;r7YIMyu zou)|x7V8$O!6FtmO@7x1Fvx1)8Mgzx8XTc%nv<%++ZB^7W(`b&Fm_7EdZ)2tAB>>s zEOKvW`W@@O*Bmz6eOd{%X{t2L>srgE>`m$PsW%OJ+ZfRDS@&t%-PqvX&7RwvLwB*} zz1<@3Zq&3GsYyy|Tdim|x?J6vZ*R9d{}s?;TXME3XDyzFaXG3w#+5%L@V)aksi%}} zzv(*U?GbDcF_2c1Qt*K}1@h;3uQ<(!#i(+VvRk zf=4%vwLYp~yEz(JcY0=)SZg8*c9u5Jm{TI&r3JI!H;dD&xwS}Q$Vx&LZ2 z!*W%N0ri|8Q(^Fh`>xN3_&W-Vyaz`hU@Tw<_BRSar|6xMR6t8r+flq>mx)Q1zd(7k2ez|a3!BszY)j(ho^6V{>Hm! zmeF)g(>iq2e@|bJn9=U@bJOeBfZ~zq&mcU^&FyJdA-sJ0(|N9*uKpnS_Ohlg*4uB( z5&h`&CqdQ&v0K)r*DpuR2e2n#qLD-?aXNiw*=0!>xTwUzc-NnI86_2CV1U( zxwZzn@6VBL!$w?j6?@EQ$4Y-XKg2VuuBknJLZIDU7vPVtu-pyix+_5XoNpp{Sc(LX zXF6zR!F)q;IoSG-66jI(&PTW5oag(fYsvi`d5y3Ia=A!=B42pE%heC`VQ|9&W|Z%8 zo$&wUoFM(^i~P_aQC|^{G|84o95Z~!y1Cm zqpvJ9fa6ksuM$j2g!KBlnPePpCdrM#%2lHx$AGiNRBVB(zn?#Y@VCFT`jM#4{>YKY zeTU!YTEfzg#L@+9%#l$Mc|JZj@VD|##OE5tHXZ3f4Xp8qH9^5ThBv+$*rH|oTrCX) zYV-w(O@GYv|^EyXmURIbh}l$r+I24vyFIaD&&hZL+fhoJ0FSpFy7 z`|up|k@_QY{0eY+v+D5BVaM5Mq20c@9v0}qgK229%k?9B{gW|$X2Yhi7&~<>OdkTS zQYGQ65jDDEjsVvZtX7!MApHnmOidc}xr9Z3ni3oqWhlp3mkZA6HAZMKZ=n%6vVGQ) z^qNp`=$;vda29lsULzvhGm~o=2jn0>8#KVnJYUS$JXm7w;df&e-hwOfIvRSgq4%mdvbya&>fP7LxBra%?mAMX~QcO`+d1->2Pa z2ut~_4?V}Gd}i*v+iRX@Dhs$0vBKEv%`nRHxjtpjewH+5bX%sxLwj)KCAFnERgh%5 z!R3nbV&*fuTwOZcG%vBx&3p{q?S;kMW|wP#SBnm_q}bvGgY zC$K?B`{1_zfurd?OkST$@R-0n)aG;P5W3!GwclN~68g)&_U5RlJZ`0O(-q409~}@L zY)de!0Jan}|Iv6F#kzeyJTe!j=#w=jy9%Al2u7c?lF!ZQ86K-WCV#5k;_W*!(_`?j5qh%$G^IpQfuw0uU87;=M>AjbC>``((2l&u(?gM zgerwKHEkEBC~R5tZ|WPap8{;wu@B)X57b(|?WImoRz%5%^0Va|EA)?&9z>Q`2x+P& zYguhhHulT&z8}xc1HWGl1&%zKPJd_fPFm?6_Wa2Qg^gb3KUqA}U2*vODpl^7Y}r#G zRDPgOf0Xo`)YL_$+Ud=z^z3V}Gu<*6b4V!JU##BZDfT=w=el0CJHhj0Un%`j)zBaI z1YA4XNLuLW!Px3xZ_(y?oO7i8RC1DPi{N=u&Gw$^GyEfWeM@$PO1j*<@5xN5=cB42 z$B^?=x99PFPoB>G`1+x!8P`9H_ADLYe5yVpfevji^M^fs!E-vZo_>|iVjrFEDtLYD z^yx%;fVoePO51XgH|=KphLBD84I?jH~`d@_V_CJIoqQSD(X|z1;>_46T_VW&5 zqrzS|n=Cw`uzhDu!m#P=^x0JOCVGzdsoufgnqRuG1?M^=y!u>s{O$_IW}ffD{tU)y ze&Mv4zwk7A4z#}nX@jvf!QV5%G|l-SUGVqb;P2Y=gS5Y6S3G$-`}F*w==;3bW;amV zF6U$nDKbWw`a661*Cbr!)&Dw{Grw?tXuj`!2@Rgub7iVJKb^{xvE$_D_<33wQU`qm zD;|~mgHpg6#_bq6T{cU)n4ssT(G|cNHs+$0ZmBJ~*p>ceTfh@9vGvZ0w3eN5e%a-g z%>fsMY!I?Zg^)dY20M6ZnnsPAd@oD5{5n-w!{rmg1`m7jw_fFsc+&0G(doD%%WB}W zL9TpA6Hzu zi`t?Kk6i9NAR2cbMDEs}BS;^SkDT&ZcX;8%dypx-BNLJDY6}f!;onhIp=#t@tELo| zj-?BUY3J{_TZd5G^09OQG1Vhnx)?MNOtsur*L@u65z`nd@eN{1;pUuy%_(f`mHS6T zHtlJtxZl`Rq1fWCJ^S)g-*-W^GsF;vDWF(mA_r^mW$@ z?(_Dcqpvt)a8A39Z5Ye=!;`ycM08{baXm(z`9 z=UVy*5grzGt*F<>ZTdp>&2>3FFbj_+!i(JWXX1_Q#e%%nqYj?pUV%)H+`!jr*V%K| zHiwk8al(|PoKNQU^3cybQ)}o>e!Cp*VF#|~>0NC&2kjK(3oPu$yoncZXBcq3kIx4A z_{hS8CoWjzeFvyD8`n2{F(Zm?=rz|$P#n2T`|-=E|7alDGOC#GD6Y8{<5WrIgY2^# zDZ}pdZ!L)ln)zIF-Rb9c#C&f-<=2sSrJY|3sbm_>d9N%sBJUXFf5B9iu#@v{h?V2kc3wv>)?HK{i zb8Sy@C(4t3CzgMAA=KWevq z3^L5{r6vx>CgndQFMy;nhn@(~`zCSRNloT{%0kZqWzo!jli+Ygt?>ec%@gRhGC?zmun>m9Z!NL8*m60c~O9 z17kV!mjZWi=a0Y=%XWMKv(BgP_EwJSz|Yg#)KUcOjI81cUS~EA*=$W@{+UgG1>~p;{xr<`MxC38J411IMBeT zXWvYIJ6?(J=|p^zLGilMrqHSu*T{e)PDMw=sqryKw8DRl9aq9)(5k&@gJZ6W#+S#Q zRmsIFQ+oI24azFpJM|ls)wYoR8ID=5OMr52;m>W|v+6>} zhmPwhg<|m$aUs|zplSI+z?Bx!=LcMA0Zr={i}*D=|4c0l$Fd|`BR1{Cy9{c03BC3j z;N!g)6NiXy(&C!x|8x%qYkyT)NPUb{+R#_(f!N-Dl6D<-gfNSTO|GmT%TKE&^M-&hH1~ z`ZUwZd?^W|@?C_B_ji0f^E~PCc{7DD0-mm4cf2anO!}1L-y)5T>yA&z1&L(5)cmq@ z9RwFsNMID(%JUR|yp`S0?93RJ0MG!rX z197x~&T;6v(J@;4ZWK`MnA8m<_T7%aPwTgn8eJ+eh9eDgjbG&+vmmP7R|&C0_&Bd zXCh73NrltI;5Iw-Nwj-;Ou=DgtEp?@>5@r8;)%+V zCY}03=Yq;&p=EU6%Hl}GH>116&9&U95aMQ3mgLBSP&xf{$uY$85JgBV_%_(7@Q8;l zga^o}eD69Mdf?v^CJ_-micA{XGZsgFBA>$zLUbUk@btVKIomNkiJHR{JeTb7@@E^r ztEc1nB)V9*kjC6R(pSb~{d6XsY&9yI*UC|8Tp% zFZb_i_ut3;j&}buR$8o{wI4bEu+oRh(}S_?eU!*U+`J5r%e4Rad+l*v*SO$QlE>9$ zKi`n^zU+17bi{@3=bLl>Z2h{gJ*NtLS8ebu&g-i4Xw5p4*Hr^ogu4r_9_~)K2Doo| zv@^_I;duiQX>ecl=*`RFzU(oW?}59?qcit~yU`PBPKCQ3?j&p`_{-MQD2Nxl8XJ{Z z#p`<3=XKo`@Ve6dMAj+zEHx-l!1bBKoI*RtOCRFWu^?8$W;Ole%Op~05e220cS~qu zQVKnqJ>tVosIv*^1!MuEfg<1@zz!?{Du8vsW?(x|4IBWDzUP>hN_%RJ@R!YTJd;ZM z3di4b989Gn1h>cGPo;4o8a&1su+hbt%rUP!M$kIP#_n`!M^QyE^Fp?8sSC%}45kD%D@#J^iG0eD*_ZaF8IJq=(jGL{v9>SmWB$9?eG5zL66{)R z3{q;|DT%Jf=R)#o$Em)U(6>2y^rQWtihJRhxa$6%QLNLN@ZoA3MIU_@Ukf|7_M;nw zt{z9<{`8{ZKa>v30BR{u_iGAg&d?NY1I`13KQ92-FAY7d~JeKN?AGmuUdDtwMt2GU-_fd?F445Z7c$1!FQ zbTHkqX%HPmKX-gRh;~(f0;wEJ(&#1d zp0KfqdtIgm$E88Eviwu;KT?sFRj2L9&vSqHU()}{|DAtQ1o{7y$7}zj2$rG4x0#R- zUu#)<7RO0mSH=HM^cT(C|BFT{S@ht;(-+M)jajs4!J;9ilvxJySKP!xM9iO+(T*|$ zhQNYF4`fVVG;3*T$@~RNGIE#hEgDQ?3}M`wIUWd_u-XUs0* z%}2Ozk|U&;MwX+Uf`2D&wlgszREo0+kG#cD-~s$4fMz|AO>h|qnhn6MwExCu>;Ici zIjIKGp}#TWn@vHWgu80BiVW9MF+oGckAPQ!^$_F`PG5RqJyGLBiN0b85qJi@8WMAl zCYcziCYh?JI$01j$y!2nniVP|p?YKxcyHEe1R}WZ-YKwO}9-2-Y zV=8z~Lf*z7$)+TL$(QI!sc!F>8T3y|H|!lSi{7a#=QJxYWZM7Yf{wo@CC5Dbv*M>zPP`rAm7skOZV}uDxDUl5;ShO=r;Go?0STFp`tUUTIdEGL U*=YmjNgn#odVv04Gm{qmA9N&*W&i*H delta 19355 zcmb7s30Ra>`}aA|%rMUk+W>-W;w*qHilC^tf}oFV3Tl>>Chmhd}Vq zwJ^)DO%X{^Q7hXld%>1hElV>S&B_P2XJEGPcLsdx{eSQOy1tL=`pvn|Irq8GzTWr4 zn)8~fGnzD_CB`;^h>IJDm<){Xatq+zK=|J=`}>V)DN?A<=3MATd$ zVg@i3SPRqx=KwC@Ts`9V60r?#6x{Wejjs&xe>9%@V%scqW8bJ?-Oqnzw>}<0;SmE6 zG!9qL>vH2zX+e;j(|MXY@W!Zx)MQIUtzpzVFGvSH|D7I+ciiZ zNyI+e*>A!_exqC=@Cw30!d>(ofc4w;Ky%^lD} z`}5ykvRCL?RFm7kHBHLBZg|MCm&jjviG0c{)|2=|Nsuc$jG$CTBERHFlm^syLuyqE zi8shu&P0hA4e~b~LG?u5=AiOQq`czQRU*^hoJNVrquYtR(a~;ClSuqGcC|zkTkU?* z$m?q|Puh6}DADdg{q`gd(d{ubipA!B*aMC(|bpI_1kZq=Tt4z)9@G2Qa?jgU3n z^Ho;=`e1pRn^?jNOKz@M9F`v}uXD3vzm(JpPe04dvef0ORBh`_Yig5Vr1BgOn3m2g z%WBR{AjWp|+FgmnSj@Kjb&nf!gmVlzA`}txePtD6iowBS9gTwgMLYY>ZA{GS@ zakf7ZKLxG<;qY^wUS00Xa8K$;t}pN$JcA(w0X{!Z^ml>(jpmsOMz2!B%5|o&=j~|w z3M&8U)W%)?o`(-$+jNh{5YH&P+B7Erq@AR_(c&-rtNc^9xAOR_EJGhgGuUYTP@Tb^ zAW?(`v$gu+RA!&*?@ca6@BBwUqQ}%2O(GBgl*0cR(oACo{`b)SY`cFpq+RguPup2| zK(AhxTqG&`=1cFXtEt@6`J0{R`Mob}-Fs9{b6)U;oMJNr^5`D+W!Uc!Zb(^#uU*&tg2M`0k$e`}TCE-hG2qC5~LO^aH(?R+C3U6K#Gt83v#YMYu48FLP0xGOJYdvn$7Q2V-tA>`x~)iF zh-wq8<7(2O;Wg!5cJj+FhtHWaC%Xc1v?#KoVhlNIWxDWbp;q3Z;EEu`I0y^fV;yWo z_=wOpcSKRt@{sz_e1AF2qm$hpb|T!^*WeWEgDt5mReRFW2E2iN0|Je_0CFBR5Ro_j z$q*uPxfLub;?1-Yhu^K8b2PVhPI~`V;)6$8N#Fgg_d)DNH%S`Odha-$T;b_&tr+?gcMljx zQo9{hSp>_{#X334x0X`#U}=x@hMZoOj=kY)Z=a&7y*bw>g`T`ZDvaA(uMp~0&bv}q zuzHOP>^rFf{Dwv~_Qio-qhx3{GzJtKB~gCU ztG>0fR9`I0uX%Na#HcGU$UVWKlY`twNmJXm@$FBuFl~D_21v!%OZ(AX`uspS zpu^gfSwCYft($HQlvg|At%{x21<2o_4C+0G<_Begbl8g*5Mz4d>OFxHF$d+-U4gRL zQP)&*^MfVLl@8HB7iTSvD{K&{*v1)Jf%YPVI&w(9RAj|H~W7nR?KxbyRJ0t2ud6Tn5_V%adfL*b586|;owO6o& z?CP5zE&Y`3I9?SfZ}6&&ftaaaOAnO4^?s<;NFm>*OM&wGc9V6Zqfh!rH>yT)%$CaZt-7uM=AB+1_5kJb8P_eFaa8frC? zyFFMkQbJ+y9Ml#eB6P24BrRH7*Nm8$ppB!~nRQ|TTn~84>)4E)2 zPd~;EtNg)5($2PsNE+oHW*#XGm5yB@64{V*+hGWjM|yIu7n*TGqbf|HP_J>GvHqj^ zmKi~^%i*whh8@CqI*tmzYb4^G#qLY^c?E5#U>K$wl~1$>$bWh>k7fPe>&OT zxDhmvwZ-*R6WQfu-FjA3E^`ag@+NB07i3A#Ix^C|N|JYuSuDtb%t~+IEfwE=U(_Jh ztHgM3+kZ!){Lu8_z~g`eei>7GHMSP7B6<9zZ1d0pBT|=nwdNrOeDyom-qMr>${?R` z)zycj8{`(JNfM+a$va62_wtC>ouqd`3r}Xk%-8TuJI5fud??18>JxFey{;+edV8p* zEz{Q})ox8&F%>0>@$*$XeOZur+FoAXHJjaRvN5jm7snPydb(EHTAy$3?kkbMFRK~O z-u0aMJWkvO`F2A29>7xcc8hOSU*Ju!qNkIkAFT$tw=?Iu#jL?Vq9|F0J9QqdyD>9u29XE2g*_GM z>B|)?&NM76P|o(^OpRR9aYD-kjmEs`^^0Zhl?S93-c7^tU3cf8#BZ-M{S8*O%=dLf+#* zko@OC(niY2Es{>G*o;AMBHR}wKX{N3O;NN}Qxr3B&DQ9rbA>a8Q9-i$Aoid!JTVs{ z;N%^NP;V1C%ERvXbqC>RE6x3B6>BtC3de@BftI_3BoA9>aaC6NIHQ*fMbW+!0Iwde za8_gY;_hROIOF{6;SC=k>%D!f{9yd8V}tROL!Ff;3#t#{dX@3sAk6PTS?l0&0R=qP z(iK~B^Fn|BGO;MqT8o=o^X06Z0J-Optme9<#5k*rjuRJ@QLzr0@-_`9s%Q)ttCr%H z2NX?mBpPdS16%Y(#1v_c#8@u#s>`T^aKh(Rfb44K-F2rwxWGCVk{FH?QiGSJB;H-= zFCX^qyG442;KryQ=RcOBk;B{jui25SIg?~Hj-r`C@}Cf~nigT7P-C!_q@A8{t2e=r0d+%c2;7Ra#QXE*jR0eaB&u4+ppc2hlK3^<+A@Jq+eBtng!k6#!1;N)%Wi*%id|LP- zRXOGgpO3(21m_<3^m4mb-DZOCfX{c`n;}(-1BXhY8Efqzz5JW^{adw_H(ND#Dg*A=UP}*J&6`gz*LY`w=8dP9H+y&Z=mgL&cxm;Ww$sbcdbLKrAoCML5cVNr z>Mo^AkD0xS8LP1h9g~itKIEMrt1(xqe4a&KYWabv+Nd~hIUQP)8+tms$s}nrHE1ra znX^yz_LUxs+2Sx6dCksu)@-Hbs)(AIAYLyQd-J3p?AkW7%7mJwOJXLk*ho~2Sd_*f zNnNQmlZ{a*kY4U^FO8*Ut%+2!B#Bt`@^$y|rUsNpM9&arkpkoO@@4lR=}^qx5yi>ERuivf?kfN%6Pr<=Qsg zfArUU&+m4nQC%5?Qx3HlAddG}ysvw7Wr-u2ryZ+rF?8VeP<6az;NK*e+eM0}j`I5mp-a1cGeI!~k3es>X-{E1`Q{Rhh z!A|vqw+G(Y1n~^$4WLEhQP?lN)2V+$c%P+I$ab>l(puC^V~F@4~WjQJu!BmA#=bXv=}XZ@?Ff5KE867GcV5fWQ9o- ziCcAg^_{ zaF&L|@g15t@dwNDm?lf5f4!zD;SsERINI+hr~TVo3>M8>e!I%bHOx=`5|0)C!sC`D z3QvB1TP-s3$-UhAnpL~CCij=t6DTOl%;-%YVbe2W)WPy$C#!+%9ha1&xjuOT2c{{yF6Py+NrRt$}h5`=Z~jz;CcE zod=Esr`gK>MSeHI9XX7h>R%Yg$zj8&h@G17i=3aFi(p81L3DrE-;YzpNGdFU+2Z^|Gdf*%<8 ztKaVkmS?lVLHGGpA!f#K_SPUXoykrP>h248eHi;~(8G7)=4AaN>l^PiJ53c@O_IM+ zvBxwSC9OQqd&xcoyIDv^K4$C(7`2_ksQ49x9ssTlV?zcP(`VSTgWskfvi?I%(VQh~ zI2CyjM&lCk6rrRFP!DH|hDfxMH4d2=%9-v0(<-1ASTLML4_)Ld&*9E|xQFo!&5liae&*2=?8u`>2;?3?J%CHEIM~GJJwy&10Vo&l2x$o(#qn zBbeU^Nzci3K=lZA_kVhKj+o=u8OuVmpVYfbsc6kZC(mXz*_m_(`)BqWp$=4IWF8SY z-yXm~|rw@>JKc-7hL*PI7@QjFQGaAY*y!Df$4rcbdKM<)1!^RwB(kpq3?tZa6B zWMXHQ+02~VN$$&L<8pI-p+97^mvYU4JTF%^6-#l@A?)Ma{=Ue_oCZ&>AC2I#IXP6E z0&E7}1s=~~(W8F!MIDD%oP+bIZwO#?%w|EOQ+yH}Ic&t}v`%3o*^<#C^fH(@BWiVU z^uTcLB|L4TM$+Jogc!B*7^abWnfkY@rN~1%ye58#L%vo{h5vMu2>(H!-@?X9y$rz! z6&wD631*bs${H_QC9R6%LV1C>;PYwc)4bkDK?9nS^J$l)hQu-5D9vI+^ZO+7niY@4 zXaIPsn?NQn4qVRc+u0j0ol z$hed4Ed1&4-<;iWy?8GToyeAoqO<H&$1~{kY-XdrPRqLlz*#FvRi-@=SRlcmeM8+bYCw25NzK@P5QA z$s2+f^jCzflNxgGe?=I66f~D-kf=Ba;OS?;^oz6PB2#WqAQTtR)|=|xnW06YY&EMhwsd7?S{ z26!(4YFyEW1CxNtVs_-gyM3jrD`wFZD}3bfVpdbJ#7AB(W}%Dk>n#3Qwq)@sA88!h zP`Kn3O5bExmNrCi;W=Y5)&V{Yc%N<=%l1C>r|{%h_S&*EUz)nH?7L+tKJv@4%rb#7vKj(Ip|Y1Sn;TAL;8?4AI+`v7L|f^Wzcg z#<3qCNej9Qp?Ajg=!aSK@|3{8ywIAl@ymPp9S1*>KDoSKxZ6wm{MnKv)s4Ao=Zc6@ zq%US4FYg7d#~;fF$A9Q0z5i&9v@Fg0y)=^RK%IV*QkOMfc04^9oIgO2UkNLG^phY? zb}ONx8JJkY;#PQq?r>~I(Ay;qDUU_cUYU4&CNtG-iNd}7`GQS^R`a#?$&ynE^jxxY zAveK2nUz0o@hh8zt!fh6^!NlinO%C^_HTiad=Hz{@Z1w|RG@D5){`mpC-&`=y+V2V zd_?k`^XC%d-K7mdm7z51PT^Kyul8Wpnnw2x*XmjeBL_bc}jc1-`QV^f~?9^V*IMmYQrUL#@rIdPCj$ZPE%BYebLnujF z&=SkHs2=UgjfQuh-AbW5D_E<<@qF$S<`m>*O`zgFxH`BI6W9aKEz;kKo;ZPh_uTK) z%07C28(qkzuj?PgOYjglHv{ff?6q~z`0=(l`5a4IA1$;$#|qak(!Gwz&w`8~NVTVhDfuWKwFw=%X z5nR+|zyV}W?8GxY*K(ENzq7uMAROpTO?kG}(~T&L7!$+;Rl2p2&`DO4BSp ztdgH)ZJYWG?+5Xh>r<^U%T=!nB8KC6$-rzUb$ZSX1!yh&hlx=7M`Bx~$|x&Zzg z%+0dH+m+>xxfnydWYs8H9Wa@V-`po`FZlli{{rwoC*@sfQ8!8)DPD@>|5TTax{FKF21qfm`A-9`gyh)$*UU z?r7(=zKnVff`DHjpsl@Ad|$SD%Xq41|HAK7mi*HFw3)4bX{>RLllN_27uQN>62DAk zKG9XF(-YbCm(s(^oSpp^jRRI^ZSG+MY`wx2lujk*_(V7zof!>gi*2dqW^h(F>Ev^c za*O`_nv@cm(4fMAqb8%#c+IYpTOI6(Ew)=nyG}ml=#Da9v)4}l1Gx@(k^O0l6y9+# zu{u$xcChs7`0lTIh$*b@q+?Xo$t%IT2znzDgpG<93g&?z_slmWAVDJVnbUF?NzM!JOU-qtgH zk((=I9GF3OqHDpz)iGgmWN^2mLZMLTRZc>;X4*!?El)Dfwm7VlJznY2Ez6gbzc~Jt zl#P331nxfTUm0WO+42aUHP3bruRiFn;kMTh@#bCZ_A7VOU^e#EBB5*&t9f-!q8cl5 zZ$M=wCcNE_5#=8b_qlRoq(%~rYozW_Pm6N7izU{YE7!Uso026Jv|W!wsVwm4_>~n% zD&%wRMvIp(3RYxC!Eq7~z?|kcQw~R?AG8$V6{4K!!kajhGU{7FkC0nJ1xcW?v4i_X z*gM34%7TWZdq` z+MX0@ay4hUPUj`ob9?a??JvFbAOmGCj*Oltxq57qdg8{ z{QhsbYNSY~$-T>RbUC?M7+6p{ zHo?TEi8o(o6R-2|mA9&^iPvJE;;O4hoQbMl~k9>kDuQ$`V(@JMXNcLDeW^EkH&Ilk@LxkluSir7uQKJe=oN zpNrf~dtaq^Q~IDGZ2pzQFav9Zt`ZmD?H<0^2=Y$|qb9LYL>t+?eNu4e> zs^ynl6eGjXXsTCP`SiFSGg+OkmLEX4p_x;UAsskD)w1k;F%iezYS{`)Fy8e%r5ac7 zoDNp8FD|6kU0VNo%*|E|p7T&K$kpuCeLd+Wc648O)~B#)z}##pWyJN3j-J1--YUMJW8%B;+f~O!sxW z`W`AK0=!Q7O}fHgO*+KfjTF2=HS(KHchcRuyM-3ok?@)?Q85zT3p}mmNi{86*sHz2 zSc}A2$ntJrN|z9?(u!66A@JG&ReDyVQC1PJ@(vDX9%Uq(ejqHgyE_T=Fr>(8=9~xa zVb2_h6AY8t&I2R5Cu1kBYsgy*?a`@doOl<8L?fSXnDc-saAx~iM?ku!PQzTvvn;tO zq1$m-04d6gUO&E6KRaqNZse2MjHcW^Z@bc)ENiu?sxw9mtTB* zYLt3*tafNNDoO%tZHl?)4X+;#H|JY&*YY>-nq1W>-Wyrof7!=NDN>I0w(^2I+1EpU z-lY13!uL%HC|Hi`s+}t@9LmIYl5`0pDif)Cc)2ofj#W{9XL$$5_c6I%up1Hn5sr{w zw5SR{HEEF6<$M~0gcrIRIEHESCERz|2M2r5_t{SeGlc11u+T&4*?XLpa;UO2mZs3c z*G*wa`lfScxurh1aHlB*zFOx+tGX?~&(fqX++_+xh|QUfHm-K^mVSe+JQNnO`eVF! z-%G^=KmzUu9>15pbtq1V`iz}8BndiXb~w#<@TQ+L>9AQy{+!J_oFceCXD=OoDf&>y zX*TmI@QJ=DpKhY_%`d%hAn**CWh-Gs--rbgXl%s4}^F#>wyxBy5WmlUsgaId5 z+>vp3d0u#=yMNz~ne(>B%$(s-`mq;}44{v)kB@xKv#B{6U+HqtYF&XtA?>tUgc}N1 zF#CZT-R@Ta-4!>fx$012o5p`c#7iH-?hpt+4r|*hj*?(Ju_rZc#K3uE`UW&aQTxp0 zG*#2G4ny{z)7K*;xBcS0)TTAycy#)6@DFL{)}X84UorjJd__Q+vX6y_^#a@0wW&=j z5b?zHN-)N;xyN?Vtt{jNOU!;plCa>wu$T^Up1SG>G(_rU*F#(nT#^Il}1emHpg{od3k zXlg(!f%ZjFUh(!ilq-$LUBIC{;53~dBVDr}gf>#!(ivau?R1~>avddXPkpKG@shq5 zTL{!+A&{}Ai)RLI7!G9%oBmM``U$K2Xgn=vtsiwSpW2ny0G+j>csvy8f(jJaz(9u$ z*WYVG{)+Oo=STZEX#IFA4MS@b0CR!o0p41#!2NqC^A#wmsdHtBLJgDI_~X-J?zC}M zBi=P6Yf}VT=!?Y>i2t2^aeVyDJMsK+HbRP(f~Dl9UTCGhA-%w}&$IAQJW^CIj)(7E z&#*&$gkyhi&XO|LD#~#;UkcW?-?G0_KWJ?Ro@bkJX{%~-EBih3=M5b-e}-E*$SObX zb?=iN(&wKo^R0(+J6FknEY?HfQcv%4EIEYqKG{mrK58ZLM}74@j=KE{+?IqH*^=k&?I!!hc|+^fsH=Oin9uocE8jOen(wsF zFDMCb^--R}yRZ-5erJs(54yEbSn6SBgD{2cs*@w9!>yyx$OPKxB1m8Sa2Z@HpJjh6` zH=vaHiw($egxgY{S|5NG>6H-(|3I`rYP|@5N(OJ=G8>n9PepW8 zE2j+X?avZuD{K9%7uB)$&-&tVDEV_!_&YAseB*Mj5{Lc6+GK*okXt#DpBYCfs%b>VnattkCnei$wfmAREwSjaP{ zqblBi+AZ@*>b4dEN;RWYJ*FCa2XA~{#mR6h8dYevsmo{AcfBMq_veAMnE9XROEcNf z6RF8@F1JFQMwBBU-K}WgYwNIB?_d5jnmXtDYa>H3ASy5*^z6kG15$k*47ruYPbTTvf&?Zohqk$4I?U2n9iFgOj6|0x^(g(sp{lY{aXK#NIrO)`3`0BN11pDfXblfVvU-YEW ztml{6A!h7+sZCKB8<(a>qwk~HgI}5obxyZ(wf#=jU>uc<9pdt}pIR!bCst$qZCJYNzUmt_>H)m! z0%D_EDeAzJIt+^pWn%O3hVftBPib4jyZ?Mz2-@9lUWc0szM8nDJkriaoSG#(+|FJ< z^}1kbXN6z?roN@%y&>zHgCNE_8g75nTixTv%24@OL5_TFrS373OysL8g(OvrWqCtx zj(nMApBYP!v-M|IQzHvIn+ogs?6Vfyz-FFZC`@y+Q)kQWy;=3qja90=(K+(Rb>MTorOf~fTyDZR<`wsu4y{RoHSS4L)J@8b9l=7Hr$SI`!qTTt#fv3*q zeR$(o=!_emhB=qz*`H}j>p_Qh=JfsEevmnb(I2*9k9qZn?gEA7X(euK%zU&&E!kzTbbj zUGJlteBl>-bl@c(e&J#SE4jp_&b~Cr?=zg0tq-u*E*%R?bm8#bOw-@BTQQZ$Xkqea zY}v0psfBI%bqv_g{d#d|i2GtW^+I#4@t?v|I7BgM8(3uURFL$T^He2A4$65K668acxy7EQD9dia=6tY3c zAyq<-bsDSr?LG~+ayZS}e|wdF!(P7ntuVvIDt_-R6uHsuD7;4(r2!7U6~Fm#U$MED{`njlZ{up2b6%5Z-@9OshK^b7zJlDdr2|V#jHu` z;U9_ERSqboY@ zanU4oi+~Sgy6sLasdN-cZc^&`ou&0~@_2;_0Cq3*#=c2gF z6;Q1EMxDCodu#N3Ltf;}&Zesv19RhXuIB_eXI)Qm=K*&vcV2Tp$sM!jGxfnkApZ0W z^y6}(Tr9<#8C!)gd_)GL;P0&)&W4QNcO7G_G5P?2qwz{cY>Q=|R zk*hkrELJV0NjL2JH1!#3>>LPR9A8$7d=fR< zr71jhMI5b)iHsWEM(BrEM9Q0r$J=Bz?PhbRX|egUG8l2e-sf?+6^%78$roWQNug`` z&_V02D+LbQ91R^2s={XjVUErr!JqQ$mfDVJXl!Npd6itIGNy{HdoUVPn>ILB8civx z(>+tvr#*PlGN)W^>9DH`bLVQ!PtE;kF6EE@N2el3ZKEc+`{|!9Q#mR^6&2Mr{0xP7 z{odeJR^TZ^Fa<)_vCI*e?@?ardQa~BYPEByYV$pnu(`f&@ARs`_K5eYJr-5T0l2+& z7Ob@cic_QjEdL@N)8=|LZ6^dg2oYTYx7XI(I*+`y`JSFGNH~aBOp-LX)i{vW)TZ5NEx?G| z;|uHCN^1(Fo|rIowrqbIMYr1S^`{y1Dcke#MVGrz+69TEz0~@$T|FI^gD+y2eF4Mv z1=|sS8b7hn?RRyQfo7(ZPjUqGgubEOulKFiK?x-{kKM)B*Pp#qN~$+Y{65T=$dsnz zSC6ad@RHxYQUBRmfpNm6Iv|lt6-{1cxNUdQzOBx8E{H zmsO16VI-eSR$&Q>hAqq~M@u{pKk%aMsUVstzWYp#Hl&OA-JCAsxZzQjIdPCcn4d4q(0q*Ni0_yxP=hHOIIYfk ze7fxg106@F+RhnhD)h=mNB{EgwXSbMjb0_%VT%l*RnfkL{Llk^Ku$N3qk@?b8J2!* z$_Crs5Nf5>wwO>lUMQZve^DqcR@1|_LlHDN<6O3?9#}dHZC~`Dqx}pUd3)I+;=p3qXd3}n z{|M$#B*LGFu`Pn1PP1)^qsigxU?#7_2U(xDksz}aZ=HoVp!aNF$I(aV5?fJE+DC}o zXj{>fnuQ)-+bcaW2cnMJJU!{a;N1>tfeKKnawOn#yvLSjqzUwzt=ve5qFLX7FaAjf zH=X6%zy`Ga8en}7=o$(q&X3G1oynIREbf0AX}oqwQOEWI9eVp#qNk5ZF%hWdyA?0t0bW!CY zY~fkxYCgvBMSVNZ!>Q~!^f;yw4|6H6`xGxuW#=J&3g)WdUG7evif(D~zrwiqok#O+kR-)SCLiz2OWnC1RWA zx}HCf0nd=(7!c)fDQ#|-a@6ZmV2pwffxJq#uOMEf4c{&i`Pcy*dn<_L*cFOXty_7= zR+2=c1k`k168$Xahl7Vv&(DBwfb+obfCEsYt_C0$NCGl}9H1DO49o&5HrbXW(-gl0 z;Fo9EUQ4F^gvU48zDuSfDyMb*--5DvoiA@kj~be}^>-xhGs#d_d6cv!nv?~rd46i; z)BHC_dK0gLh~EH5)tH-ht{D~Z1=GNd-kmP#XRIYa1_-oC&_?O1{v0ym#X#gki`3%2~Nsa93J1^*ZVrv#M4t(-q>8uO`{8AHo4XoZOe^mU1puX=!{nL&D(2hG{QG^3yGXy3+YSqsKz#_ zFMU)fbJ|+^(oI5y(>5y|i;mi9Ta!*7rs+0sIyJ?W&c=BNNC!k96u>Yc%X(8WX!iaQ z88nXGy)Yd%jDWlEf8xJ|t2iPce5>uzOdJXmZEt4MWEx^?&7^%ze=l~wqKd{IRzDm>66)VB z4{O4=Ir0-W(*W!cvu%q9(EezOH{cj}YyLf<%`t#(5H57so*PJi)&CV^TQLX?H59A! zAR5u<${;ERX2Ap$Crh{Tv!@yw2TCT(84;DLC)~?m$y|MD7ec=EoRzDj;Ybp)yzYkJAM6(+G zx`uITnM+asm-xRAbC+`KzYO#LlyUh#I6Cvt;=4gilx%#Fo>CSqxs((CJJY{;_WfTx z`%8z>Bz+(^E52iEFYaG0(TV=uE)?SlLq$mP>Q1+L1rcpk6RBx`-~{@;-@v}JX3v?v zY{5fI(<-JfSx5*sw(!TG)&sxwsV`eMzti}_r6I%#G=EU~?S|R5j>&Ywh;6%wnD81< z53?h<+kvK?_#Z*9EKOu#aPkA}O2|Cb`T1v_oe-AhvjZ{Lf5lLGVsmH}sg z0l*f3PcHs98uU~k;}yt*%MDR>?f>Im8ch4Cq2m>S0N^In-{*l}fXjdjAPD~ft^@cT zknh=_c0YYhqvskHu4$2{+Rm2IIicImqX0kxFcO%0e*c8&II2{>D--c$;9KAW;3Uul zya8+kE&#lg^=(Al2Alyt23mn;U>C3jxCC%M%75@T6K_wy;6BmmBgDFxUq*>BZ`q95 zrR57Ae28#rf=!u0Ln?(XuGSkU-A$Y)@gS9tOUY#5P8@pK_qP`DoG<`Z#B=&iru_6r zsX#tZQL$CP1cEyr$OF$RtSUMoj|h|;>!(vAkpNN?PYiUJ2Hzu4b-W;G;{6EKYMxTz z>ZDUsBJhEt)leaaJ1ec}PXg19G@>*2I0OwsA|!8Tk; z6r1OCbgfHdu6vo9y&Z%#R1^6G@+5yVtp|#PmNri}c(HfHMHtycK(Y!)%78vnDB|fq zQYyQ|50=do-skgKV#7+)z$PLWAiu<_#X2f3XX|tj;lZ3y+}DTlTd1IT;56@1GN6K= zQMO?+ru3mUTc1NcWz9zoT5}-8?^p+^V6!qV^X} zLxt$sYS)2N{Pg^g1Wn@Y7dXHt!d$w>V7l5)*f7?2LU}Pmf}3Ld4x?l$>m+!kC{#W|rdGgSfdS+_p1fqv1oZ@x`X6%!c@~W{U>@Vzy=N zI?rwH#yjn6P6hqzOUv3#F?cu#Fv!1eN#jRbHo~b@H-OHAZVRX@HNJk&ogub(luKN=o{xOM=`^de>IPdAsfme8c Gch-N4MC}X! delta 1151 zcmX|=e@t6d6vyv*?-gD6C#lZ`T-gubE{|H151m`MXE4>IN zs(>3*q_Ut@f|YcgRc14A6JU^ziMybQE{a|V(*x3Ry>60B`O1hAX7{BXI%s8^45FwD zcyJusVq6e~8y>cy;6=e`_Yt|Zktj{*PWnb+FMP;&;i9nKjqlijPlCt&Mu zRZ-O8&9fk}-e+tgJi)F#J0`(q_SRMku%8)g*X8Kn^%D6g#xbVuG)d6Mw(rW7^u$kO z2mTf}Yp8o0jF+(B76!qOe~SKEZ_|H_t4}dTscP$iC>^$Wj0!f5Vy+gwl9}yMfC2hP zLjYc8p2h|MI}PpWM&0Dtf$DP9f}IUHm;_);A(EA_+xuog z_{Gn@eyL?07+CRvQ9+mYI*|+L^;fs|)aaktCHc@KA#zCLffR}7FDLoFRFYR|NuElj_%|yW-;&vo z#><%AGX>_Oc$XC1Tl#qi`7dh*$q6>saYulY^s09jeDtjE6v%9+-y;-!iMQ~$M94UL U6Z%zpxw}*;X(^qptvlUr zsJ0_*w=MM7=_**ue4Lq&jvp=5rX$4+Zrh!i-C4V!?T+ZjR@ZIgWBu$!p}9$byXO}I zGq(H3$$8xGIluEe_xCtA?RCnd9R=*poX*7y7Y{E0VG?Pb59a5DSy2l%OFSOUIsgkLlLk+@mWF&CG-qt(}fLlZRnYK)f{0%yfgd^b~U91?Qk zkI*;w653V{i8-1r9^*X|(t@Wavhh{Fp^`kK$ZRE*Mr#tIJfZ3^#omx4t;T7;MV>X< z$N}R@o>6|Fk_*P&UPk#KB(@dF_Vztxrt^?1wlgJ+^6QYjU01=Z@{P9@+S|s?wfY(5 zK&V(oTd{8(N{c;TpSu<~Xa}(#iBUWs!6TV$O(tG(N@ zr;HsjS1`&m{UEkhqOVP)K}vkQWVmlZpHmhq{MSlcjPeitRAv-8L?%q9*q(wDAI*tp zSihhAK4Gc%kRJwLM85+_skn6&-!FQf`Vj26h#hTt7AX_wx;9)pHuRXSW=(ENlYQW< zYF=U-;ADOj8uoiQ`4iPN#L17MWc4tzQ7%^)&KQ;K%Dk9#(J=8j_gveuwX!bE-T7b~ ztVYlIVNhyTg{hJ>1djL(#`_qY|1Gt+{ZN^1B%1UxM#)#d4bZw=Q5!zA^(uaRV;iTd zMf8b_y@Jo+Hq>OwjIxH=@2QiGeI4??O8+$hXTGx^1_4-C56(^S3GPh! zYR)0n+%$vT{5@=(iDKh!N`XY~C>wxcDz%#L{FRi6%SZ zsoQ};XK~iMaDw}h*<>%!WD#p_o{1SZi}g;=>=Ah;TMDjg#=x`SJ16h10tSvH8x4$D z^W!stFWrT`tFn({%vs#OQXG$!_5S~*MX>panV=_Tz_ZwyWNEePp1{Df*mu5%ok^Br z&mq>_G81<%V!hEUqJi%!Z3_mS1^(@Kf_|s8h&4Ys6Liz}urtXu%V__(Ta)Z zoabXzSoX1MT4u&gN*8f&0p78=pc9>{&pcvwnuoke&ZMDar!bu8Fo<8NA6#bgzEt7< zo-$zs@~SWM(pVtT0pe)D;D`kDVF<1%a}C?p*WQ5aHRb$GNK3eR8a_jh)7Ke$h_$P-^rE8+*b=pFHSQO~A=^#maFWojg}zbdh2HriokQ zAgbx~W|A-QkgbD+E)Dw0$`Q*%0b z9oD~MOvlfYtS%3#uJau>0Jau6pk5pkYnaondiy9 zNlh8wgkHh&j5U22=-tvDl|BmiuPJ+pe*WSD?3*|yr^{6y2csTWH{Ki#E^gFQ&W$&e zf1r%aCi{U8Cfd5m&J5y!J-JWf2DL;UV`omqwd!O)Y%ask0;kK zW#qTX_c2DIODSb8wxR+L18m-r0p z89U_as|{85)@>e8elo$@?X53i8YQ?JnEo z_Hkd7_cbJ9qqBXGKA%~6ckr3uW29+az~@`Z=Jb244-MkxFQVCi$YFN+A&bmU;mkc|}t=e;08 z5;83o`gGBCrSdEFRGTnrHWX|)ubS`2hAKkJG7DHCLRvE|sW-wqntE>Xal56Ob#uXo+geB-wQQv9eM?niiBBh$p4WoAHS2mU_?kwKK7+Hd;Zrqr z$vx-oIOm-j$CfJ&?yBc1_7-i(?M*+ze!_|G`7uok`Ze5cOF$V{spWO7eF@h7^x&u1 zr)a^4wI0%xW%G_;6M-)dn}U1gzR-RQ3Jtg7q{ zC&t^XS?-d-42c_6xut_6UTIjGhv_kz!Skz|yr~%5r);KNVYy0o(+OZ=Z7%Gu^1F1IHXu^qMXS~r& z33aniSa09u?91xcf?rHA_B4AdULyGuLt?A{ni=bJ>vu3nUqSZS?5A-pgNq)ET5wcj z-5K)fJ8d4pPwhkz53)HEq{HSQJ@*`BGbV{^-q!S1{Mb|R@eBd|5X5h%fqAvO77R|2 z1nW}fS+dq@&3hxF?`@6k7+8#7ut={tKwz<_$tWM%Lbo}tjGtK@2FdNZtv$7l^jWRm zAG$4%$Cq2ScD2NpudeRe-rb@Fhqde_Fy7|Tg8x1%{b5%6cvkYyN+)Nf6SLCsS?S2E z^vhZ4T@62{LN>BZobS!3`9$pz)7=-EHnQ`+=xQ1=@L$ZW>GH6n6-&E3NoXI&b!gd< zGuFmhwsbX>(Hp1XLep8aQjI}Ps5#d}yI;W%6>L482ley@GGP&D&8#4BbWN^Wm?_YY z+B0D-_;T3jzR+BTAAo)_H{sv>6b~6}6&4D}2e$3Z29lMN%L%^KWNpsZrm5huAzHdkO}36_RfpdHRNFF*!F+@17Qah~n~T zaR-XlY4Pn`5C1;{=oHRv@tzo<{`8RJs-}Ya=(t+&@BqE0rfm}w)8ic+pf?&_QAcB_ zpAP`&ZPIOL7U| zTZ)F-Nt10OayRli+`WQpD!9&1PgE`V^GW=ZL7fUlrtm{JHu#)VWW#(5i__RK|52|Q zTPOhu7oiKl2u_r#&ZDkpOyG*?0_tXV4%EkV6Y6PP0<@xTLNZf-J`vhudMfqDe`tDQ zdIt5^C&9^>o=yD?gntFNG=NY7&Y13?0pjijS4?-(0P!oKKBgDY0LE3&inT!_@(mGQ5(t4HMp#|Mc8LL=Kl#=OygS{&C(p z_uO;Nz2|rDIrs7Fy4H3VkpZ@+xNw0d7ct{NDS3!l3G`H6&;Am!7ru5fl-E;iB705v zb>b!U787E&n@+z@TqM-y5WyFQ@q<(qL+~~j>L&3y-lERZW9Yy?t;F&;C!o&!{Ht;A01vSE|J8^N31$WIL-i~vaU+3orNmdqG!jA=a zh&BMEC`faILsYMgBbFTq*vK{ZH7gOn1pk%E$ha(}`tvvf>{o?z9sRE3cFmXqVi2EV zmJ*%#7JOYeD`wOEWkI4(*0Zwyizv^zM zs?@LSU{grZ{df}bC-5gROAB@eJ2=0;45F`=RNWK)&&A{p$O>|bl}JA_Zq(C9X^19a zeQes}kAuxm|EIkrB6IuHzLQGig^|c_ouv07{vqj3WVNJ-Za1v9QMwV)#6~ooCsoIi z0o}(W4M*$gZW`9RA};5K{UxA1g5Ql@QU9a(KXea>fe8At;G0!;UkmXPC1kGh#r6}W zaX!WndrUdGouDiCu?ATm3-Q_{S-3c>18h>l*c8VS&3IK@P9owbLn_$f2NK8K2Wh{B zpO4d1t*a1zJ8lIHS1yFViQ5WZWis1gbs4)l?eU{1kL@DL5ML-8yHr)g3iou!Vq?eD z)m9JO2)Wb+x>ENvswj2dx_aBc-w0&|g!m~h9*9rPMEoW%LMlh5OXbMw>d)-7lVjQ{ zIM55&7q5#)Jn1#NSWx^N#$x<=@=X5e59h@aWY#(S@%)nc#5v^M2J!X*B^&U`gkr2q zE^j{@qyxzay@`wsQ|Ou0TBtcmky2{uKpE(h9Z+{tlH<~N+R~(Y7IHlh^@!Lf)Pg6! zPMYsfeCE&jApTn^KH@XCm=OCADBAG%$;ani z&PPndyqau^$A3%NMXbU4)E43_-j$kxXH!{nUKnSmWoF8ua_)x9S|tm?&`sBhs=NMl zu8@<3$q;T#GnCy3ZD_GnZCG#S4!M4pb;wB#@}7BPCETejqDL0K3=zHM+;!IyaQ`gg zKJHhXKMmm%X?0K(LfQkw5?q~LK_&+Aj`S|#Gn|mIl=ui&XH*b9czeb>`8E&jpq$89 z>AW~jmJ&wlSvY*}b=bewZ8g$d=VW4+Ec_YQW`5q3>TN4RY`nwj{@&%#?Hr`J1fPYA zsdE9Czn558`KFBelZKS>I_YSO20)XAF`xYMKRdaf-Ivx#P1D0 z(K2wCj@io9RnPlUd4cW)@t*A8s=HuS2=i0+6Xfk;+?dm-up>D&Pq(^NT=l3dd=WC# z%R;-XhU@gI40x4l7HwF6NlaeCjv4`_XJiXm$>&lxoi|;Tdl$I|YxLEHuizpEVS4N*DPeq#b6LvcKZ}7ETpl z$!yma-SrW=w9hV$$igEbRiLfXSa*85Bgfz{d;2&lKvQMjZth@!X(!Fzz1*PyLzR1b zxbL`L*zk1tvWT3A@6z#OB9ucwN7#9iyaKWz=R255zce3FP zsIo9XRRX@O;%Auikp*LjHRw6zy?g=Qn)iHG?p;5;HH}(5YAn<$f}5!~wwZ^rhGpR& zVFGGO>p_-T9{>X8^{D9Ztrh=y92GKlzi4 zM~xfPy5J|ObumCYM@ad>;$OsTa~t4EAtZbxw}iNY$8vK_H)hm>Z~~F~O^5nj2sE9I z7_#o_6X}({KPt^gxpjHDnsSG2Lf*0**XHH4mpC$?jIGSv*ta>hvai`%*S|Rtu=B}i zy2D8VX0q_lIk^nvOLOvrAYYi1TS10v60zS6@&|MBQIJo}$(KMrGACaLd0fWK|F+8*}kRQ!`=1`T2Q7Ic~_mrAEAW70i)F|Fn(4ww@)8dP9u)w4)h>E5{lR7CXHi8%eu)*LZ5dBf{y+SAbcMs_1 zTQ;}^Q6d>&NO45DLy%r$(K)|feFXGAP%qGSps#^8SfR1Qq4}U&T`xWzUi2`bi@fKs!ftpQJ86X82EH2j HVc`D-?D9Os diff --git a/Tools/bootloaders/CubeRedSecondary_bl.hex b/Tools/bootloaders/CubeRedSecondary_bl.hex index 6f4adbe5be9c81..02f6e1d4a642c0 100644 --- a/Tools/bootloaders/CubeRedSecondary_bl.hex +++ b/Tools/bootloaders/CubeRedSecondary_bl.hex @@ -1,29 +1,29 @@ :020000040800F2 :1000000000060020E1020008E3020008E302000805 :10001000E3020008E3020008E3020008E30200082C -:10002000E3020008E3020008E3020008F1200008F0 +:10002000E3020008E3020008E3020008752200086A :10003000E3020008E3020008E3020008E30200080C :10004000E3020008E3020008E3020008E3020008FC -:10005000E3020008E3020008BD240008E9240008C8 -:1000600015250008412500086D250008E302000859 -:10007000E3020008E3020008E3020008E3020008CC -:10008000E3020008E3020008E3020008E3020008BC -:10009000E3020008E3020008E302000899250008D3 +:10005000E3020008E3020008D1290008FD29000896 +:10006000292A0008552A0008812A0008DD0F000807 +:1000700005100008311000085D1000088910000804 +:10008000B1100008DD100008E3020008E3020008D8 +:10009000E3020008E3020008E3020008AD2A0008BA :1000A000E3020008E3020008E3020008E30200089C :1000B000E3020008E3020008E3020008E30200088C :1000C000E3020008E3020008E3020008E30200087C :1000D000E3020008E3020008E3020008E30200086C -:1000E000FD250008E3020008E3020008E30200081F -:1000F000E3020008E3020008E3020008E30200084C -:10010000E3020008E302000899260008E302000861 +:1000E000112B0008E3020008E3020008E302000805 +:1000F000E3020008E3020008E30200080911000817 +:10010000E3020008E3020008AD2B0008E302000848 :10011000E3020008E3020008E3020008E30200082B -:10012000E3020008E3020008E3020008E30200081B -:10013000E3020008E3020008E3020008E30200080B +:10012000351100085D11000889110008B51100089B +:10013000E1110008E3020008E3020008E3020008FE :10014000E3020008E3020008E3020008E3020008FB -:10015000E3020008E3020008E3020008E3020008EB +:10015000091200083512000861120008E3020008C5 :10016000E3020008E3020008E3020008E3020008DB :10017000E3020008E3020008E3020008E3020008CB -:10018000E3020008E3020008712600088526000843 +:10018000E3020008E3020008852B0008992B000811 :10019000E3020008E3020008E3020008E3020008AB :1001A000E3020008E3020008E3020008E30200089B :1001B000E3020008E3020008E3020008E30200088B @@ -51,43 +51,43 @@ :100310004F8FBFF36F8F40F20000C0F2F0004EF637 :100320008851CEF200010860BFF34F8FBFF36F8F8B :100330004FF00000E1EE100A4EF63C71CEF20001E3 -:100340000860062080F31488BFF36F8F01F028FD4A -:1003500001F02AFE4FF055301F491B4A91423CBF25 +:100340000860062080F31488BFF36F8F01F0F4FF7C +:1003500002F0F6F84FF055301F491B4A91423CBF5E :1003600041F8040BFAE71D49184A91423CBF41F895 :10037000040BFAE71A491B4A1B4B9A423EBF51F83D :10038000040B42F8040BF8E700201849184A914280 -:100390003CBF41F8040BFAE701F040FD01F086FE96 +:100390003CBF41F8040BFAE702F00CF802F06EF9EA :1003A000144C154DAC4203DA54F8041B8847F9E7A6 :1003B00000F042F8114C124DAC4203DA54F8041B21 -:1003C0008847F9E701F028BD000600200022002040 +:1003C0008847F9E701F0F4BF000600200022002072 :1003D0000000000808ED00E00000002000060020FA -:1003E000582900080022002030220020302200205E -:1003F000702F0020E0020008E0020008E002000880 +:1003E000402F000800220020302200203022002070 +:1003F000F82F0020E0020008E0020008E0020008F8 :10040000E00200082DE9F04F2DED108AC1F80CD064 :10041000D0F80CD0BDEC108ABDE8F08F002383F338 -:1004200011882846A047002001F08CF9FEE701F072 -:10043000FFF800DFFEE7000038B500F0ADFB01F08B -:100440006FFC054601F0A2FC0446D0B90F4B9D425B -:1004500019D001339D4242F2107512BF04460025A7 -:100460000124002001F066FC0CB100F077F800F0E8 -:1004700023FD00F0EFFB284600F0F0F800F06EF8E6 -:10048000F9E70025EDE70546EBE700BF010007B0FF -:1004900008B500F0ABFBA0F120035842584108BD5D +:1004200011882846A047002001F006FCFEE701F0F5 +:100430009FFB00DFFEE7000038B500F009FC00F08C +:1004400061FD01F0D7FE054601F00AFF0446C0B980 +:100450000E4B9D4217D001339D4242F2107512BFE0 +:10046000044600250124002001F0CEFE0CB100F06E +:1004700075F800F01FFD284600F0F0F800F06EF867 +:10048000F9E70025EFE70546EDE700BF010007B0FB +:1004900008B500F0A9FBA0F120035842584108BD5F :1004A00007B541F21203022101A8ADF8043000F0B3 -:1004B000BBFB03B05DF804FB38B5302383F3118830 -:1004C000174803680BB101F0FBF90023154A4FF4FC -:1004D0007A71134801F0EAF9002383F31188124C72 +:1004B000B9FB03B05DF804FB38B5302383F3118832 +:1004C000174803680BB101F075FC0023154A4FF47F +:1004D0007A71134801F064FC002383F31188124CF5 :1004E000236813B12368013B2360636813B1636819 :1004F000013B63600D4D2B7833B963687BB90220F3 -:1005000000F070FC322363602B78032B07D1636803 -:100510002BB9022000F066FC4FF47A73636038BD9B +:1005000000F06EFC322363602B78032B07D1636805 +:100510002BB9022000F064FC4FF47A73636038BD9D :1005200030220020B9040008502300204822002077 :10053000084B187003280CD8DFE800F00805020803 -:10054000022000F045BC022000F038BC024B002223 +:10054000022000F043BC022000F036BC024B002227 :100550005A6070474822002050230020F8B5394BDC :10056000394A1C46196801316BD004339342F9D1E2 :100570006268364B9A4264D9354B9B6803F100633D -:1005800003F500339A425CD2002000F089FB022080 +:1005800003F500339A425CD2002000F087FB022082 :10059000FFF7CEFF2F4B00219A6C99641A6F1967F1 :1005A0001A6FDA6CD9645A6F59675A6F1A6D1965E8 :1005B0009A6F99679B6F72B64FF0E023C3F8084DAE @@ -102,14 +102,14 @@ :100640002047F8BD0000020820000208FFFF010853 :10065000002200200045025800ED00E02DE9F04F97 :1006600093B0B44B2022FF2100900AA89D6800F0AF -:10067000CDFBB14A1378A3B90121B04811700360D2 -:10068000302383F3118803680BB101F019F90023BB -:10069000AB4A4FF47A71A94801F008F9002383F3BB +:10067000CBFBB14A1378A3B90121B04811700360D4 +:10068000302383F3118803680BB101F093FB00233F +:10069000AB4A4FF47A71A94801F082FB002383F33F :1006A0001188009B13B1A74B009A1A60A64A1378D1 :1006B000032B03D000231370A24A53604FF0000AAB -:1006C000009CD3465646D146012000F081FB24B160 -:1006D0009C4B1B68002B00F02682002000F086FA5D -:1006E0000390039B002BF2DB012000F067FB039BD0 +:1006C000009CD3465646D146012000F07FFB24B162 +:1006D0009C4B1B68002B00F02682002000F084FA5F +:1006E0000390039B002BF2DB012000F065FB039BD2 :1006F000213B1F2BE8D801A252F823F07D07000808 :10070000A507000839080008C9060008C90600083E :10071000C9060008CB0800089B0A0008B5090008B4 @@ -121,547 +121,641 @@ :10077000C9060008C9060008390800080220FFF76A :1007800087FE002840F0F981009B022105A8BAF1FC :10079000000F08BF1C4641F21233ADF8143000F0D0 -:1007A00043FA91E74FF47A7000F020FA071EEBDB72 +:1007A00041FA91E74FF47A7000F01EFA071EEBDB76 :1007B0000220FFF76DFE0028E6D0013F052F00F272 :1007C000DE81DFE807F0030A0D101336052304214C -:1007D00005A8059300F028FA17E004215548F9E729 +:1007D00005A8059300F026FA17E004215548F9E72B :1007E00004215A48F6E704215948F3E74FF01C0862 -:1007F000404608F1040800F055FA0421059005A8C8 -:1008000000F012FAB8F12C0FF2D101204FF00009DC -:1008100000FA07F747EA0B0B5FFA8BFB00F042FB8D +:1007F000404608F1040800F053FA0421059005A8CA +:1008000000F010FAB8F12C0FF2D101204FF00009DE +:1008100000FA07F747EA0B0B5FFA8BFB00F040FB8F :1008200026B10BF00B030B2B08BF0024FFF738FE9B :100830004AE704214748CDE7002EA5D00BF00B0373 :100840000B2BA1D10220FFF723FE074600289BD0E7 -:100850000120002600F024FA0220FFF769FE5FFA6B -:1008600086F8404600F02CFA0446B0B103994046A1 -:100870000136A1F140025142514100F031FA002805 +:100850000120002600F022FA0220FFF769FE1FFAAD +:1008600086F8404600F02AFA0446B0B103994046A3 +:100870000136A1F140025142514100F02FFA002807 :10088000EDD1BA46044641F21213022105A83E46B4 -:10089000ADF8143000F0C8F916E725460120FFF73F -:1008A00047FE244B9B68AB4207D9284600F0FAF973 +:10089000ADF8143000F0C6F916E725460120FFF741 +:1008A00047FE244B9B68AB4207D9284600F0F8F975 :1008B000013040F067810435F3E70025224BBA464A :1008C0003E461D701F4B5D60A8E7002E3FF45CAFF5 :1008D0000BF00B030B2B7FF457AF0220FFF728FE22 -:1008E000322000F083F9B0F10008FFF64DAF18F0A8 +:1008E000322000F081F9B0F10008FFF64DAF18F0AA :1008F00003077FF449AF0F4A08EB05039268934260 :100900003FF642AFB8F5807F3FF73EAF124BB84598 -:10091000019323DD4FF47A7000F068F90390039A95 +:10091000019323DD4FF47A7000F066F90390039A97 :10092000002AFFF631AF039A0137019B03F8012B30 :10093000EDE700BF002200204C23002030220020E1 :10094000B90400085023002048220020042200207F :10095000082200200C2200204C220020C820FFF793 :1009600097FD074600283FF40FAF1F2D11D8C5F1A2 :1009700020020AAB25F0030084494245184428BFF1 -:100980004246019200F038FA019AFF217F4800F0B8 -:100990003DFA4FEAA803C8F387027C492846019331 -:1009A00000F03CFA064600283FF46DAF019B05EBD2 +:100980004246019200F036FA019AFF217F4800F0BA +:100990003BFA4FEAA803C8F387027C492846019333 +:1009A00000F03AFA064600283FF46DAF019B05EBD4 :1009B000830533E70220FFF76BFD00283FF4E4AE28 -:1009C00000F0ACF900283FF4DFAE0027B846704BCA +:1009C00000F0AAF900283FF4DFAE0027B846704BCC :1009D0009B68BB4218D91F2F11D80A9B01330ED038 :1009E00027F0030312AA134453F8203C0593404612 -:1009F000042205A9043700F087FA8046E7E7384665 -:100A000000F050F90590F2E7CDF81480042105A814 -:100A100000F00AF902E70023642104A8049300F01F -:100A2000F9F800287FF4B0AE0220FFF731FD00286E -:100A30003FF4AAAE049800F067F90590E6E70023BA -:100A4000642104A8049300F0E5F800287FF49CAE2C +:1009F000042205A9043700F0DBFA8046E7E7384611 +:100A000000F04EF90590F2E7CDF81480042105A816 +:100A100000F008F902E70023642104A8049300F021 +:100A2000F7F800287FF4B0AE0220FFF731FD002870 +:100A30003FF4AAAE049800F065F90590E6E70023BC +:100A4000642104A8049300F0E3F800287FF49CAE2E :100A50000220FFF71DFD00283FF496AE049800F039 -:100A600055F9EAE70220FFF713FD00283FF48CAEAA -:100A700000F064F9E1E70220FFF70AFD00283FF4E7 -:100A800083AE05A9142000F05FF907460421049005 -:100A900004A800F0C9F83946B9E7322000F0A6F8FA +:100A600053F9EAE70220FFF713FD00283FF48CAEAC +:100A700000F062F9E1E70220FFF70AFD00283FF4E9 +:100A800083AE05A9142000F05DF907460421049007 +:100A900004A800F0C7F83946B9E7322000F0A4F8FE :100AA000071EFFF671AEBB077FF46EAE384A07EB48 :100AB0000903926893423FF667AE0220FFF7E8FC15 :100AC00000283FF461AE27F003074F44B9453FF4D7 -:100AD000A5AE484609F1040900F0E4F804210590A8 -:100AE00005A800F0A1F8F1E74FF47A70FFF7D0FC09 -:100AF00000283FF449AE00F011F9002844D00A9BC9 -:100B000001330BD008220AA9002000F087F9002841 -:100B10003AD02022FF210AA800F078F9FFF7C0FCA4 -:100B20001C4800F015FE13B0BDE8F08F002E3FF416 +:100AD000A5AE484609F1040900F0E2F804210590AA +:100AE00005A800F09FF8F1E74FF47A70FFF7D0FC0B +:100AF00000283FF449AE00F00FF9002844D00A9BCB +:100B000001330BD008220AA9002000F085F9002843 +:100B10003AD02022FF210AA800F076F9FFF7C0FCA6 +:100B20001C4801F08FF813B0BDE8F08F002E3FF4A1 :100B30002BAE0BF00B030B2B7FF426AE00236421AE -:100B400005A8059300F066F8074600287FF41CAE60 +:100B400005A8059300F064F8074600287FF41CAE62 :100B50000220FFF79DFC804600283FF415AEFFF70A -:100B60009FFC41F2883000F0F3FD059800F0B2F9E7 -:100B700046463C4600F096F9A6E506464EE64FF09E +:100B60009FFC41F2883001F06DF8059800F0B0F973 +:100B700046463C4600F094F9A6E506464EE64FF0A0 :100B8000000901E6BA467EE637467CE64C220020A4 -:100B900000220020A086010070470000104B70B5B5 -:100BA0001B780C460133DBB2012B12D80D4B1D68AC -:100BB0004FF47A732968A2FB033222460E6A01467B -:100BC0002846B047844204D1074B002201201A7006 -:100BD00070BD4FF4FA7000F0BBFD0020F8E700BFD5 -:100BE00010220020142200209C230020002307B59F -:100BF000024601210DF107008DF80730FFF7CEFF07 -:100C000020B19DF8070003B05DF804FB4FF0FF3002 -:100C1000F9E700000A46042108B5FFF7BFFF80F09E -:100C20000100C0B2404208BD074B0A4630B41978F3 -:100C3000064B53F82140014623682046DD69044BEA -:100C4000AC4630BC604700BF9C230020142200202B -:100C5000A086010070B5104C0025104E00F038FF42 -:100C600020803068238883420CD8002520880138F2 -:100C700000F02AFF23880544013BB5F5802F23802F -:100C8000F4D370BD00F020FF336805440133B5F59F -:100C9000003F3360E5D3E8E79E230020582300207F -:100CA00000F0F4BF00F1006000F50030006870470C -:100CB00000F10060920000F5003000F06BBF000012 -:100CC000054B1A68054B1B889B1A834202D91044B6 -:100CD00000F0FABE00207047582300209E23002019 -:100CE00038B50446074D29B128682044BDE838408E -:100CF00000F002BF2868204400F0ECFE0028F3D08A -:100D000038BD00BF582300200020704700F1FF507D -:100D100000F58F10D0F8000870470000064991F8E0 -:100D2000243033B100230822086A81F82430FFF709 -:100D3000BFBF0120704700BF5C230020014B186833 -:100D4000704700BF0010005C194B013803220844B3 -:100D500070B51D68174BC5F30B042D0C1E88A642F9 -:100D60000BD15C680A46013C824213460FD214F94B -:100D7000016F4EB102F8016BF6E7013A03F1080387 -:100D8000ECD181420B4602D22C2203F8012B042421 -:100D9000094A1688AE4204D1984284BF967803F877 -:100DA000016B013C02F10402F3D1581A70BD00BF7F -:100DB0000010005C18220020B8270008022803D188 -:100DC000024B4FF080629A61704700BF000C0258DE -:100DD000022803D1024B4FF480629A61704700BF32 -:100DE000000C0258022804D1024A536983F480633C -:100DF00053617047000C0258002310B5934203D092 -:100E0000CC5CC4540133F9E710BD00000244034632 -:100E1000934202D003F8011BFAE770472DE9F8432B -:100E20001F4D14460746884695F8242052BBDFF82C -:100E300070909CB395F824302BB92022FF214846AE -:100E40002F62FFF7E3FF95F824004146C0F1080246 -:100E500005EB8000A24228BF2246D6B29200FFF7DF -:100E6000CBFF95F82430A41B17441E449044E4B2F1 -:100E7000F6B2082E85F82460DBD1FFF74FFF00287B -:100E8000D7D108E02B6A03EB82038342CFD0FFF770 -:100E900045FF0028CBD10020BDE8F8830120FBE707 -:100EA0005C230020024B1A78024B1A70704700BF77 -:100EB0009C23002010220020034B04490B60044BAC -:100EC000186800F01BBB00BF80841E008423002034 -:100ED00014220020094B1822002110B504461846A0 -:100EE000FFF794FF064A074B01461278046053F857 -:100EF0002200BDE8104000F001BB00BF84230020A9 -:100F00009C2300201422002030B50A44084D914251 -:100F10000DD011F8013B5840082340F30004013B79 -:100F20002C4013F0FF0384EA5000F6D1EFE730BD08 -:100F30002083B8ED026843681143016003B118478C -:100F400070470000024A136843F0C0031360704703 -:100F500000780040024A136843F0C00313607047F2 -:100F6000007C004037B51A4C1A4D204600F0BAFA02 -:100F700004F11400009400234FF40072164900F0AD -:100F800077F94FF40072154904F138000094144BBE -:100F900000F0F0F9134BC4E91735134C204600F06C -:100FA000A1FA04F1140000234FF400720F490094D9 -:100FB00000F05EF90E4B4FF400720E4904F1380058 -:100FC000009400F0D7F90C4BC4E9173503B030BDDD -:100FD000A023002000E1F5057824002078280020D7 -:100FE000450F0008007800400C24002078260020DF -:100FF000550F0008782A0020007C0040037C30B5A3 -:10100000274C002918BF0C46012B0CD1254B9842C8 -:1010100036D1254B9A6C42F080429A641A6F42F0A6 -:1010200080421A671B6F2268036EC16D03EB520387 -:101030008466B3FBF2F36268150442BF23F0070530 -:1010400003F0070343EA4503CB60A36843F0400382 -:101050004B60E36843F001038B6042F4967343F006 -:1010600001030B604FF0FF330B62510505D512F001 -:10107000102211D0B2F1805F10D080F8643030BD02 -:101080000A4B9842CFD1084B9A6C42F000429A64C6 -:101090001A6F42F00042C4E77F23EEE73F23ECE7FC -:1010A000C8270008A0230020004502580C24002077 -:1010B0002DE9F047C66D05463768F46921073462AB -:1010C0001AD014F0080118BF4FF48071E20748BF2E -:1010D00041F02001A3074FF0300348BF41F0400129 -:1010E000600748BF41F0800183F31188281DFFF796 -:1010F00021FF002383F31188E2050AD5302383F30F -:1011000011884FF48061281DFFF714FF002383F33B -:1011100011884FF030094FF0000A14F0200838D140 -:101120003B0616D54FF0300905F1380A200610D5D8 -:1011300089F31188504600F051F9002836DA082169 -:10114000281DFFF7F7FE27F080033360002383F3A9 -:101150001188790614D5620612D5302383F31188DD -:10116000D5E913239A4208D12B6C33B127F04007FD -:101170001021281DFFF7DEFE3760002383F311885E -:10118000E30618D5AA6E1369ABB15069BDE8F04704 -:10119000184789F31188736A284695F86410194036 -:1011A00000F0BAF98AF31188F469B6E7B06288F3FF -:1011B0001188F469BAE7BDE8F0870000F8B5154674 -:1011C000826804460B46AA4200D28568A169266956 -:1011D000761AB5420BD218462A46FFF70DFEA369D0 -:1011E0002B44A3612846A3685B1BA360F8BD0CD900 -:1011F000AF1B18463246FFF7FFFD3A46E168304420 -:10120000FFF7FAFDE3683B44EBE718462A46FFF791 -:10121000F3FDE368E5E7000083689342F7B5044611 -:10122000154600D28568D4E90460361AB5420BD25F -:101230002A46FFF7E1FD63692B4463612846A368F2 -:101240005B1BA36003B0F0BD0DD93246AF1B01910B -:10125000FFF7D2FD01993A46E0683144FFF7CCFD33 -:10126000E3683B44E9E72A46FFF7C6FDE368E4E7A5 -:1012700010B50A440024C361029B8460C16002610E -:101280000362C0E90000C0E9051110BD08B5D0E94E -:101290000532934201D1826882B98268013282604C -:1012A0005A1C426119700021D0E904329A4224BFCD -:1012B000C368436100F068FA002008BD4FF0FF30BA -:1012C000FBE7000070B5302304460E4683F3118817 -:1012D000A568A5B1A368A269013BA360531CA361E3 -:1012E00015782269934224BFE368A361E3690BB1D7 -:1012F00020469847002383F31188284607E03146AB -:10130000204600F031FA0028E2DA85F3118870BD3A -:101310002DE9F74F04460E4617469846D0F81C9024 -:101320004FF0300A8AF311884FF0000B154665B173 -:101330002A4631462046FFF741FF034660B9414641 -:10134000204600F011FA0028F1D0002383F3118821 -:10135000781B03B0BDE8F08FB9F1000F03D0019006 -:101360002046C847019B8BF31188ED1A1E448AF36F -:101370001188DCE7C160C361009B82600362C0E941 -:1013800005111144C0E9000001617047F8B5044639 -:101390000D461646302383F31188A768A7B1A368CA -:1013A000013BA36063695A1C62611D70D4E9043279 -:1013B0009A4224BFE3686361E3690BB12046984712 -:1013C000002080F3118807E03146204600F0CCF978 -:1013D0000028E2DA87F31188F8BD0000D0E9052380 -:1013E00010B59A4201D182687AB98268002101322F -:1013F00082605A1C82611C7803699A4224BFC368C8 -:10140000836100F0C1F9204610BD4FF0FF30FBE7CB -:101410002DE9F74F04460E4617469846D0F81C9023 -:101420004FF0300A8AF311884FF0000B154665B172 -:101430002A4631462046FFF7EFFE034660B9414693 -:10144000204600F091F90028F1D0002383F31188A1 -:10145000781B03B0BDE8F08FB9F1000F03D0019005 -:101460002046C847019B8BF31188ED1A1E448AF36E -:101470001188DCE7026843681143016003B1184733 -:10148000704700001430FFF743BF00004FF0FF33F8 -:101490001430FFF73DBF00003830FFF7B9BF000040 -:1014A0004FF0FF333830FFF7B3BF00001430FFF7C1 -:1014B00009BF00004FF0FF311430FFF703BF0000F9 -:1014C0003830FFF763BF00004FF0FF323830FFF7CE -:1014D0005DBF0000012914BF6FF0130000207047AA -:1014E000FFF740BD044B036000234360C0E90233B3 -:1014F00001230374704700BFE027000810B53023B4 -:10150000044683F31188FFF779FD0223002023743A -:1015100080F3118810BD000038B5C36904460D463C -:101520001BB904210844FFF7A5FF294604F1140064 -:10153000FFF7ACFE002806DA201D4FF40061BDE87D -:101540003840FFF797BF38BD0023826803750369F1 -:101550001B6899689142FBD25A6803604260106030 -:101560005860704700238268037503691B68996897 -:101570009142FBD85A68036042601060586070471F -:1015800008B50846302383F311880B7D032B05D063 -:10159000042B0DD02BB983F3118808BD8B69002271 -:1015A0001A604FF0FF338361FFF7CEFF0023F2E7AD -:1015B000D1E9003213605A60F3E70000FFF7C4BFBF -:1015C000054BD96808751868026853601A600122D3 -:1015D000D8600275FEF716BF782C00200C4B30B592 -:1015E000DD684B1C87B004460FD02B46094A68467D -:1015F00000F05CF92046FFF7E3FF009B13B168465B -:1016000000F05EF9A86907B030BDFFF7D9FFF9E730 -:10161000782C002081150008044B1A68DB6890685C -:101620009B68984294BF002001207047782C0020CE -:10163000084B10B51C68D868226853601A600122F4 -:10164000DC602275FFF78EFF01462046BDE81040A2 -:10165000FEF7D8BE782C0020044B1A68DB6892682D -:101660009B689A4201D9FFF7E3BF7047782C0020AE -:1016700038B5074C012300250649074823706560EB -:1016800000F03AFC0223237085F3118838BD00BFB7 -:10169000E02E00200C280008782C002000F046B92D -:1016A000EFF3118020B9EFF30583302282F3118824 -:1016B0007047000010B530B9EFF30584C4F3080497 -:1016C00014B180F3118810BDFFF7C6FF84F31188B1 -:1016D000F9E700008B600223086108468B8270479F -:1016E0008368A3F1840243F8142C026943F8442C64 -:1016F000426943F8402C094A43F8242CC268A3F1FC -:10170000200043F8182C022203F80C2C002203F8C6 -:101710000B2C034A43F8102C704700BF1D0400082F -:10172000782C002008B5FFF7DBFFBDE80840FFF785 -:1017300045BF0000024BDB6898610F20FFF740BFF8 -:10174000782C0020302383F31188FFF7F3BF0000CB -:1017500008B50146302383F311880820FFF73EFFC8 -:10176000002383F3118808BD064BDB6839B142685A -:1017700018605A60136043600420FFF72FBF4FF0DA -:10178000FF307047782C00200368984206D01A6812 -:101790000260506018469961FFF710BF7047000063 -:1017A000036810B59C68A2420CD85C688A600B6024 -:1017B0004C602160596099688A1A9A604FF0FF3333 -:1017C000836010BD121B1B68ECE700000A2938BFBC -:1017D0000A2170B504460D460A26601900F084FB04 -:1017E00000F06CFB041BA54203D8751C04462E4672 -:1017F000F3E70A2E04D90120BDE8704000F0BCBB1D -:1018000070BD0000F8B5144B0D460A2A4FF00A07C8 -:10181000D96103F11001826038BF0A224160196961 -:101820001446016048601861A81800F04DFB00F0F4 -:1018300045FB431B0646A34206D37C1C28192746BA -:10184000354600F051FBF2E70A2F04D90120BDE82C -:10185000F84000F091BBF8BD782C0020F8B50646A2 -:101860000D4600F02BFB0F4A134653F8107F9F42A2 -:1018700006D12A4601463046BDE8F840FFF7C2BF10 -:10188000D169BB68441A2C1928BF2C46A34202D93F -:101890002946FFF79BFF224631460348BDE8F84042 -:1018A000FFF77EBF782C0020882C0020C0E903239E -:1018B000002310B45DF8044B4361FFF7CFBF000075 -:1018C00010B5194C236998420DD08168D0E90032D7 -:1018D00013605A609A680A449A60002303604FF0CC -:1018E000FF33A36110BD0268234643F8102F5360F5 -:1018F0000022026022699A4203D1BDE8104000F044 -:10190000EDBA936881680B44936000F0D7FA2269BE -:10191000E1699268441AA242E4D91144BDE810403A -:10192000091AFFF753BF00BF782C00202DE9F047BC -:10193000DFF8BC8008F110072C4ED8F8105000F0EA -:10194000BDFAD8F81C40AA68031B9A423ED814443A -:101950004FF00009D5E90032C8F81C4013605A6006 -:10196000C5F80090D8F81030B34201D100F0B6FAB3 -:1019700089F31188D5E9033128469847302383F34A -:1019800011886B69002BD8D000F098FA6A69A0EB37 -:10199000040982464A450DD2022000F0EDFA0022E9 -:1019A000D8F81030B34208D151462846BDE8F04778 -:1019B000FFF728BF121A2244F2E712EB0909294661 -:1019C000384638BF4A46FFF7EBFEB5E7D8F8103087 -:1019D000B34208D01444C8F81C00211AA960BDE81D -:1019E000F047FFF7F3BEBDE8F08700BF882C00206A -:1019F000782C002000207047FEE7000070470000B0 -:101A00004FF0FF3070470000BFF34F8F044B1A694F -:101A10005107FCD1D3F810215207F8D1704700BF0D -:101A20000020005208B50D4B1B78ABB9FFF7ECFF57 -:101A30000B4BDA68D10704D50A4A5A6002F18832A2 -:101A40005A60D3F80C21D20706D5064AC3F8042100 -:101A500002F18832C3F8042108BD00BFE82E00203F -:101A6000002000522301674508B5114B1B78F3B9DC -:101A7000104B1A69510703D5DA6842F04002DA6068 -:101A8000D3F81021520705D5D3F80C2142F04002BB -:101A9000C3F80C21FFF7B8FF064BDA6842F00102E9 -:101AA000DA60D3F80C2142F00102C3F80C2108BD22 -:101AB000E82E0020002000520F289ABF00F5806019 -:101AC00040040020704700004FF4003070470000D1 -:101AD000102070470F2808B50BD8FFF7EDFF00F571 -:101AE00000330268013204D104308342F9D101206D -:101AF00008BD0020FCE700000F2870B5054645D85A -:101B0000FFF7CEFD224CFFF77FFF0646FFF78AFF67 -:101B10004FF0FF33072D6361C4F8143120D82361DF -:101B2000FFF772FF2B0243F02403E360E36843F006 -:101B30008003E36023695A07FCD42846FFF764FF5B -:101B40004FF40031FFF7B8FF00F002F93046FFF71D -:101B50008BFFFFF7AFFD2846BDE87040FFF7BABF27 -:101B6000C4F81031FFF750FFA5F108031B0243F042 -:101B70002403C4F80C31D4F80C3143F08003C4F8CA -:101B80000C31D4F810315B07FBD4D6E7002070BDD0 -:101B9000002000522DE9F84F40EA020305460C46AA -:101BA0001746D80602D00020BDE8F88F27F01F079F -:101BB000DFF8D4B0FFF736FF2744BC4203D1012041 -:101BC000FFF752FFF0E720222946204600F0CEFD25 -:101BD00010B920352034F0E72B4605F120021E68AD -:101BE000711CE0D104339A42F9D1FFF759FD05F198 -:101BF0007843234AB3F5801F224B28BF9A4603F14E -:101C0000040338BF9046A2F1080228BF9846A3F10A -:101C100008033ABF9146DA469946FFF7F5FEC8F841 -:101C20000060A5EB040CD9F8002004F11C0142F07F -:101C30000202C9F80020221FDAF8006016F005063B -:101C4000FAD152F8043F8A424CF80230F4D1BFF383 -:101C50004F8FFFF7D9FE4FF0FF32C8F80020D9F8B8 -:101C6000002022F00202C9F80020FFF723FD202205 -:101C70002146284600F07AFD0028AAD030469FE78A -:101C800014200052102100521020005210B5084CB0 -:101C9000237828B11BB9FFF7C5FE0123237010BDBF -:101CA000002BFCD02070BDE81040FFF7DDBE00BF68 -:101CB000E82E00200244074BD2B210B5904200D16A -:101CC00010BD441C00B253F8200041F8040BE0B2F0 -:101CD000F4E700BF504000580E4B30B51C6F240491 -:101CE00005D41C6F1C671C6F44F400441C670A4C2D -:101CF00002442368D2B243F480732360074B9042BE -:101D000000D130BD441C51F8045B00B243F82050B0 -:101D1000E0B2F4E70044025800480258504000582E -:101D200007B5012201A90020FFF7C4FF019803B005 -:101D30005DF804FB13B50446FFF7F2FFA04205D09F -:101D4000012201A900200194FFF7C6FF02B010BDD7 -:101D50000144BFF34F8F064B884204D3BFF34F8F2C -:101D6000BFF36F8F7047C3F85C022030F4E700BF09 -:101D700000ED00E0034B1A681AB9034AD2F8D024E8 -:101D80001A607047EC2E00200040025808B5FFF79B -:101D9000F1FF024B1868C0F3806008BDEC2E0020F4 -:101DA00070B5BFF34F8FBFF36F8F1A4A0021C2F88F -:101DB0005012BFF34F8FBFF36F8F536943F400335B -:101DC0005361BFF34F8FBFF36F8FC2F88410BFF31F -:101DD0004F8FD2F8803043F6E074C3F3C900C3F3E9 -:101DE0004E335B0103EA0406014646EA8175013978 -:101DF000C2F86052F9D2203B13F1200FF2D1BFF3A9 -:101E00004F8F536943F480335361BFF34F8FBFF358 -:101E10006F8F70BD00ED00E0FEE70000214B22480F -:101E2000224A70B5904237D3214BC11EDA1C121AD8 -:101E300022F003028B4238BF00220021FEF7E6FFAA -:101E40001C4A0023C2F88430BFF34F8FD2F8803091 -:101E500043F6E074C3F3C900C3F34E335B0103EAF6 -:101E60000406014646EA81750139C2F86C52F9D27E -:101E7000203B13F1200FF2D1BFF34F8FBFF36F8FD1 -:101E8000BFF34F8FBFF36F8F0023C2F85032BFF301 -:101E90004F8FBFF36F8F70BD53F8041B40F8041BC6 -:101EA000C0E700BF88290008702F0020702F002095 -:101EB000702F002000ED00E000F07CB9014B586A63 -:101EC000704700BF000C0040034B002258631A61AA -:101ED0000222DA60704700BF000C0040014B002274 -:101EE000DA607047000C0040014B5863704700BF38 -:101EF000000C0040FEE7000070B51B4B00250446B7 -:101F000086B058600E468562016300F001F904F165 -:101F10001003A560E562C4E904334FF0FF33C4E960 -:101F20000044C4E90635FFF7C9FF2B46024604F119 -:101F300034012046C4E9082380230C4A2565FFF7B5 -:101F4000C9FB01230A4AE060009203756846726883 -:101F50000192B268CDE90223064BCDE90435FFF7C3 -:101F6000E1FB06B070BD00BFE02E0020182800087D -:101F70001D280008F51E0008024AD36A1843D062E3 -:101F8000704700BF782C00204B6843608B688360EB -:101F9000CB68C3600B6943614B6903628B69436221 -:101FA0000B6803607047000008B53A4B40F2FF71C0 -:101FB0003948D3F888200A43C3F88820D3F888200A -:101FC00022F4FF6222F00702C3F88820D3F8883099 -:101FD000324B1A6C0A431A649A6E0A439A66304A64 -:101FE0009B6E1146FFF7D0FF00F5806002F11C01E7 -:101FF000FFF7CAFF00F5806002F13801FFF7C4FF68 -:1020000000F5806002F15401FFF7BEFF00F580602B -:1020100002F17001FFF7B8FF00F5806002F18C015A -:10202000FFF7B2FF00F5806002F1A801FFF7ACFFF7 -:1020300000F5806002F1C401FFF7A6FF00F58060A3 -:1020400002F1E001FFF7A0FF00F5806002F1FC0162 -:10205000FFF79AFF02F58C7100F58060FFF794FF9F -:1020600000F066F90F4BD3F8902242F00102C3F85A -:102070009022D3F8942242F00102C3F89422052260 -:10208000C3F898204FF06052C3F89C20064AC3F86A -:10209000A02008BD00440258000002580045025824 -:1020A0002428000800ED00E01F00080308B500F038 -:1020B00041FBFFF7DDFA0B4BDA6B42F04002DA63CB -:1020C0005A6E22F040025A665B6E074B1A6842F065 -:1020D00008021A601A6842F004021A60BDE808405B -:1020E000FFF748BE0045025800180248704700003C -:1020F000EFF30983054968334A6B22F001024A6312 -:1021000083F30988002383F31188704700EF00E010 -:10211000302080F3118862B60D4B0E4AD96821F445 -:10212000E0610904090C0A430B49DA60D3F8FC208A -:1021300042F08072C3F8FC20084AC2F8B01F116850 -:1021400041F0010111602022DA7783F82200704704 -:1021500000ED00E00003FA0555CEACC5001000E02C -:10216000302310B583F311880E4B5B6813F40063C2 -:1021700014D0F1EE103AEFF309844FF08073683C0D -:10218000E361094BDB6B236684F30988FFF744FAAC -:1021900010B1064BA36110BD054BFBE783F311881B -:1021A000F9E700BF00ED00E000EF00E02F040008B9 -:1021B000320400080E4B9A6C42F008029A641A6FBF -:1021C00042F008021A670B4A1B6FD36B43F00803F7 -:1021D000D363C722084B9A624FF0FF32DA620022C3 -:1021E0009A615A63DA605A6001225A611A60704734 -:1021F000004502580010005C000C0040094A08B578 -:102200001169D3680B40D9B29B076FEA01011161D4 -:1022100007D5302383F31188FFF740FA002383F3B7 -:10222000118808BD000C0040044BDA6B0243DA63EE -:102230005A6E104358665B6E704700BF00450258E7 -:102240003A4B4FF0FF31D3F8802062F00042C3F8E0 -:102250008020D3F8802002F00042C3F88020D3F819 -:102260008020D3F88420C3F88410D3F8842000227F -:10227000C3F88420D3F88400D86F40F0FF4040F4C6 -:10228000FF0040F4DF4040F07F00D867D86F20F0B7 -:10229000FF4020F4FF0020F4DF4020F07F00D867EB -:1022A000D86FD3F888006FEA40506FEA5050C3F8F7 -:1022B0008800D3F88800C0F30A00C3F88800D3F878 -:1022C0008800D3F89000C3F89010D3F89000C3F8BA -:1022D0009020D3F89000D3F89400C3F89410D3F86A -:1022E0009400C3F89420D3F89400D3F89800C3F86E -:1022F0009810D3F89800C3F89820D3F89800D3F832 -:102300008C00C3F88C10D3F88C00C3F88C20D3F861 -:102310008C00D3F89C00C3F89C10D3F89C10C3F831 -:102320009C20D3F89C3000F0BFB900BF0044025895 -:1023300008B50122504BC3F80821504B5A6D42F0AA -:1023400002025A65DA6F42F00202DA670422DB6F9A -:102350004B4BDA605A689104FCD54A4A1A60012254 -:102360009A60494ADA6000221A614FF440429A6149 -:10237000434B9A699204FCD51A6842F480721A6041 -:10238000424B1A6F12F4407F04D04FF480321A6728 -:1023900000221A671A6842F001021A603B4B1A6861 -:1023A0005007FCD500221A611A6912F03802FBD1DD -:1023B000012119604FF0804159605A67344ADA624E -:1023C000344A1A611A6842F480321A602F4B1A6834 -:1023D0009103FCD51A6842F480521A601A6892047C -:1023E000FCD52D4A2D499A6200225A63196301F5E2 -:1023F0007C01DA6301F5E77199635A64284A1A642B -:10240000284ADA621A6842F0A8521A601F4B1A680A -:1024100002F02852B2F1285FF9D148229A614FF4B4 -:102420008862DA6140221A621F4ADA641F4A1A651A -:102430001F4A5A651F4A9A6532231F4A1360136860 -:1024400003F00F03022BFAD1104A136943F0030380 -:102450001361136903F03803182BFAD14FF00050C1 -:10246000FFF7E2FE4FF08040FFF7DEFE4FF0004046 -:10247000BDE80840FFF7D8BE008000510045025873 -:102480000048025800C000F0040000010044025857 -:102490000000FF01008890083220600063020901FB -:1024A000470E0508DD0BBF012000002000000110D1 -:1024B0000910E00000010110002000524FF0B0426E -:1024C00008B5D2F8883003F00103C2F8883023B190 -:1024D000044A13680BB150689847BDE80840FFF7FD -:1024E0003FBE00BFF02E00204FF0B04208B5D2F83A -:1024F000883003F00203C2F8883023B1044A93689D -:102500000BB1D0689847BDE80840FFF729BE00BF6F -:10251000F02E00204FF0B04208B5D2F8883003F01A -:102520000403C2F8883023B1044A13690BB150691F -:102530009847BDE80840FFF713BE00BFF02E00200B -:102540004FF0B04208B5D2F8883003F00803C2F863 -:10255000883023B1044A93690BB1D0699847BDE82C -:102560000840FFF7FDBD00BFF02E00204FF0B04245 -:1025700008B5D2F8883003F01003C2F8883023B1D0 -:10258000044A136A0BB1506A9847BDE80840FFF748 -:10259000E7BD00BFF02E00204FF0B04310B5D3F8D8 -:1025A000884004F47872C3F88820A30604D5124A40 -:1025B000936A0BB1D06A9847600604D50E4A136B34 -:1025C0000BB1506B9847210604D50B4A936B0BB1A6 -:1025D000D06B9847E20504D5074A136C0BB1506CD9 -:1025E0009847A30504D5044A936C0BB1D06C984767 -:1025F000BDE81040FFF7B4BDF02E00204FF0B0430F -:1026000010B5D3F8884004F47C42C3F888206205F2 -:1026100004D5164A136D0BB1506D9847230504D5A8 -:10262000124A936D0BB1D06D9847E00404D50F4A60 -:10263000136E0BB1506E9847A10404D50B4A936EEC -:102640000BB1D06E9847620404D5084A136F0BB1E2 -:10265000506F9847230404D5044A936F0BB1D06F91 -:102660009847BDE81040FFF77BBD00BFF02E00206B -:1026700008B50348FEF71CFDBDE80840FFF770BD34 -:10268000A023002008B50348FEF712FDBDE808406E -:10269000FFF766BD0C24002008B5FFF7AFFDBDE8CD -:1026A0000840FFF75DBD0000062108B5084600F0B0 -:1026B0002BF80621072000F027F80621082000F05B -:1026C00023F80621092000F01FF806210A2000F057 -:1026D0001BF80621172000F017F80621282000F02B -:1026E00013F809217A2000F00FF80721322000F0BA -:1026F0000BF80C21522000F007F80C215320BDE804 -:10270000084000F001B80000090100F16043012217 -:1027100003F56143C9B283F8001300F01F039A4028 -:1027200043099B0003F1604303F56143C3F8802133 -:102730001A60704708B5FFF783FD00F009F8FEF74F -:10274000CFFEFFF7D3FCBDE80840FFF7B5BB0000A4 -:102750000023054A19460133102BC2E9001102F18A -:102760000802F8D1704700BFF02E002010B50139E3 -:102770000244904201D1002005E0037811F8014F96 -:10278000A34201D0181B10BD0130F2E753544D3362 -:102790003248373F3F3F0053544D33324837337848 -:1027A0002F3732780053544D3332483734332F3774 -:1027B00035332F373530000001105A00031059000F -:1027C0000120580003205600009600000000000081 -:1027D00000000000000000000000000000000000F9 -:1027E00000000000A11400088D140008C91400089E -:1027F000B5140008C1140008AD14000899140008AD -:1028000085140008D514000863300000082800086B -:10281000D02C0020E02E00206D61696E0069646C90 -:10282000650000000000002800000000AAAAAAAA73 -:1028300000000024FFFF0000000000000000000076 -:102840000000000000000000AAAAAAAA00000000E0 -:10285000FFFF00000000000000000000000000007A -:1028600000000000AAAAAAAA00000000FFFF0000C2 -:102870000000000000000000000010000000000048 -:10288000AAAAAAAA00000000FFFF000000000000A2 -:10289000000000000A80020000000000AAAAAAAA04 -:1028A00005400100FFFF00008800007007000000E5 -:1028B0000000000000000000AAAAAAAA0000000070 -:1028C000FFFF00000000000000000000000000000A -:1028D00000000000AAAAAAAA00000000FFFF000052 -:1028E00000000000000000000000000000000000E8 -:1028F000AAAAAAAA00000000FFFF00000000000032 -:10290000000000000000000000000000AAAAAAAA1F -:1029100000000000FFFF00000000000000000000B9 -:102920000000000000000000AAAAAAAA00000000FF -:10293000FFFF000000000000000000000000000099 -:1029400000000000AAAAAAAA00000000FFFF0000E1 -:1029500000000000000000002E0400000000000045 -:1029600000001A0000000000FF000000A02300206B -:10297000000000008C27000883040000972700084F -:0829800050040000A527000827 +:100B900000220020A0860100104B70B51B780C4687 +:100BA0000133DBB2012B12D80D4B1D684FF47A7361 +:100BB0002968A2FB033222460E6A01462846B04746 +:100BC000844204D1074B002201201A7070BD4FF4FB +:100BD000FA7001F037F80020F8E700BF102200207B +:100BE000142200209C230020002307B50246012187 +:100BF0000DF107008DF80730FFF7CEFF20B19DF80B +:100C0000070003B05DF804FB4FF0FF30F9E7000088 +:100C10000A46042108B5FFF7BFFF80F00100C0B20B +:100C2000404208BD074B0A4630B41978064B53F8CA +:100C30002140014623682046DD69044BAC4630BCA8 +:100C4000604700BF9C23002014220020A0860100E2 +:100C500070B5104C0025104E01F0B4F920803068BA +:100C6000238883420CD800252088013801F0A6F99A +:100C700023880544013BB5F5802F2380F4D370BD54 +:100C800001F09CF9336805440133B5F5003F33604A +:100C9000E5D3E8E79E2300205823002001F060BA46 +:100CA00000F1006000F500300068704700F100605E +:100CB000920000F5003001F0E1B90000054B1A6820 +:100CC000054B1B889B1A834202D9104401F076B968 +:100CD00000207047582300209E23002038B504468A +:100CE000074D29B128682044BDE8384001F07EB99D +:100CF0002868204401F068F90028F3D038BD00BF0F +:100D0000582300200020704700F1FF5000F58F109D +:100D1000D0F8000870470000064991F8243033B13C +:100D200000230822086A81F82430FFF7BFBF0120A2 +:100D3000704700BF5C230020014B1868704700BF5C +:100D40000010005C194B01380322084470B51D687F +:100D5000174BC5F30B042D0C1E88A6420BD15C6803 +:100D60000A46013C824213460FD214F9016F4EB17C +:100D700002F8016BF6E7013A03F10803ECD1814276 +:100D80000B4602D22C2203F8012B0424094A1688B0 +:100D9000AE4204D1984284BF967803F8016B013CBF +:100DA00002F10402F3D1581A70BD00BF0010005CBC +:100DB00018220020A02C0008022803D1024B4FF07B +:100DC00080629A61704700BF000C0258022803D16C +:100DD000024B4FF480629A61704700BF000C0258CA +:100DE000022804D1024A536983F480635361704737 +:100DF000000C0258002310B5934203D0CC5CC454BD +:100E00000133F9E710BD000002440346934202D0CB +:100E100003F8011BFAE770472DE9F8431F4D14460C +:100E20000746884695F8242052BBDFF870909CB3A3 +:100E300095F824302BB92022FF2148462F62FFF776 +:100E4000E3FF95F824004146C0F1080205EB80005D +:100E5000A24228BF2246D6B29200FFF7CBFF95F8F8 +:100E60002430A41B17441E449044E4B2F6B2082E6A +:100E700085F82460DBD1FFF74FFF0028D7D108E0C9 +:100E80002B6A03EB82038342CFD0FFF745FF002894 +:100E9000CBD10020BDE8F8830120FBE75C230020D4 +:100EA000024B1A78024B1A70704700BF9C23002037 +:100EB00010220020034B04490B60044B186800F01B +:100EC000BDBD00BF80841E008423002014220020AA +:100ED000094B1822002110B504461846FFF794FF6D +:100EE000064A074B01461278046053F82200BDE819 +:100EF000104000F0A3BD00BF842300209C230020ED +:100F000014220020F0B5A1B071B600230120002406 +:100F100080261A46194600F041FA4FF4D067214A5C +:100F20003D25136923BBD2F810310BBB036804F1D4 +:100F3000006199600368C3F80CD003685E600368C1 +:100F40001F6001680B6843F001030B6001680B68C8 +:100F500023F01E030B6001680B68DB07FCD4037BE6 +:100F60008034416805FA03F3B4F5001F0B60D8D153 +:100F700000F04AFAB4F5001F11D000240A4E0B4DC0 +:100F8000012001F0EDF83388A34205D928682044F8 +:100F9000013401F02BF8F6E7002001F0E1F861B62A +:100FA00021B0F0BD002000529E23002058230020D5 +:100FB00030B50A44084D91420DD011F8013B58401C +:100FC000082340F30004013B2C4013F0FF0384EAA4 +:100FD0005000F6D1EFE730BD2083B8ED08B5074BE0 +:100FE000074A196801F03D01996053680BB1906898 +:100FF0009847BDE8084001F075B900BF0000024005 +:10100000A023002008B5084B1968890901F03D01AB +:101010008A019A60054AD3680BB110699847BDE808 +:10102000084001F05FB900BF00000240A02300208B +:1010300008B5084B1968090C01F03D010A049A60D3 +:10104000054A53690BB190699847BDE8084001F023 +:1010500049B900BF00000240A023002008B5084B9A +:101060001968890D01F03D018A059A60054AD36926 +:101070000BB1106A9847BDE8084001F033B900BFD2 +:1010800000000240A023002008B5074B074A59681A +:1010900001F03D01D960536A0BB1906A9847BDE8F1 +:1010A000084001F01FB900BF00000240A02300204B +:1010B00008B5084B5968890901F03D018A01DA60D9 +:1010C000054AD36A0BB1106B9847BDE8084001F0A0 +:1010D00009B900BF00000240A023002008B5084B5A +:1010E0005968090C01F03D010A04DA60054A536BA6 +:1010F0000BB1906B9847BDE8084001F0F3B800BF12 +:1011000000000240A023002008B5084B5968890D53 +:1011100001F03D018A05DA60054AD36B0BB1106C12 +:101120009847BDE8084001F0DDB800BF000002406C +:10113000A023002008B5074B074A196801F03D01BC +:101140009960536C0BB1906C9847BDE8084001F072 +:10115000C9B800BF00040240A023002008B5084B16 +:101160001968890901F03D018A019A60054AD36C2A +:101170000BB1106D9847BDE8084001F0B3B800BF4F +:1011800000040240A023002008B5084B1968090C90 +:1011900001F03D010A049A60054A536D0BB1906D50 +:1011A0009847BDE8084001F09DB800BF0004024028 +:1011B000A023002008B5084B1968890D01F03D01F6 +:1011C0008A059A60054AD36D0BB1106E9847BDE849 +:1011D000084001F087B800BF00040240A0230020AF +:1011E00008B5074B074A596801F03D01D960536EB5 +:1011F0000BB1906E9847BDE8084001F073B800BF8E +:1012000000040240A023002008B5084B5968890952 +:1012100001F03D018A01DA60054AD36E0BB1106F0F +:101220009847BDE8084001F05DB800BF00040240E7 +:10123000A023002008B5084B5968090C01F03D01B6 +:101240000A04DA60054A536F0BB1906F9847BDE806 +:10125000084001F047B800BF00040240A02300206E +:1012600008B5084B5968890D01F03D018A05DA601F +:10127000054AD36F13B1D2F880009847BDE8084003 +:1012800001F030B800040240A023002000230C49E4 +:1012900010B51A460B4C0B6054F82300026001EBAA +:1012A000430004334260402BF6D1074A4FF0FF332E +:1012B0009360D360C2F80834C2F80C3410BD00BF8C +:1012C000A0230020B02C0008000002400F28F8B531 +:1012D00010D9102810D0112811D0122808D10F24AD +:1012E0000720DFF8B4E00126DEF80050A04208D95C +:1012F000002649E00446F4E70F240020F1E7072424 +:10130000FBE706FA00F73D4240D1214C4FEA001CB2 +:101310003D4304EB00160EEBC000CEF80050C0E9D0 +:101320000123FBB24BB11B48836B43F00103836382 +:10133000036E43F001030366036E17F47F4F09D079 +:101340001448836B43F002038363036E43F002038C +:101350000366036E54F80C00036823F01F03036058 +:10136000056815F00105FBD104EB0C033D2493F84F +:101370000CC05F6804FA0CF43C60212405604461F1 +:1013800012B1987B00F08EF93046F8BD0130ADE720 +:10139000B02C000800450258A023002010B53024CE +:1013A00084F31188FFF792FF002383F3118810BDA7 +:1013B00010B50446807B00F08BF901231049627B55 +:1013C00003FA02F20B6823EA0203DAB20B604AB9AD +:1013D0000C4A916B21F001019163116E21F0010122 +:1013E0001166126E13F47F4F09D1064B9A6B22F0EF +:1013F00002029A631A6E22F002021A661B6E10BD78 +:10140000A02300200045025808B5302383F311883B +:10141000FFF7CEFF002383F3118808BD02684368FD +:101420001143016003B1184770470000024A136876 +:1014300043F0C0031360704700780040024A13680D +:1014400043F0C00313607047007C004037B51A4C6E +:101450001A4D204600F0E6FA04F11400009400232F +:101460004FF40072164900F0A3F94FF400721549C9 +:1014700004F138000094144B00F01CFA134BC4E93B +:101480001735134C204600F0CDFA04F11400002368 +:101490004FF400720F49009400F08AF90E4B4FF49C +:1014A00000720E4904F13800009400F003FA0C4B6E +:1014B000C4E9173503B030BD2424002000E1F50550 +:1014C000FC240020FC2800202D1400080078004097 +:1014D00090240020FC2600203D140008FC2A002057 +:1014E000007C0040037C30B5274C002918BF0C4617 +:1014F000012B0CD1254B984236D1254B9A6C42F0EA +:1015000080429A641A6F42F080421A671B6F226809 +:10151000036EC16D03EB52038466B3FBF2F36268A2 +:10152000150442BF23F0070503F0070343EA450310 +:10153000CB60A36843F040034B60E36843F00103D2 +:101540008B6042F4967343F001030B604FF0FF335E +:101550000B62510505D512F0102211D0B2F1805F57 +:1015600010D080F8643030BD0A4B9842CFD1084B80 +:101570009A6C42F000429A641A6F42F00042C4E74B +:101580007F23EEE73F23ECE7B02D00082424002062 +:1015900000450258902400202DE9F047C66D05460D +:1015A0003768F469210734621AD014F0080118BFB3 +:1015B0004FF48071E20748BF41F02001A3074FF0CC +:1015C000300348BF41F04001600748BF41F080014F +:1015D00083F31188281DFFF721FF002383F311886F +:1015E000E2050AD5302383F311884FF48061281D6A +:1015F000FFF714FF002383F311884FF030094FF0F9 +:10160000000A14F0200838D13B0616D54FF03009F7 +:1016100005F1380A200610D589F31188504600F0EC +:101620007DF9002836DA0821281DFFF7F7FE27F09C +:1016300080033360002383F31188790614D5620692 +:1016400012D5302383F31188D5E913239A4208D1A8 +:101650002B6C33B127F040071021281DFFF7DEFE69 +:101660003760002383F31188E30618D5AA6E136947 +:10167000ABB15069BDE8F047184789F31188736A28 +:10168000284695F86410194000F0E6F98AF31188AD +:10169000F469B6E7B06288F31188F469BAE7BDE887 +:1016A000F0870000090100F16043012203F5614366 +:1016B000C9B283F8001300F01F039A4043099B004E +:1016C00003F1604303F56143C3F880211A6070475A +:1016D00000F01F0301229A40430900F160409B0083 +:1016E00000F5614003F1604303F56143C3F88020D6 +:1016F000C3F88021002380F800337047F8B5154601 +:10170000826804460B46AA4200D28568A169266910 +:10171000761AB5420BD218462A46FFF76BFBA3692F +:101720002B44A3612846A3685B1BA360F8BD0CD9BA +:10173000AF1B18463246FFF75DFB3A46E16830447E +:10174000FFF758FBE3683B44EBE718462A46FFF7F0 +:1017500051FBE368E5E7000083689342F7B5044670 +:10176000154600D28568D4E90460361AB5420BD21A +:101770002A46FFF73FFB63692B4463612846A36851 +:101780005B1BA36003B0F0BD0DD93246AF1B0191C6 +:10179000FFF730FB01993A46E0683144FFF72AFB36 +:1017A000E3683B44E9E72A46FFF724FBE368E4E704 +:1017B00010B50A440024C361029B8460C1600261C9 +:1017C0000362C0E90000C0E9051110BD08B5D0E909 +:1017D0000532934201D1826882B982680132826007 +:1017E0005A1C426119700021D0E904329A4224BF88 +:1017F000C368436100F042FA002008BD4FF0FF309B +:10180000FBE7000070B5302304460E4683F31188D1 +:10181000A568A5B1A368A269013BA360531CA3619D +:1018200015782269934224BFE368A361E3690BB191 +:1018300020469847002383F31188284607E0314665 +:10184000204600F00BFA0028E2DA85F3118870BD1B +:101850002DE9F74F04460E4617469846D0F81C90DF +:101860004FF0300A8AF311884FF0000B154665B12E +:101870002A4631462046FFF741FF034660B94146FC +:10188000204600F0EBF90028F1D0002383F3118803 +:10189000781B03B0BDE8F08FB9F1000F03D00190C1 +:1018A0002046C847019B8BF31188ED1A1E448AF32A +:1018B0001188DCE7C160C361009B82600362C0E9FC +:1018C00005111144C0E9000001617047F8B50446F4 +:1018D0000D461646302383F31188A768A7B1A36885 +:1018E000013BA36063695A1C62611D70D4E9043234 +:1018F0009A4224BFE3686361E3690BB120469847CD +:10190000002080F3118807E03146204600F0A6F958 +:101910000028E2DA87F31188F8BD0000D0E905233A +:1019200010B59A4201D182687AB9826800210132E9 +:1019300082605A1C82611C7803699A4224BFC36882 +:10194000836100F09BF9204610BD4FF0FF30FBE7AC +:101950002DE9F74F04460E4617469846D0F81C90DE +:101960004FF0300A8AF311884FF0000B154665B12D +:101970002A4631462046FFF7EFFE034660B941464E +:10198000204600F06BF90028F1D0002383F3118882 +:10199000781B03B0BDE8F08FB9F1000F03D00190C0 +:1019A0002046C847019B8BF31188ED1A1E448AF329 +:1019B0001188DCE7026843681143016003B11847EE +:1019C000704700001430FFF743BF00004FF0FF33B3 +:1019D0001430FFF73DBF00003830FFF7B9BF0000FB +:1019E0004FF0FF333830FFF7B3BF00001430FFF77C +:1019F00009BF00004FF0FF311430FFF703BF0000B4 +:101A00003830FFF763BF00004FF0FF323830FFF788 +:101A10005DBF0000012914BF6FF013000020704764 +:101A2000FFF714BD044B036000234360C0E9023399 +:101A300001230374704700BFC82D000810B5302380 +:101A4000044683F31188FFF74DFD02230020237421 +:101A500080F3118810BD000038B5C36904460D46F7 +:101A60001BB904210844FFF7A5FF294604F114001F +:101A7000FFF7ACFE002806DA201D4FF40061BDE838 +:101A80003840FFF797BF38BD0023826803750369AC +:101A90001B6899689142FBD25A68036042601060EB +:101AA0005860704700238268037503691B68996852 +:101AB0009142FBD85A6803604260106058607047DA +:101AC00008B50846302383F311880B7D032B05D01E +:101AD000042B0DD02BB983F3118808BD8B6900222C +:101AE0001A604FF0FF338361FFF7CEFF0023F2E768 +:101AF000D1E9003213605A60F3E70000FFF7C4BF7A +:101B0000054BD96808751868026853601A6001228D +:101B1000D8600275FEF776BC002D00200C4B30B566 +:101B2000DD684B1C87B004460FD02B46094A684637 +:101B300000F036F92046FFF7E3FF009B13B168463B +:101B400000F038F9A86907B030BDFFF7D9FFF9E711 +:101B5000002D0020C11A0008044B1A68DB68906849 +:101B60009B68984294BF002001207047002D002000 +:101B7000084B10B51C68D868226853601A600122AF +:101B8000DC602275FFF78EFF01462046BDE810405D +:101B9000FEF738BC002D002038B5074C0123002586 +:101BA000064907482370656000F072FC0223237029 +:101BB00085F3118838BD00BF682F0020F42D000880 +:101BC000002D002000F02CB98B600223086108462C +:101BD0008B8270478368A3F1840243F8142C026956 +:101BE00043F8442C426943F8402C094A43F8242C1A +:101BF000C268A3F1200043F8182C022203F80C2C31 +:101C0000002203F80B2C034A43F8102C704700BF46 +:101C10001D040008002D002008B5FFF7DBFFBDE81C +:101C20000840FFF76BBF0000024BDB6898610F2094 +:101C3000FFF766BF002D0020302383F31188FFF7E4 +:101C4000F3BF000008B50146302383F31188082054 +:101C5000FFF764FF002383F3118808BD064BDB68A0 +:101C600039B1426818605A60136043600420FFF77E +:101C700055BF4FF0FF307047002D00200368984299 +:101C800006D01A680260506018469961FFF736BFA7 +:101C900070470000036810B59C68A2420CD85C68CD +:101CA0008A600B604C602160596099688A1A9A605A +:101CB0004FF0FF33836010BD121B1B68ECE7000080 +:101CC0000A2938BF0A2170B504460D460A26601954 +:101CD00000F0D6FB00F0BEFB041BA54203D8751C28 +:101CE00004462E46F3E70A2E04D90120BDE87040D1 +:101CF00000F00EBC70BD0000F8B5144B0D460A2A6A +:101D00004FF00A07D96103F11001826038BF0A223F +:101D1000416019691446016048601861A81800F014 +:101D20009FFB00F097FB431B0646A34206D37C1C97 +:101D300028192746354600F0A3FBF2E70A2F04D9FD +:101D40000120BDE8F84000F0E3BBF8BD002D002005 +:101D5000F8B506460D4600F07DFB0F4A134653F8D2 +:101D6000107F9F4206D12A4601463046BDE8F84022 +:101D7000FFF7C2BFD169BB68441A2C1928BF2C4693 +:101D8000A34202D92946FFF79BFF2246314603486A +:101D9000BDE8F840FFF77EBF002D0020102D002089 +:101DA000C0E90323002310B45DF8044B4361FFF73F +:101DB000CFBF000010B5194C236998420DD081683F +:101DC000D0E9003213605A609A680A449A6000238E +:101DD00003604FF0FF33A36110BD0268234643F850 +:101DE000102F53600022026022699A4203D1BDE89D +:101DF000104000F03FBB936881680B44936000F093 +:101E000029FB2269E1699268441AA242E4D911448B +:101E1000BDE81040091AFFF753BF00BF002D002096 +:101E20002DE9F047DFF8BC8008F110072C4ED8F8F8 +:101E3000105000F00FFBD8F81C40AA68031B9A4210 +:101E40003ED814444FF00009D5E90032C8F81C40D0 +:101E500013605A60C5F80090D8F81030B34201D131 +:101E600000F008FB89F31188D5E90331284698472B +:101E7000302383F311886B69002BD8D000F0EAFA85 +:101E80006A69A0EB040982464A450DD2022000F09F +:101E90003FFB0022D8F81030B34208D15146284603 +:101EA000BDE8F047FFF728BF121A2244F2E712EB11 +:101EB00009092946384638BF4A46FFF7EBFEB5E721 +:101EC000D8F81030B34208D01444C8F81C00211AC6 +:101ED000A960BDE8F047FFF7F3BEBDE8F08700BF9B +:101EE000102D0020002D002000207047FEE700008C +:101EF000704700004FF0FF3070470000BFF34F8F76 +:101F0000044B1A695107FCD1D3F810215207F8D1BC +:101F1000704700BF0020005208B50D4B1B78ABB9CD +:101F2000FFF7ECFF0B4BDA68D10704D50A4A5A6079 +:101F300002F188325A60D3F80C21D20706D5064A3E +:101F4000C3F8042102F18832C3F8042108BD00BFA0 +:101F5000702F0020002000522301674508B5114B67 +:101F60001B78F3B9104B1A69510703D5DA6842F0B0 +:101F70004002DA60D3F81021520705D5D3F80C21BE +:101F800042F04002C3F80C21FFF7B8FF064BDA68B5 +:101F900042F00102DA60D3F80C2142F00102C3F8EA +:101FA0000C2108BD702F0020002000520F289ABF7E +:101FB00000F5806040040020704700004FF40030BE +:101FC00070470000102070470F2808B50BD8FFF7A6 +:101FD000EDFF00F500330268013204D10430834282 +:101FE000F9D1012008BD0020FCE700000F2838B51A +:101FF00005463FD8FFF782FF1F4CFFF78DFF4FF0DC +:10200000FF3307286361C4F814311DD82361FFF73B +:1020100075FF030243F02403E360E36843F08003A9 +:10202000E36023695A07FCD42846FFF767FFFFF7F0 +:10203000BDFF4FF4003100F0F5F82846FFF78EFFA2 +:10204000BDE83840FFF7C0BFC4F81031FFF756FFB6 +:10205000A0F108031B0243F02403C4F80C31D4F8A8 +:102060000C3143F08003C4F80C31D4F810315B0715 +:10207000FBD4D9E7002038BD002000522DE9F84FED +:1020800005460C46104645EA0203DE0602D0002053 +:10209000BDE8F88F20F01F00DFF8BCB0DFF8BCA06F +:1020A000FFF73AFF04EB0008444503D10120FFF796 +:1020B00055FFEDE720222946204600F0CBFD10B960 +:1020C00020352034F0E72B4605F120021F68791CEB +:1020D000DDD104339A42F9D105F178431B481C4EF7 +:1020E000B3F5801F1B4B38BF184603F1F80332BF0E +:1020F000D946D1461E46FFF701FF0760A5EB040C49 +:10210000336804F11C0143F002033360231FD9F844 +:10211000007017F00507FAD153F8042F8B424CF8E2 +:102120000320F4D1BFF34F8FFFF7E8FE4FF0FF33EA +:102130002022214603602846336823F002033360DF +:1021400000F088FD0028BBD03846B0E714210052CB +:102150000C20005214200052102000521021005276 +:1021600010B5084C237828B11BB9FFF7D5FE012321 +:10217000237010BD002BFCD02070BDE81040FFF78D +:10218000EDBE00BF702F00200244074BD2B210B545 +:10219000904200D110BD441C00B253F8200041F819 +:1021A000040BE0B2F4E700BF504000580E4B30B5CE +:1021B0001C6F240405D41C6F1C671C6F44F400447E +:1021C0001C670A4C02442368D2B243F48073236034 +:1021D000074B904200D130BD441C51F8045B00B263 +:1021E00043F82050E0B2F4E7004402580048025897 +:1021F0005040005807B5012201A90020FFF7C4FF95 +:10220000019803B05DF804FB13B50446FFF7F2FF35 +:10221000A04205D0012201A900200194FFF7C6FFCA +:1022200002B010BD0144BFF34F8F064B884204D368 +:10223000BFF34F8FBFF36F8F7047C3F85C0220303E +:10224000F4E700BF00ED00E0034B1A681AB9034A37 +:10225000D2F8D0241A607047742F00200040025832 +:1022600008B5FFF7F1FF024B1868C0F3806008BDA6 +:10227000742F0020EFF30983054968334A6B22F07D +:1022800001024A6383F30988002383F311887047AE +:1022900000EF00E0302080F3118862B60D4B0E4A4B +:1022A000D96821F4E0610904090C0A430B49DA609A +:1022B000D3F8FC2042F08072C3F8FC20084AC2F830 +:1022C000B01F116841F0010111602022DA7783F814 +:1022D0002200704700ED00E00003FA0555CEACC5C2 +:1022E000001000E0302310B583F311880E4B5B68BB +:1022F00013F4006314D0F1EE103AEFF309844FF0B9 +:102300008073683CE361094BDB6B236684F30988C7 +:10231000FFF722FC10B1064BA36110BD054BFBE794 +:1023200083F31188F9E700BF00ED00E000EF00E063 +:102330002F0400083204000870B5BFF34F8FBFF3BD +:102340006F8F1A4A0021C2F85012BFF34F8FBFF3AC +:102350006F8F536943F400335361BFF34F8FBFF363 +:102360006F8FC2F88410BFF34F8FD2F8803043F6DE +:10237000E074C3F3C900C3F34E335B0103EA040600 +:10238000014646EA81750139C2F86052F9D2203B14 +:1023900013F1200FF2D1BFF34F8F536943F4803311 +:1023A0005361BFF34F8FBFF36F8F70BD00ED00E03F +:1023B000FEE70000214B2248224A70B5904237D3F5 +:1023C000214BC11EDA1C121A22F003028B4238BFC5 +:1023D00000220021FEF718FD1C4A0023C2F88430B9 +:1023E000BFF34F8FD2F8803043F6E074C3F3C900D7 +:1023F000C3F34E335B0103EA0406014646EA8175E6 +:102400000139C2F86C52F9D2203B13F1200FF2D1FE +:10241000BFF34F8FBFF36F8FBFF34F8FBFF36F8F3C +:102420000023C2F85032BFF34F8FBFF36F8F70BDE0 +:1024300053F8041B40F8041BC0E700BF702F0008CE +:10244000F82F0020F82F0020F82F002000ED00E0EA +:1024500000F036B9014B586A704700BF000C0040CD +:10246000034B002258631A610222DA60704700BFF2 +:10247000000C0040014B0022DA607047000C004065 +:10248000014B5863704700BF000C0040FEE700009E +:1024900070B51B4B0025044686B058600E46856219 +:1024A0000163FFF7F7FE04F11003A560E562C4E9DC +:1024B00004334FF0FF33C4E90044C4E90635FFF7A5 +:1024C000C9FF2B46024604F134012046C4E9082323 +:1024D00080230C4A2565FFF777FB01230A4AE06059 +:1024E00000920375684672680192B268CDE90223D2 +:1024F000064BCDE90435FFF78FFB06B070BD00BF7A +:10250000682F0020002E0008052E00088D240008EA +:10251000024AD36A1843D062704700BF002D0020E2 +:102520004B6843608B688360CB68C3600B69436111 +:102530004B6903628B6943620B680360704700005C +:1025400008B5464B40F2FF714548D3F888200A434E +:10255000C3F88820D3F8882022F4FF6222F0070213 +:10256000C3F88820D3F888303E4B1A6C0A431A64AB +:102570009A6E0A433C499A669B6EFFF7D1FF1C3165 +:1025800000F58060FFF7CCFF1C3100F58060FFF79D +:10259000C7FF1C3100F58060FFF7C2FF1C3100F55A +:1025A0008060FFF7BDFF1C3100F58060FFF7B8FFCA +:1025B0001C3100F58060FFF7B3FF1C3100F580602F +:1025C000FFF7AEFF1C3100F58060FFF7A9FF1C315B +:1025D00000F58060FFF7A4FF1C3100F58060FFF775 +:1025E0009FFF00F02FF9214BD3F8902242F0010217 +:1025F000C3F89022D3F8942242F00102C3F8942247 +:102600000522C3F898204FF06052C3F89C20184A66 +:10261000C3F8A020174BDA6952021ED59A69D00779 +:1026200004D5154A9A6002F144329A60114BDA6976 +:10263000D107FCD41A6A22F480021A629A6942F025 +:1026400002029A61DA69D207FCD49A6942F0010267 +:102650009A61084AD369DB07FCD408BD00440258DC +:1026600000000258004502580C2E000800ED00E062 +:102670001F000803002000523B2A190808B500F08B +:10268000CDFAFFF789FA0B4BDA6B42F04002DA63BE +:102690005A6E22F040025A665B6E074B1A6842F08F +:1026A00008021A601A6842F004021A60BDE8084085 +:1026B000FFF7CABD004502580018024870470000E5 +:1026C0000E4B9A6C42F008029A641A6F42F00802AC +:1026D0001A670B4A1B6FD36B43F00803D363C722FF +:1026E000084B9A624FF0FF32DA6200229A615A6315 +:1026F000DA605A6001225A611A6070470045025838 +:102700000010005C000C0040094A08B51169D3684C +:102710000B40D9B29B076FEA0101116107D5302345 +:1027200083F31188FFF74EFA002383F3118808BD65 +:10273000000C0040044BDA6B0243DA635A6E10431C +:1027400058665B6E704700BF0045025808B53C4BA9 +:102750004FF0FF31D3F8802062F00042C3F88020B0 +:10276000D3F8802002F00042C3F88020D3F8802004 +:10277000D3F88420C3F88410D3F884200022C3F84F +:102780008420D3F88400D86F40F0FF4040F4FF006D +:1027900040F4DF4040F07F00D867D86F20F0FF4062 +:1027A00020F4FF0020F4DF4020F07F00D867D86FCE +:1027B000D3F888006FEA40506FEA5050C3F88800A1 +:1027C000D3F88800C0F30A00C3F88800D3F8880063 +:1027D000D3F89000C3F89010D3F89000C3F890207D +:1027E000D3F89000D3F89400C3F89410D3F8940071 +:1027F000C3F89420D3F89400D3F89800C3F8981045 +:10280000D3F89800C3F89820D3F89800D3F88C0038 +:10281000C3F88C10D3F88C00C3F88C20D3F88C004C +:10282000D3F89C00C3F89C10D3F89C10C3F89C20EC +:10283000D3F89C30FEF72AFDBDE8084000F0BEB991 +:102840000044025808B50122504BC3F80821504BF0 +:102850005A6D42F002025A65DA6F42F00202DA67FC +:102860000422DB6F4B4BDA605A689104FCD54A4A6C +:102870001A6001229A60494ADA6000221A614FF414 +:1028800040429A61434B9A699204FCD51A6842F41B +:1028900080721A60424B1A6F12F4407F04D04FF4DA +:1028A00080321A6700221A671A6842F001021A6021 +:1028B0003B4B1A685007FCD500221A611A6912F0C6 +:1028C0003802FBD1012119604FF0804159605A67ED +:1028D000344ADA62344A1A611A6842F480321A6061 +:1028E0002F4B1A689103FCD51A6842F480521A6083 +:1028F0001A689204FCD52D4A2D499A6200225A6327 +:10290000196301F57C01DA6301F5E77199635A6493 +:10291000284A1A64284ADA621A6842F0A8521A60F1 +:102920001F4B1A6802F02852B2F1285FF9D14822F1 +:102930009A614FF48862DA6140221A621F4ADA64AF +:102940001F4A1A651F4A5A651F4A9A6532231F4A51 +:102950001360136803F00F03022BFAD1104A1369B6 +:1029600043F003031361136903F03803182BFAD102 +:102970004FF00050FFF7DEFE4FF08040FFF7DAFE29 +:102980004FF00040BDE80840FFF7D4BE0080005182 +:10299000004502580048025800C000F00400000141 +:1029A000004402580000FF010088900832206000B7 +:1029B00063020901470E0508DD0BBF01200000205E +:1029C000000001100910E000000101100020005279 +:1029D0004FF0B04208B5D2F8883003F00103C2F8D6 +:1029E000883023B1044A13680BB150689847BDE89A +:1029F0000840FFF777BC00BF782F00204FF0B042AF +:102A000008B5D2F8883003F00203C2F8883023B149 +:102A1000044A93680BB1D0689847BDE80840FFF7B7 +:102A200061BC00BF782F00204FF0B04208B5D2F84B +:102A3000883003F00403C2F8883023B1044A1369D4 +:102A40000BB150699847BDE80840FFF74BBC00BF89 +:102A5000782F00204FF0B04208B5D2F8883003F04C +:102A60000803C2F8883023B1044A93690BB1D069D6 +:102A70009847BDE80840FFF735BC00BF782F00201D +:102A80004FF0B04208B5D2F8883003F01003C2F816 +:102A9000883023B1044A136A0BB1506A9847BDE8E5 +:102AA0000840FFF71FBC00BF782F00204FF0B04355 +:102AB00010B5D3F8884004F47872C3F88820A306D0 +:102AC00004D5124A936A0BB1D06A9847600604D5C0 +:102AD0000E4A136B0BB1506B9847210604D50B4A75 +:102AE000936B0BB1D06B9847E20504D5074A136C82 +:102AF0000BB1506C9847A30504D5044A936C0BB1F5 +:102B0000D06C9847BDE81040FFF7ECBB782F002051 +:102B10004FF0B04310B5D3F8884004F47C42C3F8BA +:102B20008820620504D5164A136D0BB1506D984785 +:102B3000230504D5124A936D0BB1D06D9847E0047C +:102B400004D50F4A136E0BB1506E9847A10404D5FB +:102B50000B4A936E0BB1D06E9847620404D5084AB5 +:102B6000136F0BB1506F9847230404D5044A936F39 +:102B70000BB1D06F9847BDE81040FFF7B3BB00BF63 +:102B8000782F002008B50348FEF706FDBDE8084091 +:102B9000FFF7A8BB2424002008B50348FEF7FCFC7F +:102BA000BDE80840FFF79EBB9024002008B5FFF762 +:102BB000ABFDBDE80840FFF795BB0000062108B556 +:102BC0000846FEF76FFD06210720FEF76BFD062184 +:102BD0000820FEF767FD06210920FEF763FD0621A8 +:102BE0000A20FEF75FFD06211720FEF75BFD062198 +:102BF0002820FEF757FD09217A20FEF753FD072113 +:102C00003220FEF74FFD0C215220FEF74BFD0C2128 +:102C10005320BDE80840FEF745BD000008B5FFF7AA +:102C200095FD00F009F8FEF7FBFEFFF747FDBDE854 +:102C30000840FFF70DBC00000023054A1946013388 +:102C4000102BC2E9001102F10802F8D1704700BF51 +:102C5000782F002010B501390244904201D10020A4 +:102C600005E0037811F8014FA34201D0181B10BDF5 +:102C70000130F2E753544D333248373F3F3F005362 +:102C8000544D3332483733782F3732780053544D10 +:102C90003332483734332F3735332F373530000050 +:102CA00001105A000310590001205800032056005B +:102CB00010000240080002400008024000000B0023 +:102CC00028000240080002400408024006010C00EF +:102CD00040000240080002400808024010020D00B7 +:102CE00058000240080002400C08024016030E0083 +:102CF000700002400C0002401008024000040F0067 +:102D0000880002400C000240140802400605100032 +:102D1000A00002400C0002401808024010061100FA +:102D2000B80002400C0002401C08024016072F00A9 +:102D30001004024008040240200802400008380045 +:102D40002804024008040240240802400609390011 +:102D5000400402400804024028080240100A3A00D9 +:102D600058040240080402402C080240160B3B00A5 +:102D7000700402400C04024030080240000C3C0089 +:102D8000880402400C04024034080240060D44004E +:102D9000A00402400C04024038080240100E450016 +:102DA000B80402400C0402403C080240160F4600E2 +:102DB000009600000000000000000000000000007D +:102DC000000000000000000000000000E119000801 +:102DD000CD190008091A0008F5190008011A0008A1 +:102DE000ED190008D9190008C5190008151A0008BE +:102DF00063300000F02D0008582D0020682F0020BF +:102E00006D61696E0069646C650000000000002857 +:102E100000000000AAAAAAAA00000024FFFF0000E8 +:102E200000000000000000000000000000000000A2 +:102E3000AAAAAAAA00000000FFFF000000000000EC +:102E4000000000000000000000000000AAAAAAAADA +:102E500000000000FFFF0000000000000000000074 +:102E60000000100000000000AAAAAAAA00000000AA +:102E7000FFFF000000000000000000000A800200C8 +:102E800000000000AAAAAAAA05400100FFFF000056 +:102E90008800007007000000000000000000000033 +:102EA000AAAAAAAA00000000FFFF0000000000007C +:102EB000000000000000000000000000AAAAAAAA6A +:102EC00000000000FFFF0000000000000000000004 +:102ED0000000000000000000AAAAAAAA000000004A +:102EE000FFFF0000000000000000000000000000E4 +:102EF00000000000AAAAAAAA00000000FFFF00002C +:102F000000000000000000000000000000000000C1 +:102F1000AAAAAAAA00000000FFFF0000000000000B +:102F2000000000000000000000000000AAAAAAAAF9 +:102F300000000000FFFF0000000000000000000093 +:102F40002E0400000000000000001A000000000035 +:102F5000FF0000002424002000000000742C000862 +:102F6000830400007F2C0008500400008D2C000812 :00000001FF From 452df9022b4cc856dc2d2ab0d2eac73d72ab766f Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 3 Jul 2024 15:48:10 +1000 Subject: [PATCH 11/16] .github: add debug build test for macos --- .github/workflows/macos_build.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/macos_build.yml b/.github/workflows/macos_build.yml index 7dba405b0300e6..dd9dc964839839 100644 --- a/.github/workflows/macos_build.yml +++ b/.github/workflows/macos_build.yml @@ -188,5 +188,7 @@ jobs: echo $PATH ./waf configure --board ${{matrix.config}} ./waf + ./waf configure --board ${{matrix.config}} --debug + ./waf ccache -s ccache -z From 1916490ae694f82fa74af6c1d6e3ac7c7fa88354 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 7 Mar 2024 21:04:28 +1100 Subject: [PATCH 12/16] AC_Sprayer: create and use an AP_Sprayer_config.h --- libraries/AC_Sprayer/AC_Sprayer.cpp | 3 ++- libraries/AC_Sprayer/AC_Sprayer.h | 10 ++++------ libraries/AC_Sprayer/AC_Sprayer_config.h | 7 +++++++ 3 files changed, 13 insertions(+), 7 deletions(-) create mode 100644 libraries/AC_Sprayer/AC_Sprayer_config.h diff --git a/libraries/AC_Sprayer/AC_Sprayer.cpp b/libraries/AC_Sprayer/AC_Sprayer.cpp index c6b026eb5628df..5b903fac63102d 100644 --- a/libraries/AC_Sprayer/AC_Sprayer.cpp +++ b/libraries/AC_Sprayer/AC_Sprayer.cpp @@ -1,7 +1,8 @@ -#include "AC_Sprayer.h" +#include "AC_Sprayer_config.h" #if HAL_SPRAYER_ENABLED +#include "AC_Sprayer.h" #include #include #include diff --git a/libraries/AC_Sprayer/AC_Sprayer.h b/libraries/AC_Sprayer/AC_Sprayer.h index 240e354d22070f..e4f0ba425ac6a9 100644 --- a/libraries/AC_Sprayer/AC_Sprayer.h +++ b/libraries/AC_Sprayer/AC_Sprayer.h @@ -14,6 +14,10 @@ **/ #pragma once +#include "AC_Sprayer_config.h" + +#if HAL_SPRAYER_ENABLED + #include #include #include @@ -25,12 +29,6 @@ #define AC_SPRAYER_DEFAULT_TURN_ON_DELAY 100 ///< delay between when we reach the minimum speed and we begin spraying. This reduces the likelihood of constantly turning on/off the pump #define AC_SPRAYER_DEFAULT_SHUT_OFF_DELAY 1000 ///< shut-off delay in milli seconds. This reduces the likelihood of constantly turning on/off the pump -#ifndef HAL_SPRAYER_ENABLED -#define HAL_SPRAYER_ENABLED 1 -#endif - -#if HAL_SPRAYER_ENABLED - /// @class AC_Sprayer /// @brief Object managing a crop sprayer comprised of a spinner and a pump both controlled by pwm class AC_Sprayer { diff --git a/libraries/AC_Sprayer/AC_Sprayer_config.h b/libraries/AC_Sprayer/AC_Sprayer_config.h new file mode 100644 index 00000000000000..4bb39f35fdf5f6 --- /dev/null +++ b/libraries/AC_Sprayer/AC_Sprayer_config.h @@ -0,0 +1,7 @@ +#pragma once + +#include + +#ifndef HAL_SPRAYER_ENABLED +#define HAL_SPRAYER_ENABLED 1 +#endif From 271f08fc03c41f937ef4e01f272cb8db14381663 Mon Sep 17 00:00:00 2001 From: BLash Date: Wed, 3 Jul 2024 13:07:10 +1000 Subject: [PATCH 13/16] AP_ExternalAHRS: VectorNav: Add support for sensors outside VN-100 and VN-300 Includes naming changes to match new broadened usage --- .../AP_ExternalAHRS_VectorNav.cpp | 146 +++++++++--------- .../AP_ExternalAHRS_VectorNav.h | 16 +- 2 files changed, 86 insertions(+), 76 deletions(-) diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp index af207f54c6a5ba..f43ac8598d6e5f 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp @@ -39,7 +39,7 @@ extern const AP_HAL::HAL &hal; /* - header for pre-configured 50Hz data + header for 50Hz INS data assumes the following config for VN-300: $VNWRG,75,3,8,34,072E,0106,0612*0C @@ -66,10 +66,10 @@ extern const AP_HAL::HAL &hal; VelU */ -static const uint8_t vn_pkt1_header[] { 0x34, 0x2E, 0x07, 0x06, 0x01, 0x12, 0x06 }; -#define VN_PKT1_LENGTH 170 // includes header and CRC +static const uint8_t vn_ins_pkt1_header[] { 0x34, 0x2E, 0x07, 0x06, 0x01, 0x12, 0x06 }; +#define VN_INS_PKT1_LENGTH 170 // includes header and CRC -struct PACKED VN_packet1 { +struct PACKED VN_INS_packet1 { float uncompMag[3]; float uncompAccel[3]; float uncompAngRate[3]; @@ -87,10 +87,10 @@ struct PACKED VN_packet1 { }; // check packet size for 4 groups -static_assert(sizeof(VN_packet1)+2+3*2+2 == VN_PKT1_LENGTH, "incorrect VN_packet1 length"); +static_assert(sizeof(VN_INS_packet1)+2+3*2+2 == VN_INS_PKT1_LENGTH, "incorrect VN_INS_packet1 length"); /* - header for pre-configured 5Hz data + header for 5Hz GNSS data assumes the following VN-300 config: $VNWRG,76,3,80,4E,0002,0010,20B8,0018*63 @@ -113,10 +113,10 @@ static_assert(sizeof(VN_packet1)+2+3*2+2 == VN_PKT1_LENGTH, "incorrect VN_packet NumSats Fix */ -static const uint8_t vn_pkt2_header[] { 0x4e, 0x02, 0x00, 0x10, 0x00, 0xb8, 0x20, 0x18, 0x00 }; -#define VN_PKT2_LENGTH 92 // includes header and CRC +static const uint8_t vn_ins_pkt2_header[] { 0x4e, 0x02, 0x00, 0x10, 0x00, 0xb8, 0x20, 0x18, 0x00 }; +#define VN_INS_PKT2_LENGTH 92 // includes header and CRC -struct PACKED VN_packet2 { +struct PACKED VN_INS_packet2 { uint64_t timeGPS; float temp; uint8_t numGPS1Sats; @@ -129,10 +129,11 @@ struct PACKED VN_packet2 { }; // check packet size for 4 groups -static_assert(sizeof(VN_packet2)+2+4*2+2 == VN_PKT2_LENGTH, "incorrect VN_packet2 length"); +static_assert(sizeof(VN_INS_packet2)+2+4*2+2 == VN_INS_PKT2_LENGTH, "incorrect VN_INS_packet2 length"); /* - assumes the following VN-300 config: +header for 50Hz IMU data, used in TYPE::VN_AHRS only + assumes the following VN-100 config: $VNWRG,75,3,80,14,073E,0004*66 Alternate first packet for VN-100 @@ -151,10 +152,10 @@ static_assert(sizeof(VN_packet2)+2+4*2+2 == VN_PKT2_LENGTH, "incorrect VN_packet 0x0004: Quaternion */ -static const uint8_t vn_100_pkt1_header[] { 0x14, 0x3E, 0x07, 0x04, 0x00 }; -#define VN_100_PKT1_LENGTH 104 // includes header and CRC +static const uint8_t vn_ahrs_pkt1_header[] { 0x14, 0x3E, 0x07, 0x04, 0x00 }; +#define VN_AHRS_PKT1_LENGTH 104 // includes header and CRC -struct PACKED VN_100_packet1 { +struct PACKED VN_AHRS_packet1 { float uncompMag[3]; float uncompAccel[3]; float uncompAngRate[3]; @@ -166,7 +167,7 @@ struct PACKED VN_100_packet1 { float quaternion[4]; }; -static_assert(sizeof(VN_100_packet1)+2+2*2+2 == VN_100_PKT1_LENGTH, "incorrect VN_100_packet1 length"); +static_assert(sizeof(VN_AHRS_packet1)+2+2*2+2 == VN_AHRS_PKT1_LENGTH, "incorrect VN_AHRS_packet1 length"); // constructor AP_ExternalAHRS_VectorNav::AP_ExternalAHRS_VectorNav(AP_ExternalAHRS *_frontend, @@ -182,12 +183,12 @@ AP_ExternalAHRS_VectorNav::AP_ExternalAHRS_VectorNav(AP_ExternalAHRS *_frontend, baudrate = sm.find_baudrate(AP_SerialManager::SerialProtocol_AHRS, 0); port_num = sm.find_portnum(AP_SerialManager::SerialProtocol_AHRS, 0); - bufsize = MAX(MAX(VN_PKT1_LENGTH, VN_PKT2_LENGTH), VN_100_PKT1_LENGTH); + bufsize = MAX(MAX(VN_INS_PKT1_LENGTH, VN_INS_PKT2_LENGTH), VN_AHRS_PKT1_LENGTH); pktbuf = NEW_NOTHROW uint8_t[bufsize]; - last_pkt1 = NEW_NOTHROW VN_packet1; - last_pkt2 = NEW_NOTHROW VN_packet2; + last_ins_pkt1 = NEW_NOTHROW VN_INS_packet1; + last_ins_pkt2 = NEW_NOTHROW VN_INS_packet2; - if (!pktbuf || !last_pkt1 || !last_pkt2) { + if (!pktbuf || !last_ins_pkt1 || !last_ins_pkt2) { AP_BoardConfig::allocation_error("VectorNav ExternalAHRS"); } @@ -230,43 +231,43 @@ bool AP_ExternalAHRS_VectorNav::check_uart() goto reset; } - if (type == TYPE::VN_300) { - match_header1 = (0 == memcmp(&pktbuf[1], vn_pkt1_header, MIN(sizeof(vn_pkt1_header), unsigned(pktoffset-1)))); - match_header2 = (0 == memcmp(&pktbuf[1], vn_pkt2_header, MIN(sizeof(vn_pkt2_header), unsigned(pktoffset-1)))); + if (type == TYPE::VN_INS) { + match_header1 = (0 == memcmp(&pktbuf[1], vn_ins_pkt1_header, MIN(sizeof(vn_ins_pkt1_header), unsigned(pktoffset-1)))); + match_header2 = (0 == memcmp(&pktbuf[1], vn_ins_pkt2_header, MIN(sizeof(vn_ins_pkt2_header), unsigned(pktoffset-1)))); } else { - match_header3 = (0 == memcmp(&pktbuf[1], vn_100_pkt1_header, MIN(sizeof(vn_100_pkt1_header), unsigned(pktoffset-1)))); + match_header3 = (0 == memcmp(&pktbuf[1], vn_ahrs_pkt1_header, MIN(sizeof(vn_ahrs_pkt1_header), unsigned(pktoffset-1)))); } if (!match_header1 && !match_header2 && !match_header3) { goto reset; } - if (match_header1 && pktoffset >= VN_PKT1_LENGTH) { - uint16_t crc = crc16_ccitt(&pktbuf[1], VN_PKT1_LENGTH-1, 0); + if (match_header1 && pktoffset >= VN_INS_PKT1_LENGTH) { + uint16_t crc = crc16_ccitt(&pktbuf[1], VN_INS_PKT1_LENGTH-1, 0); if (crc == 0) { // got pkt1 - process_packet1(&pktbuf[sizeof(vn_pkt1_header)+1]); - memmove(&pktbuf[0], &pktbuf[VN_PKT1_LENGTH], pktoffset-VN_PKT1_LENGTH); - pktoffset -= VN_PKT1_LENGTH; + process_ins_packet1(&pktbuf[sizeof(vn_ins_pkt1_header)+1]); + memmove(&pktbuf[0], &pktbuf[VN_INS_PKT1_LENGTH], pktoffset-VN_INS_PKT1_LENGTH); + pktoffset -= VN_INS_PKT1_LENGTH; } else { goto reset; } - } else if (match_header2 && pktoffset >= VN_PKT2_LENGTH) { - uint16_t crc = crc16_ccitt(&pktbuf[1], VN_PKT2_LENGTH-1, 0); + } else if (match_header2 && pktoffset >= VN_INS_PKT2_LENGTH) { + uint16_t crc = crc16_ccitt(&pktbuf[1], VN_INS_PKT2_LENGTH-1, 0); if (crc == 0) { // got pkt2 - process_packet2(&pktbuf[sizeof(vn_pkt2_header)+1]); - memmove(&pktbuf[0], &pktbuf[VN_PKT2_LENGTH], pktoffset-VN_PKT2_LENGTH); - pktoffset -= VN_PKT2_LENGTH; + process_ins_packet2(&pktbuf[sizeof(vn_ins_pkt2_header)+1]); + memmove(&pktbuf[0], &pktbuf[VN_INS_PKT2_LENGTH], pktoffset-VN_INS_PKT2_LENGTH); + pktoffset -= VN_INS_PKT2_LENGTH; } else { goto reset; } - } else if (match_header3 && pktoffset >= VN_100_PKT1_LENGTH) { - uint16_t crc = crc16_ccitt(&pktbuf[1], VN_100_PKT1_LENGTH-1, 0); + } else if (match_header3 && pktoffset >= VN_AHRS_PKT1_LENGTH) { + uint16_t crc = crc16_ccitt(&pktbuf[1], VN_AHRS_PKT1_LENGTH-1, 0); if (crc == 0) { - // got VN-100 pkt1 - process_packet_VN_100(&pktbuf[sizeof(vn_100_pkt1_header)+1]); - memmove(&pktbuf[0], &pktbuf[VN_100_PKT1_LENGTH], pktoffset-VN_100_PKT1_LENGTH); - pktoffset -= VN_100_PKT1_LENGTH; + // got AHRS pkt + process_ahrs_packet(&pktbuf[sizeof(vn_ahrs_pkt1_header)+1]); + memmove(&pktbuf[0], &pktbuf[VN_AHRS_PKT1_LENGTH], pktoffset-VN_AHRS_PKT1_LENGTH); + pktoffset -= VN_AHRS_PKT1_LENGTH; } else { goto reset; } @@ -414,18 +415,25 @@ void AP_ExternalAHRS_VectorNav::update_thread() wait_register_responce(1); // Setup for messages respective model types (on both UARTs) - if (strncmp(model_name, "VN-100", 6) == 0) { + if (strncmp(model_name, "VN-1", 4) == 0) { // VN-100 - type = TYPE::VN_100; + type = TYPE::VN_AHRS; // This assumes unit is still configured at its default rate of 800hz nmea_printf(uart, "$VNWRG,75,3,%u,14,073E,0004", unsigned(800/get_rate())); } else { - // Default to Setup for VN-300 series - // This assumes unit is still configured at its default rate of 400hz - nmea_printf(uart, "$VNWRG,75,3,%u,34,072E,0106,0612", unsigned(400/get_rate())); - nmea_printf(uart, "$VNWRG,76,3,80,4E,0002,0010,20B8,0018"); + // Default to setup for sensors other than VN-100 or VN-110 + // This assumes unit is still configured at its default IMU rate of 400hz for VN-300, 800hz for others + uint16_t imu_rate = 800; // Default for everything but VN-300 + if (strncmp(model_name, "VN-300", 6) == 0) { + imu_rate = 400; + } + if (strncmp(model_name, "VN-3", 4) == 0) { + has_dual_gnss = true; + } + nmea_printf(uart, "$VNWRG,75,3,%u,34,072E,0106,0612", unsigned(imu_rate/get_rate())); + nmea_printf(uart, "$VNWRG,76,3,%u,4E,0002,0010,20B8,0018", unsigned(imu_rate/5)); } setup_complete = true; @@ -445,15 +453,15 @@ const char* AP_ExternalAHRS_VectorNav::get_name() const } /* - process packet type 1 + process INS mode INS packet */ -void AP_ExternalAHRS_VectorNav::process_packet1(const uint8_t *b) +void AP_ExternalAHRS_VectorNav::process_ins_packet1(const uint8_t *b) { - const struct VN_packet1 &pkt1 = *(struct VN_packet1 *)b; - const struct VN_packet2 &pkt2 = *last_pkt2; + const struct VN_INS_packet1 &pkt1 = *(struct VN_INS_packet1 *)b; + const struct VN_INS_packet2 &pkt2 = *last_ins_pkt2; last_pkt1_ms = AP_HAL::millis(); - *last_pkt1 = pkt1; + *last_ins_pkt1 = pkt1; const bool use_uncomp = option_is_set(AP_ExternalAHRS::OPTIONS::VN_UNCOMP_IMU); @@ -514,15 +522,15 @@ void AP_ExternalAHRS_VectorNav::process_packet1(const uint8_t *b) } /* - process packet type 2 + process INS mode GNSS packet */ -void AP_ExternalAHRS_VectorNav::process_packet2(const uint8_t *b) +void AP_ExternalAHRS_VectorNav::process_ins_packet2(const uint8_t *b) { - const struct VN_packet2 &pkt2 = *(struct VN_packet2 *)b; - const struct VN_packet1 &pkt1 = *last_pkt1; + const struct VN_INS_packet2 &pkt2 = *(struct VN_INS_packet2 *)b; + const struct VN_INS_packet1 &pkt1 = *last_ins_pkt1; last_pkt2_ms = AP_HAL::millis(); - *last_pkt2 = pkt2; + *last_ins_pkt2 = pkt2; AP_ExternalAHRS::gps_data_message_t gps; @@ -562,11 +570,11 @@ void AP_ExternalAHRS_VectorNav::process_packet2(const uint8_t *b) } /* - process VN-100 packet type 1 + process AHRS mode AHRS packet */ -void AP_ExternalAHRS_VectorNav::process_packet_VN_100(const uint8_t *b) +void AP_ExternalAHRS_VectorNav::process_ahrs_packet(const uint8_t *b) { - const struct VN_100_packet1 &pkt = *(struct VN_100_packet1 *)b; + const struct VN_AHRS_packet1 &pkt = *(struct VN_AHRS_packet1 *)b; last_pkt1_ms = AP_HAL::millis(); @@ -669,7 +677,7 @@ int8_t AP_ExternalAHRS_VectorNav::get_port(void) const bool AP_ExternalAHRS_VectorNav::healthy(void) const { const uint32_t now = AP_HAL::millis(); - if (type == TYPE::VN_100) { + if (type == TYPE::VN_AHRS) { return (now - last_pkt1_ms < 40); } return (now - last_pkt1_ms < 40 && now - last_pkt2_ms < 500); @@ -680,7 +688,7 @@ bool AP_ExternalAHRS_VectorNav::initialised(void) const if (!setup_complete) { return false; } - if (type == TYPE::VN_100) { + if (type == TYPE::VN_AHRS) { return last_pkt1_ms != 0; } return last_pkt1_ms != 0 && last_pkt2_ms != 0; @@ -696,12 +704,12 @@ bool AP_ExternalAHRS_VectorNav::pre_arm_check(char *failure_msg, uint8_t failure hal.util->snprintf(failure_msg, failure_msg_len, "VectorNav unhealthy"); return false; } - if (type == TYPE::VN_300) { - if (last_pkt2->GPS1Fix < 3) { + if (type == TYPE::VN_INS) { + if (last_ins_pkt2->GPS1Fix < 3) { hal.util->snprintf(failure_msg, failure_msg_len, "VectorNav no GPS1 lock"); return false; } - if (last_pkt2->GPS2Fix < 3) { + if (has_dual_gnss && (last_ins_pkt2->GPS2Fix < 3)) { hal.util->snprintf(failure_msg, failure_msg_len, "VectorNav no GPS2 lock"); return false; } @@ -716,16 +724,16 @@ bool AP_ExternalAHRS_VectorNav::pre_arm_check(char *failure_msg, uint8_t failure void AP_ExternalAHRS_VectorNav::get_filter_status(nav_filter_status &status) const { memset(&status, 0, sizeof(status)); - if (type == TYPE::VN_300) { - if (last_pkt1 && last_pkt2) { + if (type == TYPE::VN_INS) { + if (last_ins_pkt1 && last_ins_pkt2) { status.flags.initalized = true; } - if (healthy() && last_pkt2) { + if (healthy() && last_ins_pkt2) { status.flags.attitude = true; status.flags.vert_vel = true; status.flags.vert_pos = true; - const struct VN_packet2 &pkt2 = *last_pkt2; + const struct VN_INS_packet2 &pkt2 = *last_ins_pkt2; if (pkt2.GPS1Fix >= 3) { status.flags.horiz_vel = true; status.flags.horiz_pos_rel = true; @@ -746,7 +754,7 @@ void AP_ExternalAHRS_VectorNav::get_filter_status(nav_filter_status &status) con // send an EKF_STATUS message to GCS void AP_ExternalAHRS_VectorNav::send_status_report(GCS_MAVLINK &link) const { - if (!last_pkt1) { + if (!last_ins_pkt1) { return; } // prepare flags @@ -788,7 +796,7 @@ void AP_ExternalAHRS_VectorNav::send_status_report(GCS_MAVLINK &link) const } // send message - const struct VN_packet1 &pkt1 = *(struct VN_packet1 *)last_pkt1; + const struct VN_INS_packet1 &pkt1 = *(struct VN_INS_packet1 *)last_ins_pkt1; const float vel_gate = 5; const float pos_gate = 5; const float hgt_gate = 5; diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h index c0e54c88bf2a45..05c4a01fae6829 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h @@ -61,26 +61,28 @@ class AP_ExternalAHRS_VectorNav : public AP_ExternalAHRS_backend { void update_thread(); bool check_uart(); - void process_packet1(const uint8_t *b); - void process_packet2(const uint8_t *b); - void process_packet_VN_100(const uint8_t *b); + void process_ins_packet1(const uint8_t *b); + void process_ins_packet2(const uint8_t *b); + void process_ahrs_packet(const uint8_t *b); void wait_register_responce(const uint8_t register_num); uint8_t *pktbuf; uint16_t pktoffset; uint16_t bufsize; - struct VN_packet1 *last_pkt1; - struct VN_packet2 *last_pkt2; + struct VN_INS_packet1 *last_ins_pkt1; + struct VN_INS_packet2 *last_ins_pkt2; uint32_t last_pkt1_ms; uint32_t last_pkt2_ms; enum class TYPE { - VN_300, - VN_100, + VN_INS, // Full INS mode, requiring GNSS. Used by VN-2X0 and VN-3X0 + VN_AHRS, // IMU-only mode, used by VN-1X0 } type; + bool has_dual_gnss = false; + char model_name[25]; // NMEA parsing for setup From 0e4124060c9ef8757ec8c72366edbbc6544745f4 Mon Sep 17 00:00:00 2001 From: BLash Date: Wed, 3 Jul 2024 13:07:11 +1000 Subject: [PATCH 14/16] SITL: VectorNav: Add support for sensors outside VN-100 and VN-300 Includes naming changes to match new broadened usage --- libraries/SITL/SIM_VectorNav.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/SITL/SIM_VectorNav.cpp b/libraries/SITL/SIM_VectorNav.cpp index 27c19be7f0f4fa..2c7d54953c02a9 100644 --- a/libraries/SITL/SIM_VectorNav.cpp +++ b/libraries/SITL/SIM_VectorNav.cpp @@ -29,7 +29,7 @@ VectorNav::VectorNav() : { } -struct PACKED VN_packet1 { +struct PACKED VN_INS_packet1 { float uncompMag[3]; float uncompAccel[3]; float uncompAngRate[3]; @@ -46,7 +46,7 @@ struct PACKED VN_packet1 { float velU; }; -struct PACKED VN_packet2 { +struct PACKED VN_INS_packet2 { uint64_t timeGPS; float temp; uint8_t numGPS1Sats; @@ -84,7 +84,7 @@ void VectorNav::send_packet1(void) { const auto &fdm = _sitl->state; - struct VN_packet1 pkt {}; + struct VN_INS_packet1 pkt {}; pkt.uncompAccel[0] = fdm.xAccel; pkt.uncompAccel[1] = fdm.yAccel; @@ -146,7 +146,7 @@ void VectorNav::send_packet2(void) { const auto &fdm = _sitl->state; - struct VN_packet2 pkt {}; + struct VN_INS_packet2 pkt {}; struct timeval tv; simulation_timeval(&tv); From c1c3580f8b4c978d7a3857bf484c9b1662c17101 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 4 Jul 2024 12:05:26 +1000 Subject: [PATCH 15/16] AP_Logger: remove unused _log_file_size_bytes variable AP_Logger: comment corection --- libraries/AP_Logger/AP_Logger_Backend.cpp | 2 -- libraries/AP_Logger/AP_Logger_Backend.h | 1 - libraries/AP_Logger/AP_Logger_Block.cpp | 2 +- 3 files changed, 1 insertion(+), 4 deletions(-) diff --git a/libraries/AP_Logger/AP_Logger_Backend.cpp b/libraries/AP_Logger/AP_Logger_Backend.cpp index 3274e1a2e0cf4d..6fab3cb587ea02 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.cpp +++ b/libraries/AP_Logger/AP_Logger_Backend.cpp @@ -100,7 +100,6 @@ void AP_Logger_Backend::start_new_log_reset_variables() _dropped = 0; _startup_messagewriter->reset(); _front.backend_starting_new_log(this); - _log_file_size_bytes = 0; _formats_written.clearall(); } @@ -709,7 +708,6 @@ void AP_Logger_Backend::df_stats_gather(const uint16_t bytes_written, uint32_t s } stats.buf_space_sigma += space_remaining; stats.bytes += bytes_written; - _log_file_size_bytes += bytes_written; stats.blocks++; } diff --git a/libraries/AP_Logger/AP_Logger_Backend.h b/libraries/AP_Logger/AP_Logger_Backend.h index e9f99e8aaba58f..6549ee0c782ae6 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.h +++ b/libraries/AP_Logger/AP_Logger_Backend.h @@ -208,7 +208,6 @@ class AP_Logger_Backend uint16_t _cached_oldest_log; uint32_t _dropped; - uint32_t _log_file_size_bytes; // should we rotate when we next stop logging bool _rotate_pending; diff --git a/libraries/AP_Logger/AP_Logger_Block.cpp b/libraries/AP_Logger/AP_Logger_Block.cpp index 482366a58b2263..d9ed2f0d36d65b 100644 --- a/libraries/AP_Logger/AP_Logger_Block.cpp +++ b/libraries/AP_Logger/AP_Logger_Block.cpp @@ -541,7 +541,7 @@ void AP_Logger_Block::stop_logging_async(void) void AP_Logger_Block::start_new_log(void) { if (erase_started) { - // already erasing + // currently erasing return; } From 9090420db072efe991c59f7e93517164e8c2d0fd Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 15 Apr 2024 08:43:58 +1000 Subject: [PATCH 16/16] SITL: remove duplicated crc code same as one we already have --- libraries/SITL/SIM_GPS_NOVA.cpp | 30 +++--------------------------- libraries/SITL/SIM_GPS_NOVA.h | 2 -- 2 files changed, 3 insertions(+), 29 deletions(-) diff --git a/libraries/SITL/SIM_GPS_NOVA.cpp b/libraries/SITL/SIM_GPS_NOVA.cpp index cd4608b7f0b91d..08f793f4d27138 100644 --- a/libraries/SITL/SIM_GPS_NOVA.cpp +++ b/libraries/SITL/SIM_GPS_NOVA.cpp @@ -142,36 +142,12 @@ void GPS_NOVA::publish(const GPS_Data *d) void GPS_NOVA::nova_send_message(uint8_t *header, uint8_t headerlength, uint8_t *payload, uint8_t payloadlen) { write_to_autopilot((char*)header, headerlength); -write_to_autopilot((char*)payload, payloadlen); + write_to_autopilot((char*)payload, payloadlen); - uint32_t crc = CalculateBlockCRC32(headerlength, header, (uint32_t)0); - crc = CalculateBlockCRC32(payloadlen, payload, crc); + uint32_t crc = crc_crc32((uint32_t)0, header, headerlength); + crc = crc_crc32(crc, payload, payloadlen); write_to_autopilot((char*)&crc, 4); } -#define CRC32_POLYNOMIAL 0xEDB88320L -uint32_t GPS_NOVA::CRC32Value(uint32_t icrc) -{ - int i; - uint32_t crc = icrc; - for ( i = 8 ; i > 0; i-- ) - { - if ( crc & 1 ) - crc = ( crc >> 1 ) ^ CRC32_POLYNOMIAL; - else - crc >>= 1; - } - return crc; -} - -uint32_t GPS_NOVA::CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc) -{ - while ( length-- != 0 ) - { - crc = ((crc >> 8) & 0x00FFFFFFL) ^ (CRC32Value(((uint32_t) crc ^ *buffer++) & 0xff)); - } - return( crc ); -} - #endif // AP_SIM_GPS_NOVA_ENABLED diff --git a/libraries/SITL/SIM_GPS_NOVA.h b/libraries/SITL/SIM_GPS_NOVA.h index 4df22b32d8dc9a..0801dd9533adbb 100644 --- a/libraries/SITL/SIM_GPS_NOVA.h +++ b/libraries/SITL/SIM_GPS_NOVA.h @@ -21,8 +21,6 @@ class GPS_NOVA : public GPS_Backend { private: void nova_send_message(uint8_t *header, uint8_t headerlength, uint8_t *payload, uint8_t payloadlen); - uint32_t CRC32Value(uint32_t icrc); - uint32_t CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc); }; };